Skip to main content

maliput/api/
mod.rs

1// BSD 3-Clause License
2//
3// Copyright (c) 2024, Woven by Toyota.
4// All rights reserved.
5//
6// Redistribution and use in source and binary forms, with or without
7// modification, are permitted provided that the following conditions are met:
8//
9// * Redistributions of source code must retain the above copyright notice, this
10//   list of conditions and the following disclaimer.
11//
12// * Redistributions in binary form must reproduce the above copyright notice,
13//   this list of conditions and the following disclaimer in the documentation
14//   and/or other materials provided with the distribution.
15//
16// * Neither the name of the copyright holder nor the names of its
17//   contributors may be used to endorse or promote products derived from
18//   this software without specific prior written permission.
19//
20// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30
31use crate::common::MaliputError;
32use crate::math::Matrix3;
33use crate::math::Quaternion;
34use crate::math::RollPitchYaw;
35use crate::math::Vector3;
36
37pub mod rules;
38
39/// Enumerates the available maliput road network backends.
40///
41/// Each variant corresponds to a plugin that implements the `RoadNetworkLoader` interface.
42/// The string representation matches the plugin ID expected by the C++ `MaliputPluginManager`.
43///
44/// Which variants are available depends on the enabled features:
45/// - `maliput_malidrive` (default): Enables the `MaliputMalidrive` variant.
46/// - `maliput_geopackage` (opt-in): Enables the `MaliputGeopackage` variant.
47///
48/// # Example
49///
50/// ```rust
51/// use maliput::api::RoadNetworkBackend;
52///
53/// let backend = RoadNetworkBackend::MaliputMalidrive;
54/// assert_eq!(backend.to_string(), "maliput_malidrive");
55/// ```
56#[derive(Debug, Clone, Copy, PartialEq, Eq, strum_macros::Display, strum_macros::EnumString)]
57pub enum RoadNetworkBackend {
58    /// The `maliput_malidrive` backend. Loads road networks from OpenDRIVE (`.xodr`) files.
59    #[cfg(feature = "maliput_malidrive")]
60    #[strum(serialize = "maliput_malidrive")]
61    MaliputMalidrive,
62    /// The `maliput_geopackage` backend. Loads road networks from GeoPackage (`.gpkg`) files.
63    #[cfg(feature = "maliput_geopackage")]
64    #[strum(serialize = "maliput_geopackage")]
65    MaliputGeopackage,
66}
67
68/// Represents a complete Maliput road network.
69///
70/// A `RoadNetwork` is the main entry point for interacting with a road map in Maliput.
71/// It serves as a container for all the elements that describe a road network,
72/// including its physical layout and the rules of the road.
73///
74/// It provides access to the following key components:
75///
76/// * [`RoadGeometry`]: The geometric description of the road surfaces.
77/// * [`rules::RoadRulebook`]: The set of traffic rules, like speed limits and right-of-way.
78/// * [`rules::TrafficLightBook`]: A catalog of all traffic lights in the network.
79/// * [`IntersectionBook`]: A collection of logical intersections and their states.
80///   TODO: Complete with other books when available (e.g., `RuleRegistry / PhaseRingBook / etc)
81///
82/// More info can be found at https://maliput.readthedocs.io/en/latest/html/deps/maliput/html/maliput_design.html.
83///
84/// # Example
85///
86/// ```rust, no_run
87/// use maliput::api::{RoadNetwork, RoadNetworkBackend};
88/// use std::collections::HashMap;
89///
90/// // Properties to load an OpenDRIVE file using the maliput_malidrive backend.
91/// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
92/// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
93/// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
94///
95/// // Create the RoadNetwork by specifying the backend and properties.
96/// let road_network = RoadNetwork::new(RoadNetworkBackend::MaliputMalidrive, &road_network_properties).unwrap();
97/// ```
98pub struct RoadNetwork {
99    pub(crate) rn: cxx::UniquePtr<maliput_sys::api::ffi::RoadNetwork>,
100}
101
102impl RoadNetwork {
103    /// Create a new `RoadNetwork` with the given `backend` and `properties`.
104    ///
105    /// # Arguments
106    ///
107    /// * `backend` - The backend to use for loading the road network. See [`RoadNetworkBackend`].
108    /// * `properties` - The properties of the road network.
109    ///
110    /// # Details
111    /// It relies on `maliput_sys::plugin::ffi::CreateRoadNetwork` to create a new `RoadNetwork`.
112    ///
113    /// # Returns
114    /// A result containing the `RoadNetwork` or a `MaliputError` if the creation fails.
115    #[allow(clippy::vec_init_then_push)]
116    pub fn new(
117        backend: RoadNetworkBackend,
118        properties: &std::collections::HashMap<&str, &str>,
119    ) -> Result<RoadNetwork, MaliputError> {
120        // Translate the properties to ffi types
121        let mut properties_vec = Vec::new();
122        for (key, value) in properties.iter() {
123            properties_vec.push(format!("{}:{}", key, value));
124        }
125        // If MALIPUT_PLUGIN_PATH is not set, it will be created.
126        let new_path = match std::env::var_os("MALIPUT_PLUGIN_PATH") {
127            Some(current_path) => {
128                // Add the plugin paths obtained from maliput_sdk to MALIPUT_PLUGIN_PATH.
129                // These are added first in the list as the plugins are loaded sequentially and we
130                // want these to be used only when no others are present. (typically in dev mode).
131                let mut new_paths = vec![];
132                #[cfg(feature = "maliput_malidrive")]
133                new_paths.push(maliput_sdk::get_maliput_malidrive_plugin_path());
134                #[cfg(feature = "maliput_geopackage")]
135                new_paths.push(maliput_sdk::get_maliput_geopackage_plugin_path());
136                new_paths.extend(std::env::split_paths(&current_path).collect::<Vec<_>>());
137                std::env::join_paths(new_paths).unwrap()
138            }
139            None => {
140                let mut paths = vec![];
141                #[cfg(feature = "maliput_malidrive")]
142                paths.push(maliput_sdk::get_maliput_malidrive_plugin_path());
143                #[cfg(feature = "maliput_geopackage")]
144                paths.push(maliput_sdk::get_maliput_geopackage_plugin_path());
145                std::env::join_paths(paths).unwrap()
146            }
147        };
148        std::env::set_var("MALIPUT_PLUGIN_PATH", new_path);
149        let rn = maliput_sys::plugin::ffi::CreateRoadNetwork(&backend.to_string(), &properties_vec)?;
150        Ok(RoadNetwork { rn })
151    }
152
153    /// Get the `RoadGeometry` of the `RoadNetwork`.
154    pub fn road_geometry(&self) -> RoadGeometry<'_> {
155        unsafe {
156            RoadGeometry {
157                rg: self.rn.road_geometry().as_ref().expect(""),
158            }
159        }
160    }
161    /// Get the `IntersectionBook` of the `RoadNetwork`.
162    pub fn intersection_book(&self) -> IntersectionBook<'_> {
163        let intersection_book_ffi = maliput_sys::api::ffi::RoadNetwork_intersection_book(&self.rn);
164        IntersectionBook {
165            intersection_book: unsafe {
166                intersection_book_ffi
167                    .as_ref()
168                    .expect("Underlying IntersectionBook is null")
169            },
170        }
171    }
172    /// Get the `TrafficLightBook` of the `RoadNetwork`.
173    pub fn traffic_light_book(&self) -> rules::TrafficLightBook<'_> {
174        let traffic_light_book_ffi = self.rn.traffic_light_book();
175        rules::TrafficLightBook {
176            traffic_light_book: unsafe {
177                traffic_light_book_ffi
178                    .as_ref()
179                    .expect("Underlying TrafficLightBook is null")
180            },
181        }
182    }
183    /// Get the `RoadRulebook` of the `RoadNetwork`.
184    pub fn rulebook(&self) -> rules::RoadRulebook<'_> {
185        let rulebook_ffi = self.rn.rulebook();
186        rules::RoadRulebook {
187            road_rulebook: unsafe { rulebook_ffi.as_ref().expect("Underlying RoadRulebook is null") },
188        }
189    }
190
191    /// Get the `PhaseRingBook` of the `RoadNetwork`.
192    pub fn phase_ring_book(&self) -> rules::PhaseRingBook<'_> {
193        let phase_ring_book_ffi = self.rn.phase_ring_book();
194        rules::PhaseRingBook {
195            phase_ring_book: unsafe { phase_ring_book_ffi.as_ref().expect("Underlying PhaseRingBook is null") },
196        }
197    }
198
199    /// Get the `RuleRegistry` of the `RoadNetwork`.
200    pub fn rule_registry(&self) -> rules::RuleRegistry<'_> {
201        let rule_registry_ffi = self.rn.rule_registry();
202        rules::RuleRegistry {
203            rule_registry: unsafe { rule_registry_ffi.as_ref().expect("Underlying RuleRegistry is null") },
204        }
205    }
206
207    /// Get the `PhaseProvider` of the `RoadNetwork`.
208    pub fn phase_provider(&self) -> rules::PhaseProvider<'_> {
209        let phase_provider_ffi = maliput_sys::api::ffi::RoadNetwork_phase_provider(&self.rn);
210        rules::PhaseProvider {
211            phase_provider: unsafe { phase_provider_ffi.as_ref().expect("Underlying PhaseProvider is null") },
212        }
213    }
214
215    /// Get the `DiscreteValueRuleStateProvider` of the `RoadNetwork`.
216    pub fn discrete_value_rule_state_provider(&self) -> rules::DiscreteValueRuleStateProvider<'_> {
217        let state_provider = maliput_sys::api::ffi::RoadNetwork_discrete_value_rule_state_provider(&self.rn);
218        rules::DiscreteValueRuleStateProvider {
219            state_provider: unsafe {
220                state_provider
221                    .as_ref()
222                    .expect("Underlying DiscreteValueRuleStateProvider is null")
223            },
224        }
225    }
226
227    /// Get the `RangeValueRuleStateProvider` of the `RoadNetwork`.
228    pub fn range_value_rule_state_provider(&self) -> rules::RangeValueRuleStateProvider<'_> {
229        let state_provider = maliput_sys::api::ffi::RoadNetwork_range_value_rule_state_provider(&self.rn);
230        rules::RangeValueRuleStateProvider {
231            state_provider: unsafe {
232                state_provider
233                    .as_ref()
234                    .expect("Underlying RangeValueRuleStateProvider is null")
235            },
236        }
237    }
238}
239
240/// Represents the geometry of a road network.
241///
242/// `RoadGeometry` is the top-level container for the road network's geometric
243/// description. It is composed of a set of `Junction`s, which in turn contain
244/// `Segment`s and `Lane`s.
245///
246/// It provides access to the entire road network's geometric structure,
247/// allowing for queries about its components (e.g., finding a `Lane` by its ID)
248/// and for coordinate conversions between the inertial frame and the road network's
249/// intrinsic coordinate systems (lane coordinates).
250///
251/// An instance of `RoadGeometry` is typically obtained from a `RoadNetwork`.
252///
253/// More info can be found at https://maliput.readthedocs.io/en/latest/html/deps/maliput/html/maliput_design.html.
254///
255/// # Example of obtaining a `RoadGeometry`
256///
257/// ```rust, no_run
258/// use maliput::api::{RoadNetwork, RoadNetworkBackend};
259/// use std::collections::HashMap;
260///
261/// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
262/// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
263/// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
264/// let road_network = RoadNetwork::new(RoadNetworkBackend::MaliputMalidrive, &road_network_properties).unwrap();
265/// let road_geometry = road_network.road_geometry();
266/// println!("RoadGeometry ID: {}", road_geometry.id());
267/// ```
268pub struct RoadGeometry<'a> {
269    rg: &'a maliput_sys::api::ffi::RoadGeometry,
270}
271
272impl<'a> RoadGeometry<'a> {
273    /// Returns the id of the RoadGeometry.
274    pub fn id(&self) -> String {
275        maliput_sys::api::ffi::RoadGeometry_id(self.rg)
276    }
277    /// Returns the number of Junctions in the RoadGeometry.
278    ///
279    /// Return value is non-negative.
280    pub fn num_junctions(&self) -> i32 {
281        self.rg.num_junctions()
282    }
283    /// Returns the tolerance guaranteed for linear measurements (positions).
284    pub fn linear_tolerance(&self) -> f64 {
285        self.rg.linear_tolerance()
286    }
287    /// Returns the tolerance guaranteed for angular measurements (orientations).
288    pub fn angular_tolerance(&self) -> f64 {
289        self.rg.angular_tolerance()
290    }
291    /// Returns the number of BranchPoints in the RoadGeometry.
292    ///
293    /// Return value is non-negative.
294    pub fn num_branch_points(&self) -> i32 {
295        self.rg.num_branch_points()
296    }
297    /// Determines the [RoadPosition] on the 3D road manifold that corresponds to
298    /// [InertialPosition] `inertial_position`.
299    ///
300    /// The [RoadGeometry]'s manifold is a 3D volume, with each point defined by (s, r, h)
301    /// coordinates. This method returns a [RoadPositionQuery]. Its [RoadPosition] is the
302    /// point in the [RoadGeometry]'s manifold which is, in the `Inertial`-frame, closest to
303    /// `inertial_position`. Its InertialPosition is the `Inertial`-frame equivalent of the
304    /// [RoadPosition] and its distance is the Cartesian distance from
305    /// `inertial_position` to the nearest point.
306    ///
307    /// This method guarantees that its result satisfies the condition that
308    /// `result.lane.to_lane_position(result.pos)` is within `linear_tolerance()`
309    /// of the returned [InertialPosition].
310    ///
311    /// The map from [RoadGeometry] to the `Inertial`-frame is not onto (as a bounded
312    /// [RoadGeometry] cannot completely cover the unbounded Cartesian universe).
313    /// If `inertial_position` does represent a point contained within the volume
314    /// of the RoadGeometry, then result distance is guaranteed to be less
315    /// than or equal to `linear_tolerance()`.
316    ///
317    /// The map from [RoadGeometry] to `Inertial`-frame is not necessarily one-to-one.
318    /// Different `(s,r,h)` coordinates from different Lanes, potentially from
319    /// different Segments, may map to the same `(x,y,z)` `Inertial`-frame location.
320    ///
321    /// If `inertial_position` is contained within the volumes of multiple Segments,
322    /// then to_road_position() will choose a [Segment] which yields the minimum
323    /// height `h` value in the result.  If the chosen [Segment] has multiple
324    /// Lanes, then to_road_position() will choose a [Lane] which contains
325    /// `inertial_position` within its `lane_bounds()` if possible, and if that is
326    /// still ambiguous, it will further select a [Lane] which minimizes the
327    /// absolute value of the lateral `r` coordinate in the result.
328    ///
329    /// # Arguments
330    /// * `inertial_position` - The [InertialPosition] to convert into a [RoadPosition].
331    ///
332    /// # Return
333    /// A [RoadPositionQuery] with the nearest [RoadPosition], the corresponding [InertialPosition]
334    /// to that [RoadPosition] and the distance between the input and output [InertialPosition]s.
335    pub fn to_road_position(&self, inertial_position: &InertialPosition) -> Result<RoadPositionQuery, MaliputError> {
336        let rpr = maliput_sys::api::ffi::RoadGeometry_ToRoadPosition(self.rg, &inertial_position.ip)?;
337        Ok(RoadPositionQuery {
338            road_position: RoadPosition {
339                rp: maliput_sys::api::ffi::RoadPositionResult_road_position(&rpr),
340            },
341            nearest_position: InertialPosition {
342                ip: maliput_sys::api::ffi::RoadPositionResult_nearest_position(&rpr),
343            },
344            distance: maliput_sys::api::ffi::RoadPositionResult_distance(&rpr),
345        })
346    }
347
348    /// Determines the [RoadPosition] on the road surface that corresponds to
349    /// [InertialPosition] `inertial_position`.
350    ///
351    /// This method is similar to [RoadGeometry::to_road_position], in a way that it determines if
352    /// `inertial_position` is within the [RoadGeometry]'s 3D volume. If it is, a [RoadPosition] is
353    /// returned where the height `h` is set to 0, effectively placing the point on the road
354    /// surface.
355    ///
356    /// # Arguments
357    /// * `inertial_position` - The [InertialPosition] to convert into a [RoadPosition].
358    ///
359    /// # Return
360    /// The corresponding [RoadPosition] on the road surface or a [MaliputError] if the `inertial_position` is not on the road surface (i.e., the distance is greater than `linear_tolerance`).
361    ///
362    /// # Example
363    ///
364    /// ```rust, no_run
365    /// use maliput::api::{RoadNetwork, RoadNetworkBackend, InertialPosition};
366    /// use std::collections::HashMap;
367    ///
368    /// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
369    /// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
370    /// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
371    /// let road_network = RoadNetwork::new(RoadNetworkBackend::MaliputMalidrive, &road_network_properties).unwrap();
372    /// let road_geometry = road_network.road_geometry();
373    ///
374    /// // Although this isn't directly on the surface, it is within the RoadGeometry volume.
375    /// let inertial_pos = InertialPosition::new(1.0, 0.0, 1.0);
376    /// let road_pos = road_geometry.to_road_position_surface(&inertial_pos);
377    /// assert!(road_pos.is_ok());
378    /// let road_pos = road_pos.unwrap();
379    /// println!("Road position on surface: s={}, r={}, h={}", road_pos.pos().s(), road_pos.pos().r(), road_pos.pos().h());
380    /// assert_eq!(road_pos.pos().s(), 1.0);
381    /// assert_eq!(road_pos.pos().r(), 0.0);
382    /// assert_eq!(road_pos.pos().h(), 0.0);  // h is set to 0.
383    ///
384    /// // An inertial position that is off the road volume.
385    /// let inertial_pos= InertialPosition::new(1.0, 0.0, 10.0);
386    /// let road_pos= road_geometry.to_road_position_surface(&inertial_pos);
387    /// assert!(road_pos.is_err());
388    /// ```
389    pub fn to_road_position_surface(&self, inertial_position: &InertialPosition) -> Result<RoadPosition, MaliputError> {
390        let rpr = maliput_sys::api::ffi::RoadGeometry_ToRoadPosition(self.rg, &inertial_position.ip)?;
391        let road_position = RoadPosition {
392            rp: maliput_sys::api::ffi::RoadPositionResult_road_position(&rpr),
393        };
394
395        let distance = maliput_sys::api::ffi::RoadPositionResult_distance(&rpr);
396        if distance > self.linear_tolerance() {
397            return Err(MaliputError::Other(format!(
398                "InertialPosition {} does not correspond to a RoadPosition. It is off by {}m to the closest lane {} at {}.",
399                maliput_sys::api::ffi::InertialPosition_to_str(&inertial_position.ip),
400                distance, road_position.lane().id(), road_position.pos())));
401        }
402
403        let lane_position =
404            maliput_sys::api::ffi::LanePosition_new(road_position.pos().s(), road_position.pos().r(), 0.);
405        unsafe {
406            Ok(RoadPosition {
407                rp: maliput_sys::api::ffi::RoadPosition_new(road_position.lane().lane, &lane_position),
408            })
409        }
410    }
411
412    /// Obtains all [RoadPosition]s within a radius of the inertial_position.
413    ///
414    /// Only Lanes whose segment regions include points that are within radius of
415    /// inertial position are included in the search. For each of these Lanes,
416    /// include the [RoadPosition] or [RoadPosition]s with the minimum distance to
417    /// inertial position in the returned result.
418    ///
419    /// # Arguments
420    ///
421    /// * `inertial_position` - The [InertialPosition] to search around.
422    /// * `radius` - The radius around the [InertialPosition] to search for [RoadPosition]s.
423    ///
424    /// # Return
425    ///
426    /// A vector of [RoadPositionQuery]s.
427    pub fn find_road_positions(
428        &self,
429        inertial_position: &InertialPosition,
430        radius: f64,
431    ) -> Result<Vec<RoadPositionQuery>, MaliputError> {
432        let positions = maliput_sys::api::ffi::RoadGeometry_FindRoadPositions(self.rg, &inertial_position.ip, radius)?;
433        Ok(positions
434            .iter()
435            .map(|rpr| RoadPositionQuery {
436                road_position: RoadPosition {
437                    rp: maliput_sys::api::ffi::RoadPositionResult_road_position(rpr),
438                },
439                nearest_position: InertialPosition {
440                    ip: maliput_sys::api::ffi::RoadPositionResult_nearest_position(rpr),
441                },
442                distance: maliput_sys::api::ffi::RoadPositionResult_distance(rpr),
443            })
444            .collect())
445    }
446
447    /// Get the lane matching given `lane_id`.
448    ///
449    /// # Arguments
450    /// * `lane_id` - The id of the lane.
451    ///
452    /// # Return
453    /// The lane with the given id.
454    /// If no lane is found with the given id, return None.
455    pub fn get_lane(&self, lane_id: &String) -> Option<Lane<'_>> {
456        let lane = maliput_sys::api::ffi::RoadGeometry_GetLane(self.rg, lane_id);
457        if lane.lane.is_null() {
458            return None;
459        }
460        Some(Lane {
461            lane: unsafe { lane.lane.as_ref().expect("") },
462        })
463    }
464    /// Get all lanes of the `RoadGeometry`.
465    /// Returns a vector of `Lane`.
466    /// # Example
467    /// ```rust, no_run
468    /// use maliput::api::{RoadNetwork, RoadNetworkBackend};
469    /// use std::collections::HashMap;
470    ///
471    /// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
472    /// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
473    /// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
474    /// let road_network = RoadNetwork::new(RoadNetworkBackend::MaliputMalidrive, &road_network_properties).unwrap();
475    /// let road_geometry = road_network.road_geometry();
476    /// let lanes = road_geometry.get_lanes();
477    /// for lane in lanes {
478    ///    println!("lane_id: {}", lane.id());
479    /// }
480    /// ```
481    pub fn get_lanes(&self) -> Vec<Lane<'_>> {
482        let lanes = maliput_sys::api::ffi::RoadGeometry_GetLanes(self.rg);
483        lanes
484            .into_iter()
485            .map(|l| Lane {
486                lane: unsafe { l.lane.as_ref().expect("") },
487            })
488            .collect::<Vec<Lane>>()
489    }
490    /// Get the segment matching given `segment_id`.
491    ///
492    /// # Arguments
493    /// * `segment_id` - The id of the segment.
494    ///
495    /// # Return
496    /// The segment with the given id.
497    /// If no segment is found with the given id, return None.
498    pub fn get_segment(&self, segment_id: &String) -> Option<Segment<'_>> {
499        let segment = maliput_sys::api::ffi::RoadGeometry_GetSegment(self.rg, segment_id);
500        if segment.is_null() {
501            return None;
502        }
503        unsafe {
504            Some(Segment {
505                segment: segment.as_ref().expect(""),
506            })
507        }
508    }
509
510    /// Returns a Vec with all [Junction]s in the RoadGeometry, which can be iterated.
511    ///
512    /// # Returns
513    /// A Vec with all junction in the road geometry.
514    pub fn get_juntions(&self) -> Result<Vec<Junction<'_>>, MaliputError> {
515        let mut junctions = vec![];
516        for i in 0..self.num_junctions() {
517            if let Some(junction) = self.junction(i) {
518                junctions.push(junction);
519            } else {
520                return Err(MaliputError::Other(format!("No junction found at index {}", i)));
521            };
522        }
523        Ok(junctions)
524    }
525
526    /// Get the junction at the given index.
527    /// The index is in the range [0, num_junctions).
528    ///
529    /// # Arguments
530    /// * `index` - The index of the junction.
531    ///
532    /// # Return
533    /// The junction at the given index.
534    /// If no junction is found at the given index, return None.
535    pub fn junction(&self, index: i32) -> Option<Junction<'_>> {
536        let junction = self.rg.junction(index).ok()?;
537        if junction.is_null() {
538            return None;
539        }
540        unsafe {
541            Some(Junction {
542                junction: junction.as_ref().expect(""),
543            })
544        }
545    }
546
547    /// Get the junction matching given `junction_id`.
548    ///
549    /// # Arguments
550    /// * `junction_id` - The id of the junction.
551    ///
552    /// # Return
553    /// The junction with the given id.
554    /// If no junction is found with the given id, return None.
555    pub fn get_junction(&self, junction_id: &String) -> Option<Junction<'_>> {
556        let junction = maliput_sys::api::ffi::RoadGeometry_GetJunction(self.rg, junction_id);
557        if junction.is_null() {
558            return None;
559        }
560        unsafe {
561            Some(Junction {
562                junction: junction.as_ref().expect(""),
563            })
564        }
565    }
566    /// Get the branch point matching given `branch_point_id`.
567    ///
568    /// # Arguments
569    /// * `branch_point_id` - The id of the branch point.
570    ///
571    /// # Return
572    /// The branch point with the given id.
573    /// If no branch point is found with the given id, return None.
574    pub fn get_branch_point(&self, branch_point_id: &String) -> Option<BranchPoint<'_>> {
575        let branch_point = maliput_sys::api::ffi::RoadGeometry_GetBranchPoint(self.rg, branch_point_id);
576        if branch_point.is_null() {
577            return None;
578        }
579        unsafe {
580            Some(BranchPoint {
581                branch_point: branch_point.as_ref().expect(""),
582            })
583        }
584    }
585    /// Execute a custom command on the backend.
586    ///
587    /// # Details
588    /// The documentation of the custom command should be provided by the backend: https://github.com/maliput/maliput_malidrive/blob/main/src/maliput_malidrive/base/road_geometry.h
589    ///
590    /// # Arguments
591    /// * `command` - The command to execute.
592    ///
593    /// # Return
594    /// The result of the command.
595    // pub fn backend_custom_command(&self, command: &String) -> String {
596    pub fn backend_custom_command(&self, command: &String) -> Result<String, MaliputError> {
597        Ok(maliput_sys::api::ffi::RoadGeometry_BackendCustomCommand(
598            self.rg, command,
599        )?)
600    }
601    /// Obtains the Geo Reference info of this RoadGeometry.
602    ///
603    /// # Return
604    /// A string containing the Geo Reference projection, if any.
605    pub fn geo_reference_info(&self) -> String {
606        maliput_sys::api::ffi::RoadGeometry_GeoReferenceInfo(self.rg)
607    }
608
609    /// Get the boundary matching given `boundary_id`.
610    ///
611    /// # Arguments
612    /// * `boundary_id` - The ID of the boundary.
613    ///
614    /// # Return
615    /// The lane boundary with the given ID.
616    /// If no lane boundary is found with the given ID, return None.
617    pub fn get_boundary(&self, boundary_id: &String) -> Option<LaneBoundary<'_>> {
618        let boundary = maliput_sys::api::ffi::RoadGeometry_GetLaneBoundary(self.rg, boundary_id);
619        if boundary.is_null() {
620            return None;
621        }
622        Some(LaneBoundary {
623            lane_boundary: unsafe { boundary.as_ref().expect("") },
624        })
625    }
626}
627
628/// A 3-dimensional position in a `Lane`-frame, consisting of three components:
629///
630/// * s is longitudinal position, as arc-length along a Lane's reference line.
631/// * r is lateral position, perpendicular to the reference line at s. +r is to
632///   to the left when traveling in the direction of +s.
633/// * h is height above the road surface.
634///
635/// # Example
636///
637/// ```rust, no_run
638/// use maliput::api::LanePosition;
639///
640/// let lane_pos = LanePosition::new(1.0, 2.0, 3.0);
641/// println!("lane_pos = {}", lane_pos);
642/// assert_eq!(lane_pos.s(), 1.0);
643/// assert_eq!(lane_pos.r(), 2.0);
644/// assert_eq!(lane_pos.h(), 3.0);
645/// ```
646pub struct LanePosition {
647    lp: cxx::UniquePtr<maliput_sys::api::ffi::LanePosition>,
648}
649
650impl LanePosition {
651    /// Create a new `LanePosition` with the given `s`, `r`, and `h` components.
652    pub fn new(s: f64, r: f64, h: f64) -> LanePosition {
653        LanePosition {
654            lp: maliput_sys::api::ffi::LanePosition_new(s, r, h),
655        }
656    }
657    /// Get the `s` component of the `LanePosition`.
658    pub fn s(&self) -> f64 {
659        self.lp.s()
660    }
661    /// Get the `r` component of the `LanePosition`.
662    pub fn r(&self) -> f64 {
663        self.lp.r()
664    }
665    /// Get the `h` component of the `LanePosition`.
666    pub fn h(&self) -> f64 {
667        self.lp.h()
668    }
669
670    /// Returns all components as 3-vector `[s, r, h]`.
671    pub fn srh(&self) -> Vector3 {
672        let srh = self.lp.srh();
673        Vector3::new(srh.x(), srh.y(), srh.z())
674    }
675
676    /// Set the `s` component of the `LanePosition`.
677    pub fn set_s(&mut self, s: f64) {
678        self.lp.as_mut().expect("Underlying LanePosition is null").set_s(s);
679    }
680
681    /// Set the `r` component of the `LanePosition`.
682    pub fn set_r(&mut self, r: f64) {
683        self.lp.as_mut().expect("Underlying LanePosition is null").set_r(r);
684    }
685
686    /// Set the `h` component of the `LanePosition`.
687    pub fn set_h(&mut self, h: f64) {
688        self.lp.as_mut().expect("Underlying LanePosition is null").set_h(h);
689    }
690
691    /// Set all components from 3-vector `[s, r, h]`.
692    pub fn set_srh(&mut self, srh: &Vector3) {
693        let ffi_vec = maliput_sys::math::ffi::Vector3_new(srh.x(), srh.y(), srh.z());
694        self.lp
695            .as_mut()
696            .expect("Underlying LanePosition is null")
697            .set_srh(&ffi_vec);
698    }
699}
700
701impl PartialEq for LanePosition {
702    fn eq(&self, other: &Self) -> bool {
703        self.srh() == other.srh()
704    }
705}
706
707impl Eq for LanePosition {}
708
709impl std::fmt::Display for LanePosition {
710    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
711        write!(f, "{}", maliput_sys::api::ffi::LanePosition_to_str(&self.lp))
712    }
713}
714
715impl std::fmt::Debug for LanePosition {
716    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
717        f.debug_struct("LanePosition")
718            .field("s", &self.s())
719            .field("r", &self.r())
720            .field("h", &self.h())
721            .finish()
722    }
723}
724
725/// A position in 3-dimensional geographical Cartesian space, i.e., in the
726/// `Inertial`-frame, consisting of three components x, y, and z.
727///
728/// # Example
729///
730/// ```rust, no_run
731/// use maliput::api::InertialPosition;
732///
733/// let inertial_pos = InertialPosition::new(1.0, 2.0, 3.0);
734/// println!("inertial_pos = {}", inertial_pos);
735/// assert_eq!(inertial_pos.x(), 1.0);
736/// assert_eq!(inertial_pos.y(), 2.0);
737/// assert_eq!(inertial_pos.z(), 3.0);
738/// ```
739pub struct InertialPosition {
740    ip: cxx::UniquePtr<maliput_sys::api::ffi::InertialPosition>,
741}
742
743impl InertialPosition {
744    /// Create a new `InertialPosition` with the given `x`, `y`, and `z` components.
745    pub fn new(x: f64, y: f64, z: f64) -> InertialPosition {
746        InertialPosition {
747            ip: maliput_sys::api::ffi::InertialPosition_new(x, y, z),
748        }
749    }
750    /// Get the `x` component of the `InertialPosition`.
751    pub fn x(&self) -> f64 {
752        self.ip.x()
753    }
754    /// Get the `y` component of the `InertialPosition`.
755    pub fn y(&self) -> f64 {
756        self.ip.y()
757    }
758    /// Get the `z` component of the `InertialPosition`.
759    pub fn z(&self) -> f64 {
760        self.ip.z()
761    }
762
763    /// Returns all components as 3-vector `[x, y, z]`.
764    pub fn xyz(&self) -> Vector3 {
765        let xyz = self.ip.xyz();
766        Vector3::new(xyz.x(), xyz.y(), xyz.z())
767    }
768
769    /// Set the `x` component of the `InertialPosition`.
770    pub fn set_x(&mut self, x: f64) {
771        self.ip.as_mut().expect("Underlying InertialPosition is null").set_x(x);
772    }
773
774    /// Set the `y` component of the `InertialPosition`.
775    pub fn set_y(&mut self, y: f64) {
776        self.ip.as_mut().expect("Underlying InertialPosition is null").set_y(y);
777    }
778
779    /// Set the `z` component of the `InertialPosition`.
780    pub fn set_z(&mut self, z: f64) {
781        self.ip.as_mut().expect("Underlying InertialPosition is null").set_z(z);
782    }
783
784    /// Set all components from 3-vector `[x, y, z]`.
785    pub fn set_xyz(&mut self, xyz: &Vector3) {
786        let ffi_vec = maliput_sys::math::ffi::Vector3_new(xyz.x(), xyz.y(), xyz.z());
787        self.ip
788            .as_mut()
789            .expect("Underlying InertialPosition is null")
790            .set_xyz(&ffi_vec);
791    }
792
793    /// Get the length of `InertialPosition`.
794    pub fn length(&self) -> f64 {
795        self.ip.length()
796    }
797
798    /// Get the distance between two `InertialPosition`.
799    pub fn distance(&self, other: &InertialPosition) -> f64 {
800        self.ip.Distance(&other.ip)
801    }
802}
803
804impl PartialEq for InertialPosition {
805    fn eq(&self, other: &Self) -> bool {
806        maliput_sys::api::ffi::InertialPosition_operator_eq(&self.ip, &other.ip)
807    }
808}
809
810impl Eq for InertialPosition {}
811
812impl std::fmt::Display for InertialPosition {
813    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
814        write!(f, "{}", maliput_sys::api::ffi::InertialPosition_to_str(&self.ip))
815    }
816}
817
818impl std::fmt::Debug for InertialPosition {
819    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
820        f.debug_struct("InertialPosition")
821            .field("x", &self.x())
822            .field("y", &self.y())
823            .field("z", &self.z())
824            .finish()
825    }
826}
827
828impl std::ops::Add for InertialPosition {
829    type Output = InertialPosition;
830
831    fn add(self, other: InertialPosition) -> InertialPosition {
832        InertialPosition {
833            ip: maliput_sys::api::ffi::InertialPosition_operator_sum(&self.ip, &other.ip),
834        }
835    }
836}
837
838impl std::ops::Sub for InertialPosition {
839    type Output = InertialPosition;
840
841    fn sub(self, other: InertialPosition) -> InertialPosition {
842        InertialPosition {
843            ip: maliput_sys::api::ffi::InertialPosition_operator_sub(&self.ip, &other.ip),
844        }
845    }
846}
847
848impl std::ops::Mul<f64> for InertialPosition {
849    type Output = InertialPosition;
850
851    fn mul(self, scalar: f64) -> InertialPosition {
852        InertialPosition {
853            ip: maliput_sys::api::ffi::InertialPosition_operator_mul_scalar(&self.ip, scalar),
854        }
855    }
856}
857
858impl Clone for InertialPosition {
859    fn clone(&self) -> Self {
860        InertialPosition {
861            ip: maliput_sys::api::ffi::InertialPosition_new(self.x(), self.y(), self.z()),
862        }
863    }
864}
865
866/// Bounds in the lateral dimension (r component) of a `Lane`-frame, consisting
867/// of a pair of minimum and maximum r value.  The bounds must straddle r = 0,
868/// i.e., the minimum must be <= 0 and the maximum must be >= 0.
869pub struct RBounds {
870    min: f64,
871    max: f64,
872}
873
874impl RBounds {
875    /// Create a new `RBounds` with the given `min` and `max` values.
876    pub fn new(min: f64, max: f64) -> RBounds {
877        RBounds { min, max }
878    }
879    /// Get the `min` value of the `RBounds`.
880    pub fn min(&self) -> f64 {
881        self.min
882    }
883    /// Get the `max` value of the `RBounds`.
884    pub fn max(&self) -> f64 {
885        self.max
886    }
887    /// Set the `min` value of the `RBounds`.
888    pub fn set_min(&mut self, min: f64) {
889        self.min = min;
890    }
891    /// Set the `max` value of the `RBounds`.
892    pub fn set_max(&mut self, max: f64) {
893        self.max = max;
894    }
895}
896
897/// Bounds in the elevation dimension (`h` component) of a `Lane`-frame,
898/// consisting of a pair of minimum and maximum `h` value.  The bounds
899/// must straddle `h = 0`, i.e., the minimum must be `<= 0` and the
900/// maximum must be `>= 0`.
901pub struct HBounds {
902    min: f64,
903    max: f64,
904}
905
906impl HBounds {
907    /// Create a new `HBounds` with the given `min` and `max` values.
908    pub fn new(min: f64, max: f64) -> HBounds {
909        HBounds { min, max }
910    }
911    /// Get the `min` value of the `HBounds`.
912    pub fn min(&self) -> f64 {
913        self.min
914    }
915    /// Get the `max` value of the `HBounds`.
916    pub fn max(&self) -> f64 {
917        self.max
918    }
919    /// Set the `min` value of the `HBounds`.
920    pub fn set_min(&mut self, min: f64) {
921        self.min = min;
922    }
923    /// Set the `max` value of the `HBounds`.
924    pub fn set_max(&mut self, max: f64) {
925        self.max = max;
926    }
927}
928
929/// Isometric velocity vector in a `Lane`-frame.
930///
931/// sigma_v, rho_v, and eta_v are the components of velocity in a
932/// (sigma, rho, eta) coordinate system.  (sigma, rho, eta) have the same
933/// orientation as the (s, r, h) at any given point in space, however they
934/// form an isometric system with a Cartesian distance metric.  Hence,
935/// IsoLaneVelocity represents a "real" physical velocity vector (albeit
936/// with an orientation relative to the road surface).
937#[derive(Default, Copy, Clone, Debug, PartialEq)]
938pub struct IsoLaneVelocity {
939    pub sigma_v: f64,
940    pub rho_v: f64,
941    pub eta_v: f64,
942}
943
944impl IsoLaneVelocity {
945    /// Create a new `IsoLaneVelocity` with the given `sigma_v`, `rho_v`, and `eta_v` components.
946    pub fn new(sigma_v: f64, rho_v: f64, eta_v: f64) -> IsoLaneVelocity {
947        IsoLaneVelocity { sigma_v, rho_v, eta_v }
948    }
949}
950
951/// Lane classification options.
952///
953/// LaneType defines the intended use of a lane.
954#[derive(strum_macros::Display, Debug, Copy, Clone, PartialEq, Eq)]
955pub enum LaneType {
956    /// Default state.
957    Unknown,
958    /// Standard driving lane.
959    Driving,
960    /// Turn available.
961    Turn,
962    /// High Occupancy Vehicle lane (+2 passengers).
963    Hov,
964    /// Bus only.
965    Bus,
966    /// Taxi only.
967    Taxi,
968    /// Emergency vehicles only (fire, ambulance, police).
969    Emergency,
970    /// Soft border at the edge of the road.
971    Shoulder,
972    /// Reserved for cyclists.
973    Biking,
974    /// Sidewalks / Crosswalks.
975    Walking,
976    /// Lane with parking spaces.
977    Parking,
978    /// Hard shoulder / Emergency stop.
979    Stop,
980    /// Hard border at the edge of the road.
981    Border,
982    /// Curb stones.
983    Curb,
984    /// Sits between driving lanes that lead in opposite directions.
985    Median,
986    /// Generic restricted (use if HOV/Bus/Emergency don't fit).
987    Restricted,
988    /// Road works.
989    Construction,
990    /// Trains/Trams.
991    Rail,
992    /// Merge into main road.
993    Entry,
994    /// Exit from the main road.
995    Exit,
996    /// Ramp leading to a motorway.
997    OnRamp,
998    /// Ramp leading away from a motorway.
999    OffRamp,
1000    // Ramp that connects two motorways.
1001    ConnectingRamp,
1002    /// Change roads without driving into the main intersection.
1003    SlipLane,
1004    /// Intersection crossings with no physical markings.
1005    Virtual,
1006}
1007
1008/// A Lane represents a lane of travel in a road network.  A Lane defines
1009/// a curvilinear coordinate system covering the road surface, with a
1010/// longitudinal 's' coordinate that expresses the arc-length along a
1011/// central reference curve.  The reference curve nominally represents
1012/// an ideal travel trajectory along the Lane.
1013///
1014/// Lanes are grouped by Segment.  All Lanes belonging to a Segment
1015/// represent the same road surface, but with different coordinate
1016/// parameterizations (e.g., each Lane has its own reference curve).
1017pub struct Lane<'a> {
1018    lane: &'a maliput_sys::api::ffi::Lane,
1019}
1020
1021impl<'a> Lane<'a> {
1022    /// Returns the id of the Lane.
1023    ///
1024    /// The id is a unique identifier for the Lane within the RoadGeometry.
1025    ///
1026    /// # Returns
1027    /// A `String` containing the id of the Lane.
1028    pub fn id(&self) -> String {
1029        maliput_sys::api::ffi::Lane_id(self.lane)
1030    }
1031    /// Returns the index of this Lane within the Segment which owns it.
1032    pub fn index(&self) -> i32 {
1033        self.lane.index()
1034    }
1035    /// Returns the Segment to which this Lane belongs.
1036    ///
1037    /// # Returns
1038    /// A [`Segment`] containing the Segment to which this Lane belongs.
1039    pub fn segment(&self) -> Segment<'a> {
1040        unsafe {
1041            Segment {
1042                segment: self.lane.segment().as_ref().expect(""),
1043            }
1044        }
1045    }
1046    /// Returns the adjacent lane to the left, if one exists.
1047    ///
1048    /// "Left" is defined as the direction of `+r` in the `(s, r, h)` lane-coordinate frame.
1049    ///
1050    /// # Returns
1051    ///
1052    /// An [`Option<Lane>`] containing the left lane, or `None` if this is the
1053    /// leftmost lane.
1054    pub fn to_left(&self) -> Option<Lane<'_>> {
1055        let lane = self.lane.to_left();
1056        if lane.is_null() {
1057            None
1058        } else {
1059            unsafe {
1060                Some(Lane {
1061                    lane: lane.as_ref().expect(""),
1062                })
1063            }
1064        }
1065    }
1066    /// Returns the adjacent lane to the right, if one exists.
1067    ///
1068    /// "Right" is defined as the direction of `-r` in the `(s, r, h)` lane-coordinate
1069    /// frame.
1070    ///
1071    /// # Returns
1072    ///
1073    /// An [`Option<Lane>`] containing the right lane, or `None` if this is the
1074    /// rightmost lane.
1075    pub fn to_right(&self) -> Option<Lane<'_>> {
1076        let lane = self.lane.to_right();
1077        if lane.is_null() {
1078            None
1079        } else {
1080            unsafe {
1081                Some(Lane {
1082                    lane: lane.as_ref().expect(""),
1083                })
1084            }
1085        }
1086    }
1087    /// Returns the arc-length of the Lane along its reference curve.
1088    ///
1089    /// The value of length() is also the maximum s-coordinate for this Lane;
1090    /// i.e., the domain of s is [0, length()].
1091    ///
1092    /// # Returns
1093    ///
1094    /// The length of the Lane in meters.
1095    pub fn length(&self) -> f64 {
1096        self.lane.length()
1097    }
1098
1099    /// Get the orientation of the `Lane` at the given `LanePosition`.
1100    pub fn get_orientation(&self, lane_position: &LanePosition) -> Result<Rotation, MaliputError> {
1101        Ok(Rotation {
1102            r: maliput_sys::api::ffi::Lane_GetOrientation(self.lane, lane_position.lp.as_ref().expect(""))?,
1103        })
1104    }
1105
1106    /// Returns the signed Euclidean curvature at the given [LanePosition].
1107    ///
1108    /// The Euclidean curvature magnitude is defined as the reciprocal of the radius
1109    /// of the osculating circle at a given point on the curve: $|\kappa| = 1/R$.
1110    ///
1111    /// The sign convention follows the right-hand rule with respect to the lane's
1112    /// `h`-axis (vertical/normal direction):
1113    /// - **Positive curvature**: The path curves to the left (toward +r direction),
1114    ///   i.e., counter-clockwise when viewed from above.
1115    /// - **Negative curvature**: The path curves to the right (toward -r direction),
1116    ///   i.e., clockwise when viewed from above.
1117    ///
1118    /// # Arguments
1119    /// * `lane_position` - A [LanePosition]. The `s` component must be in domain
1120    ///   `[0, Lane::length()]`. The `r` and `h` components are used to determine
1121    ///   the curvature at the corresponding offset from the centerline.
1122    ///
1123    /// # Returns
1124    /// The signed Euclidean curvature (1/m) at the given position.
1125    pub fn get_curvature(&self, lane_position: &LanePosition) -> Result<f64, MaliputError> {
1126        Ok(self.lane.GetCurvature(lane_position.lp.as_ref().expect(""))?)
1127    }
1128
1129    /// # Brief
1130    /// Get the [InertialPosition] of the [Lane] at the given [LanePosition].
1131    ///
1132    /// # Notes
1133    /// Note there is no constraint for the `r` coordinate, as it can be outside the lane boundaries.
1134    /// In that scenario, the resultant inertial position represents a point in the `s-r` plane at the given `s` and `h`
1135    /// coordinates. It's on the user side to verify, if needed, that the lane position is within lane boundaries.
1136    /// Bare in mind that the inertial position will be a point in the `s-r` plane, but *not* necessarily on the road surface.
1137    ///
1138    /// # Arguments
1139    /// * `lane_position` - A maliput [LanePosition].
1140    ///
1141    /// # Precondition
1142    /// The s component of `lane_position` must be in domain [0, Lane::length()].
1143    ///
1144    /// # Return
1145    /// The [InertialPosition] corresponding to the input [LanePosition].
1146    pub fn to_inertial_position(&self, lane_position: &LanePosition) -> Result<InertialPosition, MaliputError> {
1147        Ok(InertialPosition {
1148            ip: maliput_sys::api::ffi::Lane_ToInertialPosition(self.lane, lane_position.lp.as_ref().expect(""))?,
1149        })
1150    }
1151    /// Determines the LanePosition corresponding to InertialPosition `inertial_position`.
1152    /// The LanePosition is expected to be contained within the lane's 3D boundaries (s, r, h).
1153    /// See [Lane::to_segment_position] method.
1154    ///
1155    /// This method guarantees that its result satisfies the condition that
1156    /// `to_inertial_position(result.lane_position)` is within `linear_tolerance()`
1157    ///  of `result.nearest_position`.
1158    ///
1159    /// # Arguments
1160    /// * `inertial_position` - A [InertialPosition] to get a [LanePosition] from.
1161    ///
1162    /// # Return
1163    /// A [LanePositionQuery] with the closest [LanePosition], the corresponding [InertialPosition] to that [LanePosition]
1164    /// and the distance between the input and output [InertialPosition]s.
1165    pub fn to_lane_position(&self, inertial_position: &InertialPosition) -> Result<LanePositionQuery, MaliputError> {
1166        let lpr = maliput_sys::api::ffi::Lane_ToLanePosition(self.lane, inertial_position.ip.as_ref().expect(""))?;
1167        Ok(LanePositionQuery {
1168            lane_position: LanePosition {
1169                lp: maliput_sys::api::ffi::LanePositionResult_road_position(&lpr),
1170            },
1171            nearest_position: InertialPosition {
1172                ip: maliput_sys::api::ffi::LanePositionResult_nearest_position(&lpr),
1173            },
1174            distance: maliput_sys::api::ffi::LanePositionResult_distance(&lpr),
1175        })
1176    }
1177    /// Determines the [LanePosition] corresponding to [InertialPosition] `inertial_position`.
1178    /// The [LanePosition] is expected to be contained within the segment's 3D boundaries (s, r, h).
1179    /// See [Lane::to_lane_position] method.
1180    ///
1181    /// This method guarantees that its result satisfies the condition that
1182    /// `to_inertial_position(result.lane_position)` is within `linear_tolerance()`
1183    ///  of `result.nearest_position`.
1184    ///
1185    /// # Arguments
1186    /// * `inertial_position` - A [InertialPosition] to get a SegmentPosition from.
1187    ///
1188    /// # Return
1189    /// A [LanePositionQuery] with the closest [LanePosition] within the segment, the corresponding
1190    /// [InertialPosition] to that [LanePosition] and the distance between the input and output
1191    /// [InertialPosition]s.
1192    pub fn to_segment_position(&self, inertial_position: &InertialPosition) -> Result<LanePositionQuery, MaliputError> {
1193        let spr = maliput_sys::api::ffi::Lane_ToSegmentPosition(self.lane, inertial_position.ip.as_ref().expect(""))?;
1194        Ok(LanePositionQuery {
1195            lane_position: LanePosition {
1196                lp: maliput_sys::api::ffi::LanePositionResult_road_position(&spr),
1197            },
1198            nearest_position: InertialPosition {
1199                ip: maliput_sys::api::ffi::LanePositionResult_nearest_position(&spr),
1200            },
1201            distance: maliput_sys::api::ffi::LanePositionResult_distance(&spr),
1202        })
1203    }
1204    /// Returns the nominal lateral (r) bounds for the lane as a function of s.
1205    ///
1206    /// These are the lateral bounds for a position that is considered to be
1207    /// "staying in the lane".
1208    ///
1209    /// See also [Lane::segment_bounds] that defines the whole surface.
1210    ///
1211    /// # Arguments
1212    /// * `s` - The longitudinal position along the lane's reference line.
1213    ///
1214    /// # Returns
1215    /// A [RBounds] containing the lateral bounds of the lane at the given `s.
1216    ///
1217    /// # Errors
1218    /// If lane bounds cannot be computed, an error is returned. This can happen if the
1219    /// `s` value is out of bounds (i.e., not in the range [0, Lane::length()]).
1220    pub fn lane_bounds(&self, s: f64) -> Result<RBounds, MaliputError> {
1221        let bounds = maliput_sys::api::ffi::Lane_lane_bounds(self.lane, s)?;
1222        Ok(RBounds::new(bounds.min(), bounds.max()))
1223    }
1224    /// Returns the lateral segment (r) bounds of the lane as a function of s.
1225    ///
1226    /// These are the lateral bounds for a position that is considered to be
1227    /// "on segment", reflecting the physical extent of the surface of the
1228    /// lane's segment.
1229    ///
1230    /// See also [Lane::lane_bounds] that defines what's considered to be "staying
1231    /// in the lane".
1232    ///
1233    /// # Arguments
1234    /// * `s` - The longitudinal position along the lane's reference line.
1235    ///
1236    /// # Returns
1237    /// A [RBounds] containing the lateral segment bounds of the lane at the given `
1238    /// s`.
1239    ///
1240    /// # Errors
1241    /// If segment bounds cannot be computed, an error is returned. This can happen if the
1242    /// `s` value is out of bounds (i.e., not in the range [0, Lane::length()]).
1243    pub fn segment_bounds(&self, s: f64) -> Result<RBounds, MaliputError> {
1244        let bounds = maliput_sys::api::ffi::Lane_segment_bounds(self.lane, s)?;
1245        Ok(RBounds::new(bounds.min(), bounds.max()))
1246    }
1247    /// Returns the elevation (`h`) bounds of the lane as a function of `(s, r)`.
1248    ///
1249    /// These are the elevation bounds for a position that is considered to be
1250    /// within the Lane's volume modeled by the RoadGeometry.
1251    ///
1252    /// `s` is within [0, `length()`] of this Lane and `r` is within
1253    /// `lane_bounds(s)`.
1254    ///
1255    /// # Arguments
1256    /// * `s` - The longitudinal position along the lane's reference line.
1257    /// * `r` - The lateral position perpendicular to the reference line at `s`.
1258    ///
1259    /// # Returns
1260    /// A [HBounds] containing the elevation bounds of the lane at the given `(s, r)`.
1261    ///
1262    /// # Errors
1263    /// If elevation bounds cannot be computed, an error is returned. This can happen if the
1264    /// `s` value is out of bounds (i.e., not in the range [0, Lane::length()]) or if `r` is not within the
1265    /// lane bounds at `s`.
1266    pub fn elevation_bounds(&self, s: f64, r: f64) -> Result<HBounds, MaliputError> {
1267        let bounds = maliput_sys::api::ffi::Lane_elevation_bounds(self.lane, s, r)?;
1268        Ok(HBounds::new(bounds.min(), bounds.max()))
1269    }
1270    /// Computes derivatives of [LanePosition] given a velocity vector `velocity`.
1271    /// `velocity` is a isometric velocity vector oriented in the `Lane`-frame
1272    /// at `position`.
1273    ///
1274    /// # Arguments
1275    /// * `lane_position` - A [LanePosition] at which to evaluate the derivatives.
1276    /// * `velocity` - An [IsoLaneVelocity] representing the velocity vector in the `Lane`-frame
1277    ///   at `lane_position`.
1278    ///
1279    /// # Returns
1280    /// Returns `Lane`-frame derivatives packed into a [LanePosition] struct.
1281    pub fn eval_motion_derivatives(&self, lane_position: &LanePosition, velocity: &IsoLaneVelocity) -> LanePosition {
1282        LanePosition {
1283            lp: maliput_sys::api::ffi::Lane_EvalMotionDerivatives(
1284                self.lane,
1285                lane_position.lp.as_ref().expect(""),
1286                velocity.sigma_v,
1287                velocity.rho_v,
1288                velocity.eta_v,
1289            ),
1290        }
1291    }
1292    /// Returns the lane's [BranchPoint] for the specified end.
1293    ///
1294    /// # Argument
1295    /// * `end` - This lane's start or end [LaneEnd].
1296    ///
1297    /// # Return
1298    /// The lane's [BranchPoint] for the specified end.
1299    pub fn get_branch_point(&self, end: &LaneEnd) -> Result<BranchPoint<'_>, MaliputError> {
1300        if end != &LaneEnd::Start(self.clone()) && end != &LaneEnd::Finish(self.clone()) {
1301            return Err(MaliputError::AssertionError(format!(
1302                "LaneEnd must be an end of this lane {:?}",
1303                end
1304            )));
1305        }
1306        Ok(BranchPoint {
1307            branch_point: unsafe {
1308                maliput_sys::api::ffi::Lane_GetBranchPoint(self.lane, end == &LaneEnd::Start(self.clone()))
1309                    .as_ref()
1310                    .expect("Underlying BranchPoint is null")
1311            },
1312        })
1313    }
1314    /// Returns the set of [LaneEnd]'s which connect with this lane on the
1315    /// same side of the [BranchPoint] at `end`. At a minimum,
1316    /// this set will include this [Lane].
1317    ///
1318    /// # Arguments
1319    /// * `end` - This lane's start or end [LaneEnd].
1320    ///
1321    /// # Return
1322    /// A [LaneEndSet] with all the [LaneEnd]s at the same side of the [BranchPoint] at `end`.
1323    pub fn get_confluent_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
1324        if end != &LaneEnd::Start(self.clone()) && end != &LaneEnd::Finish(self.clone()) {
1325            return Err(MaliputError::AssertionError(format!(
1326                "LaneEnd must be an end of this lane {:?}",
1327                end
1328            )));
1329        }
1330        Ok(LaneEndSet {
1331            lane_end_set: unsafe {
1332                maliput_sys::api::ffi::Lane_GetConfluentBranches(self.lane, end == &LaneEnd::Start(self.clone()))?
1333                    .as_ref()
1334                    .expect("Underlying LaneEndSet is null")
1335            },
1336        })
1337    }
1338    /// Returns the set of [LaneEnd]s which continue onward from this lane at the
1339    /// [BranchPoint] at `end`.
1340    ///
1341    /// # Arguments
1342    /// * `end` - This lane's start or end [LaneEnd].
1343    ///
1344    /// # Return
1345    /// A [LaneEndSet] with all the [LaneEnd]s at the opposite side of the [BranchPoint] at `end`.
1346    pub fn get_ongoing_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
1347        if end != &LaneEnd::Start(self.clone()) && end != &LaneEnd::Finish(self.clone()) {
1348            return Err(MaliputError::AssertionError(format!(
1349                "LaneEnd must be an end of this lane {:?}",
1350                end
1351            )));
1352        }
1353        Ok(LaneEndSet {
1354            lane_end_set: unsafe {
1355                maliput_sys::api::ffi::Lane_GetOngoingBranches(self.lane, end == &LaneEnd::Start(self.clone()))?
1356                    .as_ref()
1357                    .expect("Underlying LaneEndSet is null")
1358            },
1359        })
1360    }
1361    /// Returns the default ongoing LaneEnd connected at `end`,
1362    /// or None if no default branch has been established.
1363    ///
1364    /// # Arguments
1365    /// * `end` - This lane's start or end [LaneEnd].
1366    ///
1367    /// # Return
1368    /// An `Option<LaneEnd>` containing the default branch if it exists, or None
1369    /// if no default branch has been established.
1370    pub fn get_default_branch(&self, end: &LaneEnd) -> Option<LaneEnd<'_>> {
1371        assert! {
1372            end == &LaneEnd::Start(self.clone()) || end == &LaneEnd::Finish(self.clone()),
1373            "LaneEnd must be an end of this lane {:?}",
1374           end
1375        }
1376        let lane_end = maliput_sys::api::ffi::Lane_GetDefaultBranch(self.lane, end == &LaneEnd::Start(self.clone()));
1377        match lane_end.is_null() {
1378            true => None,
1379            false => {
1380                let lane_end_ref: &maliput_sys::api::ffi::LaneEnd =
1381                    lane_end.as_ref().expect("Underlying LaneEnd is null");
1382                let is_start = maliput_sys::api::ffi::LaneEnd_is_start(lane_end_ref);
1383                let lane_ref = unsafe {
1384                    maliput_sys::api::ffi::LaneEnd_lane(lane_end_ref)
1385                        .as_ref()
1386                        .expect("Underlying LaneEnd is null")
1387                };
1388                match is_start {
1389                    true => Some(LaneEnd::Start(Lane { lane: lane_ref })),
1390                    false => Some(LaneEnd::Finish(Lane { lane: lane_ref })),
1391                }
1392            }
1393        }
1394    }
1395    /// Evaluates if the `Lane` contains the given `LanePosition`.
1396    ///
1397    /// # Arguments
1398    /// * `lane_position` - A [LanePosition] to check if it is contained within the `Lane`.
1399    ///
1400    /// # Returns
1401    /// A boolean indicating whether the `Lane` contains the `LanePosition`.
1402    pub fn contains(&self, lane_position: &LanePosition) -> bool {
1403        self.lane.Contains(lane_position.lp.as_ref().expect(""))
1404    }
1405    /// Returns the [LaneType] of the [Lane].
1406    ///
1407    /// # Returns
1408    /// The [LaneType] of the [Lane].
1409    pub fn lane_type(&self) -> LaneType {
1410        let lane_type = maliput_sys::api::ffi::Lane_type(self.lane);
1411        match lane_type {
1412            maliput_sys::api::ffi::LaneType::kDriving => LaneType::Driving,
1413            maliput_sys::api::ffi::LaneType::kTurn => LaneType::Turn,
1414            maliput_sys::api::ffi::LaneType::kHov => LaneType::Hov,
1415            maliput_sys::api::ffi::LaneType::kBus => LaneType::Bus,
1416            maliput_sys::api::ffi::LaneType::kTaxi => LaneType::Taxi,
1417            maliput_sys::api::ffi::LaneType::kEmergency => LaneType::Emergency,
1418            maliput_sys::api::ffi::LaneType::kShoulder => LaneType::Shoulder,
1419            maliput_sys::api::ffi::LaneType::kBiking => LaneType::Biking,
1420            maliput_sys::api::ffi::LaneType::kWalking => LaneType::Walking,
1421            maliput_sys::api::ffi::LaneType::kParking => LaneType::Parking,
1422            maliput_sys::api::ffi::LaneType::kStop => LaneType::Stop,
1423            maliput_sys::api::ffi::LaneType::kBorder => LaneType::Border,
1424            maliput_sys::api::ffi::LaneType::kCurb => LaneType::Curb,
1425            maliput_sys::api::ffi::LaneType::kMedian => LaneType::Median,
1426            maliput_sys::api::ffi::LaneType::kRestricted => LaneType::Restricted,
1427            maliput_sys::api::ffi::LaneType::kConstruction => LaneType::Construction,
1428            maliput_sys::api::ffi::LaneType::kRail => LaneType::Rail,
1429            maliput_sys::api::ffi::LaneType::kEntry => LaneType::Entry,
1430            maliput_sys::api::ffi::LaneType::kExit => LaneType::Exit,
1431            maliput_sys::api::ffi::LaneType::kOnRamp => LaneType::OnRamp,
1432            maliput_sys::api::ffi::LaneType::kOffRamp => LaneType::OffRamp,
1433            maliput_sys::api::ffi::LaneType::kConnectingRamp => LaneType::ConnectingRamp,
1434            maliput_sys::api::ffi::LaneType::kSlipLane => LaneType::SlipLane,
1435            maliput_sys::api::ffi::LaneType::kVirtual => LaneType::Virtual,
1436            _ => LaneType::Unknown,
1437        }
1438    }
1439
1440    /// Returns the boundary at the left of the lane.
1441    pub fn left_boundary(&self) -> Result<LaneBoundary<'_>, MaliputError> {
1442        let lane_boundary = self.lane.left_boundary()?;
1443        if lane_boundary.is_null() {
1444            return Err(MaliputError::AssertionError(
1445                "Lane does not have a left boundary".to_string(),
1446            ));
1447        }
1448
1449        Ok(LaneBoundary {
1450            lane_boundary: unsafe { lane_boundary.as_ref().expect("") },
1451        })
1452    }
1453
1454    /// Returns the boundary at the right of the lane.
1455    pub fn right_boundary(&self) -> Result<LaneBoundary<'_>, MaliputError> {
1456        let lane_boundary = self.lane.right_boundary()?;
1457        if lane_boundary.is_null() {
1458            return Err(MaliputError::AssertionError(
1459                "Lane does not have a right boundary".to_string(),
1460            ));
1461        }
1462
1463        Ok(LaneBoundary {
1464            lane_boundary: unsafe { lane_boundary.as_ref().expect("") },
1465        })
1466    }
1467}
1468
1469/// Copy trait for Lane.
1470/// A reference to the Lane is copied.
1471impl Clone for Lane<'_> {
1472    fn clone(&self) -> Self {
1473        Lane { lane: self.lane }
1474    }
1475}
1476
1477/// A Segment represents a bundle of adjacent Lanes which share a
1478/// continuously traversable road surface. Every [LanePosition] on a
1479/// given [Lane] of a Segment has a corresponding [LanePosition] on each
1480/// other [Lane], all with the same height-above-surface h, that all
1481/// map to the same GeoPoint in 3-space.
1482///
1483/// Segments are grouped by [Junction].
1484pub struct Segment<'a> {
1485    segment: &'a maliput_sys::api::ffi::Segment,
1486}
1487
1488impl<'a> Segment<'a> {
1489    /// Returns the id of the Segment.
1490    /// The id is a unique identifier for the Segment within the RoadGeometry.
1491    ///
1492    /// # Returns
1493    /// A `String` containing the id of the Segment.
1494    pub fn id(&self) -> String {
1495        maliput_sys::api::ffi::Segment_id(self.segment)
1496    }
1497    /// Returns the [Junction] to which this Segment belongs.
1498    ///
1499    /// # Returns
1500    /// An [`Result<Junction, MaliputError>`] containing the Junction to which this Segment belongs.
1501    /// If the Segment does not belong to a Junction, an error is returned.
1502    pub fn junction(&self) -> Result<Junction<'_>, MaliputError> {
1503        let junction = self.segment.junction()?;
1504        if junction.is_null() {
1505            return Err(MaliputError::AssertionError(
1506                "Segment does not belong to a Junction".to_string(),
1507            ));
1508        }
1509        unsafe {
1510            Ok(Junction {
1511                junction: junction.as_ref().expect(""),
1512            })
1513        }
1514    }
1515    /// Returns the number of lanes in the Segment.
1516    ///
1517    /// # Returns
1518    /// The number of lanes in the Segment.
1519    pub fn num_lanes(&self) -> i32 {
1520        self.segment.num_lanes()
1521    }
1522    /// Returns the lane at the given `index`.
1523    ///
1524    /// # Arguments
1525    /// * `index` - The index of the lane to retrieve.
1526    ///
1527    /// # Returns
1528    /// A [`Lane`] containing the lane at the given index.
1529    pub fn lane(&self, index: i32) -> Result<Lane<'_>, MaliputError> {
1530        if index < 0 || index >= self.num_lanes() {
1531            return Err(MaliputError::AssertionError(format!(
1532                "Index {} is out of bounds for Segment with {} lanes",
1533                index,
1534                self.num_lanes()
1535            )));
1536        }
1537        let lane = self.segment.lane(index)?;
1538        unsafe {
1539            Ok(Lane {
1540                lane: lane.as_ref().expect(""),
1541            })
1542        }
1543    }
1544
1545    /// Returns the amount of boundaries in the segment.
1546    pub fn num_boundaries(&self) -> i32 {
1547        self.segment.num_boundaries()
1548    }
1549
1550    /// Returns a Vec with all [LaneBoundary]s in the segment, which can be iterated.
1551    ///
1552    /// # Returns
1553    /// A Vec with all lane boundaries in the segment.
1554    pub fn boundaries(&self) -> Result<Vec<LaneBoundary<'_>>, MaliputError> {
1555        let mut boundaries = vec![];
1556        for i in 0..self.num_boundaries() {
1557            let boundary = self.boundary(i)?;
1558            boundaries.push(boundary);
1559        }
1560        Ok(boundaries)
1561    }
1562
1563    /// Returns the [LaneBoundary] that matches the index.
1564    ///
1565    /// # Arguments
1566    /// * `index` - The index of the boundary. See [LaneBoundary] for more info about indexes.
1567    ///
1568    /// # Returns
1569    /// The [LaneBoundary] at the given index.
1570    pub fn boundary(&self, index: i32) -> Result<LaneBoundary<'_>, MaliputError> {
1571        let lane_boundary = self.segment.boundary(index)?;
1572        if lane_boundary.is_null() {
1573            return Err(MaliputError::AssertionError(
1574                "Segment does not have a boundary".to_string(),
1575            ));
1576        }
1577        Ok(LaneBoundary {
1578            lane_boundary: unsafe { lane_boundary.as_ref().expect("") },
1579        })
1580    }
1581}
1582
1583/// A Junction is a closed set of [Segment]s which have physically
1584/// coplanar road surfaces, in the sense that [RoadPosition]s with the
1585/// same h value (height above surface) in the domains of two [Segment]s
1586/// map to the same [InertialPosition].  The [Segment]s need not be directly
1587/// connected to one another in the network topology.
1588///
1589/// Junctions are grouped by [RoadGeometry].
1590pub struct Junction<'a> {
1591    junction: &'a maliput_sys::api::ffi::Junction,
1592}
1593
1594impl<'a> Junction<'a> {
1595    /// Returns the id of the Junction.
1596    /// The id is a unique identifier for the Junction within the RoadGeometry.
1597    ///
1598    /// # Returns
1599    /// A `String` containing the id of the Junction.
1600    pub fn id(&self) -> String {
1601        maliput_sys::api::ffi::Junction_id(self.junction)
1602    }
1603    /// Returns the [RoadGeometry] to which this Junction belongs.
1604    ///
1605    /// # Returns
1606    /// A [`RoadGeometry`] containing the RoadGeometry to which this Junction belongs.
1607    pub fn road_geometry(&self) -> RoadGeometry<'_> {
1608        unsafe {
1609            RoadGeometry {
1610                rg: self.junction.road_geometry().as_ref().expect(""),
1611            }
1612        }
1613    }
1614    /// Returns the number of segments in the Junction.
1615    ///
1616    /// # Returns
1617    /// The number of segments in the Junction.
1618    pub fn num_segments(&self) -> i32 {
1619        self.junction.num_segments()
1620    }
1621    /// Returns the segment at the given `index`.
1622    ///
1623    /// # Arguments
1624    /// * `index` - The index of the segment to retrieve.
1625    ///
1626    /// # Returns
1627    /// A [Result<Segment, MaliputError>] containing the segment at the given index.
1628    /// If the index is out of bounds, an error is returned.
1629    pub fn segment(&self, index: i32) -> Result<Segment<'_>, MaliputError> {
1630        unsafe {
1631            Ok(Segment {
1632                segment: self.junction.segment(index)?.as_ref().expect(""),
1633            })
1634        }
1635    }
1636
1637    /// Returns a Vec with all [Segment]s in the Junction, which can be iterated.
1638    ///
1639    /// # Returns
1640    /// A Vec with all segments in the junction.
1641    pub fn get_segments(&self) -> Result<Vec<Segment<'_>>, MaliputError> {
1642        let mut segments = vec![];
1643        for i in 0..self.num_segments() {
1644            let segment = self.segment(i)?;
1645            segments.push(segment);
1646        }
1647        Ok(segments)
1648    }
1649}
1650
1651/// A position in the road network compound by a specific lane and a lane-frame position in that lane.
1652/// This position is defined by a [Lane] and a [LanePosition].
1653pub struct RoadPosition {
1654    rp: cxx::UniquePtr<maliput_sys::api::ffi::RoadPosition>,
1655}
1656
1657impl RoadPosition {
1658    /// Create a new `RoadPosition` with the given `lane` and `lane_pos`.
1659    ///
1660    /// # Arguments
1661    /// * `lane` - A reference to a [Lane] that this `RoadPosition` is associated with.
1662    /// * `lane_pos` - A reference to a [LanePosition] that defines the position within the lane.
1663    ///
1664    /// # Returns
1665    /// A new `RoadPosition` instance.
1666    pub fn new(lane: &Lane, lane_pos: &LanePosition) -> RoadPosition {
1667        unsafe {
1668            RoadPosition {
1669                rp: maliput_sys::api::ffi::RoadPosition_new(lane.lane, &lane_pos.lp),
1670            }
1671        }
1672    }
1673    /// Computes the [InertialPosition] corresponding to this `RoadPosition`.
1674    ///
1675    /// # Notes
1676    /// This is an indirection to [Lane::to_inertial_position] method.
1677    ///
1678    /// # Returns
1679    /// An [InertialPosition] corresponding to this `RoadPosition`.
1680    pub fn to_inertial_position(&self) -> Result<InertialPosition, MaliputError> {
1681        Ok(InertialPosition {
1682            ip: maliput_sys::api::ffi::RoadPosition_ToInertialPosition(&self.rp)?,
1683        })
1684    }
1685    /// Gets the [Lane] associated with this `RoadPosition`.
1686    ///
1687    /// # Returns
1688    /// A [Lane] that this `RoadPosition` is associated with.
1689    pub fn lane(&self) -> Lane<'_> {
1690        unsafe {
1691            Lane {
1692                lane: maliput_sys::api::ffi::RoadPosition_lane(&self.rp).as_ref().expect(""),
1693            }
1694        }
1695    }
1696    /// Gets the [LanePosition] associated with this `RoadPosition`.
1697    ///
1698    /// # Returns
1699    /// A [LanePosition] that defines the position within the lane for this `RoadPosition`.
1700    pub fn pos(&self) -> LanePosition {
1701        LanePosition {
1702            lp: maliput_sys::api::ffi::RoadPosition_pos(&self.rp),
1703        }
1704    }
1705}
1706
1707/// Represents the result of a RoadPosition query.
1708/// This struct contains the `RoadPosition`, the nearest `InertialPosition` to that `RoadPosition`,
1709/// and the distance between the input `InertialPosition` and the nearest `InertialPosition`.
1710///
1711/// This struct is typically used as return type for the methods: [RoadGeometry::to_road_position] and [RoadGeometry::find_road_positions].
1712pub struct RoadPositionQuery {
1713    /// The candidate RoadPosition returned by the query.
1714    pub road_position: RoadPosition,
1715    /// The nearest InertialPosition to the candidate RoadPosition.
1716    /// This is the position in the inertial frame that is closest to the candidate RoadPosition
1717    pub nearest_position: InertialPosition,
1718    /// The distance between the input InertialPosition and the nearest InertialPosition.
1719    pub distance: f64,
1720}
1721
1722impl RoadPositionQuery {
1723    /// Create a new `RoadPositionQuery` with the given `road_position`, `nearest_position`, and `distance`.
1724    pub fn new(road_position: RoadPosition, nearest_position: InertialPosition, distance: f64) -> RoadPositionQuery {
1725        RoadPositionQuery {
1726            road_position,
1727            nearest_position,
1728            distance,
1729        }
1730    }
1731}
1732
1733/// Represents the result of a LanePosition query.
1734/// This struct contains the `LanePosition`, the nearest `InertialPosition` to that `LanePosition`,
1735/// and the distance between the input `InertialPosition` and the nearest `InertialPosition`.
1736///
1737/// This struct is typically used as return type for the methods: [Lane::to_lane_position] and [Lane::to_segment_position].
1738pub struct LanePositionQuery {
1739    /// The candidate LanePosition within the Lane' lane-bounds or segment-bounds
1740    /// depending if [Lane::to_lane_position] or [Lane::to_segment_position] respectively, was called.
1741    /// The LanePosition is closest to a `inertial_position` supplied to [Lane::to_lane_position]
1742    /// (measured by the Cartesian metric in the `Inertial`-frame).
1743    pub lane_position: LanePosition,
1744    /// The position that exactly corresponds to `lane_position`.
1745    pub nearest_position: InertialPosition,
1746    /// The Cartesian distance between `nearest_position` and the
1747    /// `inertial_position` supplied to [Lane::to_lane_position] / [Lane::to_segment_position].
1748    pub distance: f64,
1749}
1750
1751impl LanePositionQuery {
1752    /// Create a new `LanePositionQuery` with the given `lane_position`, `nearest_position`, and `distance`.
1753    pub fn new(lane_position: LanePosition, nearest_position: InertialPosition, distance: f64) -> LanePositionQuery {
1754        LanePositionQuery {
1755            lane_position,
1756            nearest_position,
1757            distance,
1758        }
1759    }
1760}
1761
1762/// A 3-dimensional rotation in the road network.
1763/// This struct represents a rotation in the road network, which can be defined
1764/// using a quaternion or roll-pitch-yaw angles.
1765/// It provides methods to create a rotation, convert between representations,
1766/// and apply the rotation to an inertial position.
1767pub struct Rotation {
1768    r: cxx::UniquePtr<maliput_sys::api::ffi::Rotation>,
1769}
1770
1771impl Default for Rotation {
1772    fn default() -> Self {
1773        Self::new()
1774    }
1775}
1776
1777impl Rotation {
1778    /// Create a new `Rotation`.
1779    pub fn new() -> Rotation {
1780        Rotation {
1781            r: maliput_sys::api::ffi::Rotation_new(),
1782        }
1783    }
1784    /// Create a new `Rotation` from a `Quaternion`.
1785    pub fn from_quat(q: &Quaternion) -> Rotation {
1786        let q_ffi = maliput_sys::math::ffi::Quaternion_new(q.w(), q.x(), q.y(), q.z());
1787        Rotation {
1788            r: maliput_sys::api::ffi::Rotation_from_quat(&q_ffi),
1789        }
1790    }
1791    /// Create a new `Rotation` from a `RollPitchYaw`.
1792    pub fn from_rpy(rpy: &RollPitchYaw) -> Rotation {
1793        let rpy_ffi = maliput_sys::math::ffi::RollPitchYaw_new(rpy.roll_angle(), rpy.pitch_angle(), rpy.yaw_angle());
1794        Rotation {
1795            r: maliput_sys::api::ffi::Rotation_from_rpy(&rpy_ffi),
1796        }
1797    }
1798    /// Get the roll of the `Rotation`.
1799    pub fn roll(&self) -> f64 {
1800        self.r.roll()
1801    }
1802    /// Get the pitch of the `Rotation`.
1803    pub fn pitch(&self) -> f64 {
1804        self.r.pitch()
1805    }
1806    /// Get the yaw of the `Rotation`.
1807    pub fn yaw(&self) -> f64 {
1808        self.r.yaw()
1809    }
1810    /// Get a quaternion representation of the `Rotation`.
1811    pub fn quat(&self) -> Quaternion {
1812        let q_ffi = self.r.quat();
1813        Quaternion::new(q_ffi.w(), q_ffi.x(), q_ffi.y(), q_ffi.z())
1814    }
1815    /// Get a roll-pitch-yaw representation of the `Rotation`.
1816    pub fn rpy(&self) -> RollPitchYaw {
1817        let rpy_ffi = maliput_sys::api::ffi::Rotation_rpy(&self.r);
1818        RollPitchYaw::new(rpy_ffi.roll_angle(), rpy_ffi.pitch_angle(), rpy_ffi.yaw_angle())
1819    }
1820    /// Set the `Rotation` from a `Quaternion`.
1821    pub fn set_quat(&mut self, q: &Quaternion) {
1822        let q_ffi = maliput_sys::math::ffi::Quaternion_new(q.w(), q.x(), q.y(), q.z());
1823        maliput_sys::api::ffi::Rotation_set_quat(self.r.pin_mut(), &q_ffi);
1824    }
1825    /// Get the matrix representation of the `Rotation`.
1826    pub fn matrix(&self) -> Matrix3 {
1827        let matrix_ffi: cxx::UniquePtr<maliput_sys::math::ffi::Matrix3> =
1828            maliput_sys::api::ffi::Rotation_matrix(&self.r);
1829        let row_0 = maliput_sys::math::ffi::Matrix3_row(matrix_ffi.as_ref().expect(""), 0);
1830        let row_1 = maliput_sys::math::ffi::Matrix3_row(matrix_ffi.as_ref().expect(""), 1);
1831        let row_2 = maliput_sys::math::ffi::Matrix3_row(matrix_ffi.as_ref().expect(""), 2);
1832        Matrix3::new(
1833            Vector3::new(row_0.x(), row_0.y(), row_0.z()),
1834            Vector3::new(row_1.x(), row_1.y(), row_1.z()),
1835            Vector3::new(row_2.x(), row_2.y(), row_2.z()),
1836        )
1837    }
1838    /// Get the distance between two `Rotation`.
1839    pub fn distance(&self, other: &Rotation) -> f64 {
1840        self.r.Distance(&other.r)
1841    }
1842    /// Apply the `Rotation` to an `InertialPosition`.
1843    pub fn apply(&self, v: &InertialPosition) -> InertialPosition {
1844        InertialPosition {
1845            ip: maliput_sys::api::ffi::Rotation_Apply(&self.r, &v.ip),
1846        }
1847    }
1848    /// Get the reverse of the `Rotation`.
1849    pub fn reverse(&self) -> Rotation {
1850        Rotation {
1851            r: maliput_sys::api::ffi::Rotation_Reverse(&self.r),
1852        }
1853    }
1854}
1855
1856/// Directed, inclusive longitudinal (s value) range from s0 to s1.
1857pub struct SRange {
1858    s_range: cxx::UniquePtr<maliput_sys::api::ffi::SRange>,
1859}
1860
1861impl SRange {
1862    /// Creates a new `SRange` with the given `s0` and `s1`.
1863    ///
1864    /// # Arguments
1865    /// * `s0` - The starting value of the range.
1866    /// * `s1` - The ending value of the range.
1867    ///
1868    /// # Returns
1869    /// A new `SRange` instance.
1870    pub fn new(s0: f64, s1: f64) -> SRange {
1871        SRange {
1872            s_range: maliput_sys::api::ffi::SRange_new(s0, s1),
1873        }
1874    }
1875    /// Returns the s0 of the `SRange`.
1876    ///
1877    /// # Returns
1878    /// The starting value of the range.
1879    pub fn s0(&self) -> f64 {
1880        self.s_range.s0()
1881    }
1882    /// Returns the s1 of the `SRange`.
1883    ///
1884    /// # Returns
1885    /// The ending value of the range.
1886    pub fn s1(&self) -> f64 {
1887        self.s_range.s1()
1888    }
1889    /// Sets the s0 of the `SRange`.
1890    ///
1891    /// # Arguments
1892    /// * `s0` - The new starting value of the range.
1893    pub fn set_s0(&mut self, s0: f64) {
1894        self.s_range.as_mut().expect("Underlying SRange is null").set_s0(s0);
1895    }
1896    /// Sets the s1 of the `SRange`.
1897    ///
1898    /// # Arguments
1899    /// * `s1` - The new ending value of the range.
1900    pub fn set_s1(&mut self, s1: f64) {
1901        self.s_range.as_mut().expect("Underlying SRange is null").set_s1(s1);
1902    }
1903    /// Get the size of the `SRange`.
1904    ///
1905    /// # Returns
1906    /// The size of the range, which is the difference between s1 and s0.
1907    pub fn size(&self) -> f64 {
1908        self.s_range.size()
1909    }
1910    /// Defines whether this SRange is in the direction of +s (i.e., s1() > s0()).
1911    ///
1912    /// # Returns
1913    /// A boolean indicating whether the SRange is in the direction of +s.
1914    pub fn with_s(&self) -> bool {
1915        self.s_range.WithS()
1916    }
1917    /// Determines whether this SRange intersects with `s_range`.
1918    ///
1919    /// # Arguments
1920    /// * `s_range` - Another `SRange` to check for intersection.
1921    /// * `tolerance` - A tolerance value to consider when checking for intersection.
1922    ///
1923    /// # Returns
1924    /// A boolean indicating whether this SRange intersects with `s_range`.
1925    pub fn intersects(&self, s_range: &SRange, tolerance: f64) -> bool {
1926        self.s_range.Intersects(&s_range.s_range, tolerance)
1927    }
1928    /// Determines whether this SRange contains `s_range`.
1929    ///
1930    /// # Arguments
1931    /// * `s_range` - Another `SRange` to check if it is contained within this SRange.
1932    /// * `tolerance` - A tolerance value to consider when checking for containment.
1933    pub fn contains(&self, s_range: &SRange, tolerance: f64) -> bool {
1934        self.s_range.Contains(&s_range.s_range, tolerance)
1935    }
1936    /// Get the intersection of this SRange with `s_range`.
1937    ///
1938    /// # Arguments
1939    /// * `s_range` - Another `SRange` to get the intersection with.
1940    /// * `tolerance` - A tolerance value to consider when checking for intersection.
1941    ///
1942    /// # Returns
1943    /// An `Option<SRange>` containing the intersection of this SRange with `s_range`.
1944    /// If the intersection is empty, it returns None.
1945    pub fn get_intersection(&self, s_range: &SRange, tolerance: f64) -> Option<SRange> {
1946        let intersection = maliput_sys::api::ffi::SRange_GetIntersection(&self.s_range, &s_range.s_range, tolerance);
1947        match intersection.is_null() {
1948            true => None,
1949            false => Some(SRange { s_range: intersection }),
1950        }
1951    }
1952}
1953
1954impl std::fmt::Debug for SRange {
1955    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
1956        write!(f, "SRange {{ s0: {}, s1: {} }}", self.s0(), self.s1())
1957    }
1958}
1959
1960/// Directed longitudinal range of a specific Lane, identified by a LaneId.
1961/// Similar to [SRange], but associated with a specific Lane.
1962pub struct LaneSRange {
1963    pub(crate) lane_s_range: cxx::UniquePtr<maliput_sys::api::ffi::LaneSRange>,
1964}
1965
1966impl LaneSRange {
1967    /// Creates a new `LaneSRange` with the given `lane_id` and `s_range`.
1968    /// # Arguments
1969    /// * `lane_id` - A `String` representing the id of the lane.
1970    /// * `s_range` - A reference to an [SRange] that defines the longitudinal range of the lane.
1971    ///
1972    /// # Returns
1973    /// A new `LaneSRange` instance.
1974    pub fn new(lane_id: &String, s_range: &SRange) -> LaneSRange {
1975        LaneSRange {
1976            lane_s_range: maliput_sys::api::ffi::LaneSRange_new(lane_id, &s_range.s_range),
1977        }
1978    }
1979    /// Returns the lane id of the `LaneSRange`.
1980    ///
1981    /// # Returns
1982    /// A `String` containing the id of the lane associated with this `LaneSRange`.
1983    pub fn lane_id(&self) -> String {
1984        maliput_sys::api::ffi::LaneSRange_lane_id(&self.lane_s_range)
1985    }
1986    /// Returns the [SRange] of the `LaneSRange`.
1987    ///
1988    /// # Returns
1989    /// An [SRange] containing the longitudinal range of the lane associated with this `LaneSRange`.
1990    pub fn s_range(&self) -> SRange {
1991        SRange {
1992            s_range: maliput_sys::api::ffi::LaneSRange_s_range(&self.lane_s_range),
1993        }
1994    }
1995    /// Returns the length of the `LaneSRange`.
1996    ///
1997    /// This is equivalent to `s_range.size()`.
1998    ///
1999    /// # Returns
2000    /// A `f64` representing the length of the `LaneSRange`.
2001    pub fn length(&self) -> f64 {
2002        self.lane_s_range.length()
2003    }
2004    /// Determines whether this LaneSRange intersects with `lane_s_range`.
2005    ///
2006    /// # Arguments
2007    /// * `lane_s_range` - Another `LaneSRange` to check for intersection.
2008    /// * `tolerance` - A tolerance value to consider when checking for intersection.
2009    ///
2010    /// # Returns
2011    /// A boolean indicating whether this LaneSRange intersects with `lane_s_range`.
2012    pub fn intersects(&self, lane_s_range: &LaneSRange, tolerance: f64) -> bool {
2013        self.lane_s_range.Intersects(&lane_s_range.lane_s_range, tolerance)
2014    }
2015    /// Determines whether this LaneSRange contains `lane_s_range`.
2016    ///
2017    /// # Arguments
2018    /// * `lane_s_range` - Another `LaneSRange` to check if it is contained within this LaneSRange.
2019    /// * `tolerance` - A tolerance value to consider when checking for containment.
2020    ///
2021    /// # Returns
2022    /// A boolean indicating whether this LaneSRange contains `lane_s_range`.
2023    /// This checks if the `s_range` of `lane_s_range` is fully contained
2024    /// within the `s_range` of this `LaneSRange`, considering the lane id.
2025    /// If the lane id does not match, it returns false.
2026    pub fn contains(&self, lane_s_range: &LaneSRange, tolerance: f64) -> bool {
2027        self.lane_s_range.Contains(&lane_s_range.lane_s_range, tolerance)
2028    }
2029    /// Computes the intersection of this `LaneSRange` with `lane_s_range`.
2030    ///
2031    /// # Arguments
2032    /// * `lane_s_range` - Another `LaneSRange` to get the intersection with.
2033    /// * `tolerance` - A tolerance value to consider when checking for intersection.
2034    ///
2035    /// # Returns
2036    /// An `Option<LaneSRange>` containing the intersection of this `LaneSRange` with `lane_s_range`.
2037    /// If the lane ids do not match, it returns None.
2038    /// If the intersection is empty, it returns None.
2039    pub fn get_intersection(&self, lane_s_range: &LaneSRange, tolerance: f64) -> Option<LaneSRange> {
2040        let intersection = maliput_sys::api::ffi::LaneSRange_GetIntersection(
2041            &self.lane_s_range,
2042            &lane_s_range.lane_s_range,
2043            tolerance,
2044        );
2045        match intersection.is_null() {
2046            true => None,
2047            false => Some(LaneSRange {
2048                lane_s_range: intersection,
2049            }),
2050        }
2051    }
2052}
2053
2054impl std::fmt::Debug for LaneSRange {
2055    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
2056        write!(
2057            f,
2058            "LaneSRange {{ lane_id: {}, s_range: {:?} }}",
2059            self.lane_id(),
2060            self.s_range()
2061        )
2062    }
2063}
2064
2065/// A route, possibly spanning multiple (end-to-end) lanes.
2066///
2067/// The sequence of [LaneSRange]s should be contiguous by either presenting
2068/// laterally adjacent [LaneSRange]s, or consecutive [LaneSRange]s. (In other words,
2069/// taken as a Lane-space path with r=0 and h=0, it should present a
2070/// G1-continuous curve.)
2071pub struct LaneSRoute {
2072    lane_s_route: cxx::UniquePtr<maliput_sys::api::ffi::LaneSRoute>,
2073}
2074
2075impl LaneSRoute {
2076    /// Creates a new `LaneSRoute` with the given `ranges`.
2077    ///
2078    /// # Arguments
2079    /// * `ranges` - A vector of [LaneSRange] to create the [LaneSRoute].
2080    ///
2081    /// # Returns
2082    /// A new `LaneSRoute` instance containing the provided ranges.
2083    pub fn new(ranges: Vec<LaneSRange>) -> LaneSRoute {
2084        let mut lane_s_ranges_cpp = cxx::CxxVector::new();
2085        for range in &ranges {
2086            lane_s_ranges_cpp
2087                .as_mut()
2088                .unwrap()
2089                .push(maliput_sys::api::ffi::ConstLaneSRangeRef {
2090                    lane_s_range: &range.lane_s_range,
2091                });
2092        }
2093        LaneSRoute {
2094            lane_s_route: maliput_sys::api::ffi::LaneSRoute_new(&lane_s_ranges_cpp),
2095        }
2096    }
2097
2098    /// Returns the sequence of [LaneSRange]s.
2099    ///
2100    /// # Returns
2101    /// A vector of [LaneSRange]s that make up this [LaneSRoute].
2102    pub fn ranges(&self) -> Vec<LaneSRange> {
2103        let mut ranges = Vec::new();
2104        let lane_s_ranges = self.lane_s_route.ranges();
2105        for range in lane_s_ranges {
2106            ranges.push(LaneSRange {
2107                lane_s_range: maliput_sys::api::ffi::LaneSRange_new(
2108                    &maliput_sys::api::ffi::LaneSRange_lane_id(range),
2109                    maliput_sys::api::ffi::LaneSRange_s_range(range).as_ref().expect(""),
2110                ),
2111            })
2112        }
2113        ranges
2114    }
2115
2116    /// Computes the accumulated length of all [LaneSRange]s.
2117    ///
2118    /// # Returns
2119    /// A `f64` representing the total length of the [LaneSRoute].
2120    pub fn length(&self) -> f64 {
2121        self.lane_s_route.length()
2122    }
2123
2124    /// Determines whether this LaneSRoute intersects with `other`.
2125    ///
2126    /// # Arguments
2127    /// * `other` - The other LaneSRoute to check for intersection.
2128    /// * `tolerance` - The tolerance to use for intersection checks.
2129    ///
2130    /// # Returns
2131    /// * `true` if the two LaneSRoute intersect, `false` otherwise.
2132    pub fn intersects(&self, other: &LaneSRoute, tolerance: f64) -> bool {
2133        self.lane_s_route.Intersects(&other.lane_s_route, tolerance)
2134    }
2135}
2136
2137impl std::fmt::Debug for LaneSRoute {
2138    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
2139        write!(f, "LaneSRoute {{ ranges: {:?} }}", self.ranges())
2140    }
2141}
2142
2143/// A specific endpoint of a specific Lane.
2144pub enum LaneEnd<'a> {
2145    /// The start of the Lane. ("s == 0")
2146    Start(Lane<'a>),
2147    /// The end of the Lane. ("s == length")
2148    Finish(Lane<'a>),
2149}
2150
2151impl LaneEnd<'_> {
2152    /// Gets the Lane of the `LaneEnd`.
2153    ///
2154    /// # Returns
2155    /// A reference to the [Lane] associated with this `LaneEnd`.
2156    /// This will return the Lane for both Start and Finish variants.
2157    pub fn lane(&self) -> &Lane<'_> {
2158        match self {
2159            LaneEnd::Start(lane) => lane,
2160            LaneEnd::Finish(lane) => lane,
2161        }
2162    }
2163}
2164
2165impl PartialEq for LaneEnd<'_> {
2166    fn eq(&self, other: &Self) -> bool {
2167        match self {
2168            LaneEnd::Start(lane) => match other {
2169                LaneEnd::Start(other_lane) => lane.id() == other_lane.id(),
2170                _ => false,
2171            },
2172            LaneEnd::Finish(lane) => match other {
2173                LaneEnd::Finish(other_lane) => lane.id() == other_lane.id(),
2174                _ => false,
2175            },
2176        }
2177    }
2178}
2179
2180impl Eq for LaneEnd<'_> {}
2181
2182impl std::fmt::Display for LaneEnd<'_> {
2183    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
2184        match self {
2185            LaneEnd::Start(lane) => write!(f, "LaneEnd::Start({})", lane.id()),
2186            LaneEnd::Finish(lane) => write!(f, "LaneEnd::Finish({})", lane.id()),
2187        }
2188    }
2189}
2190
2191impl std::fmt::Debug for LaneEnd<'_> {
2192    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
2193        match self {
2194            LaneEnd::Start(lane) => write!(f, "LaneEnd::Start({})", lane.id()),
2195            LaneEnd::Finish(lane) => write!(f, "LaneEnd::Finish({})", lane.id()),
2196        }
2197    }
2198}
2199
2200/// A set of LaneEnds.
2201pub struct LaneEndSet<'a> {
2202    lane_end_set: &'a maliput_sys::api::ffi::LaneEndSet,
2203}
2204
2205impl<'a> LaneEndSet<'a> {
2206    /// Obtains the size of the LaneEndSet.
2207    ///
2208    /// # Returns
2209    /// The number of LaneEnds in the set.
2210    pub fn size(&self) -> i32 {
2211        self.lane_end_set.size()
2212    }
2213    /// Gets the [LaneEnd] at the given index.
2214    ///
2215    /// # Arguments
2216    /// * `index` - The index of the LaneEnd to retrieve.
2217    ///
2218    /// # Returns
2219    /// A [Result<LaneEnd, MaliputError>] containing the LaneEnd at the given index.
2220    /// If the index is out of bounds, an error is returned.
2221    pub fn get(&self, index: i32) -> Result<LaneEnd<'_>, MaliputError> {
2222        let lane_end = self.lane_end_set.get(index)?;
2223        // Obtain end type and lane reference.
2224        let is_start = maliput_sys::api::ffi::LaneEnd_is_start(lane_end);
2225        let lane_ref = unsafe {
2226            maliput_sys::api::ffi::LaneEnd_lane(lane_end)
2227                .as_ref()
2228                .expect("Underlying LaneEnd is null")
2229        };
2230        // Create a LaneEnd enum variant.
2231        Ok(match is_start {
2232            true => LaneEnd::Start(Lane { lane: lane_ref }),
2233            false => LaneEnd::Finish(Lane { lane: lane_ref }),
2234        })
2235    }
2236
2237    /// Converts the LaneEndSet to a map of lane-id to LaneEnd.
2238    ///
2239    /// # Returns
2240    /// A `HashMap<String, LaneEnd>` where the key is the lane id and
2241    /// the value is the corresponding LaneEnd.
2242    pub fn to_lane_map(&self) -> std::collections::HashMap<String, LaneEnd<'_>> {
2243        (0..self.size())
2244            .map(|i| {
2245                let end = self.get(i).unwrap();
2246                (end.lane().id(), end)
2247            })
2248            .collect()
2249    }
2250}
2251
2252/// A BranchPoint is a node in the network of a RoadGeometry at which
2253/// Lanes connect to one another.  A BranchPoint is a collection of LaneEnds
2254/// specifying the Lanes (and, in particular, which ends of the Lanes) are
2255/// connected at the BranchPoint.
2256///
2257/// LaneEnds participating in a BranchPoint are grouped into two sets,
2258/// arbitrarily named "A-side" and "B-side". LaneEnds on the same "side"
2259/// have coincident into-the-lane tangent vectors, which are anti-parallel
2260/// to those of LaneEnds on the other side.
2261pub struct BranchPoint<'a> {
2262    branch_point: &'a maliput_sys::api::ffi::BranchPoint,
2263}
2264
2265impl<'a> BranchPoint<'a> {
2266    /// Returns the id of the BranchPoint.
2267    ///
2268    /// # Returns
2269    /// A `String` containing the id of the BranchPoint.
2270    pub fn id(&self) -> String {
2271        maliput_sys::api::ffi::BranchPoint_id(self.branch_point)
2272    }
2273    /// Returns the [RoadGeometry] to which this BranchPoint belongs.
2274    ///
2275    /// # Returns
2276    /// A [RoadGeometry] containing the RoadGeometry to which this BranchPoint belongs.
2277    pub fn road_geometry(&self) -> RoadGeometry<'_> {
2278        unsafe {
2279            RoadGeometry {
2280                rg: self.branch_point.road_geometry().as_ref().expect(""),
2281            }
2282        }
2283    }
2284    /// Returns the set of [LaneEnd]s on the same side as the given [LaneEnd].
2285    /// E.g: For a T-junction, this would return the set of LaneEnds on the merging side.
2286    ///
2287    /// # Arguments
2288    /// * `end` - This branch's start or end [LaneEnd].
2289    ///
2290    /// # Return
2291    /// A [LaneEndSet] of [LaneEnd]s on the same side as the given [LaneEnd].
2292    pub fn get_confluent_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
2293        let lane_end_set_ptr = self.branch_point.GetConfluentBranches(
2294            BranchPoint::from_lane_end_to_ffi(end)
2295                .as_ref()
2296                .expect("Underlying LaneEnd is null"),
2297        )?;
2298        Ok(LaneEndSet {
2299            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
2300        })
2301    }
2302    /// Returns the set of [LaneEnd]s on the opposite side as the given [LaneEnd].
2303    /// E.g: For a T-junction, this would return the [LaneEnd]s which end flows into the junction.
2304    ///
2305    /// # Arguments
2306    /// * `end` - This branch's start or end [LaneEnd].
2307    ///
2308    /// # Return
2309    /// A [LaneEndSet] of [LaneEnd]s on the opposite side as the given [LaneEnd].
2310    pub fn get_ongoing_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
2311        let lane_end_set_ptr = self.branch_point.GetOngoingBranches(
2312            BranchPoint::from_lane_end_to_ffi(end)
2313                .as_ref()
2314                .expect("Underlying LaneEnd is null"),
2315        )?;
2316        Ok(LaneEndSet {
2317            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
2318        })
2319    }
2320    /// Returns the default ongoing branch (if any) for the given `end`.
2321    /// This typically represents what would be considered "continuing
2322    /// through-traffic" from `end` (e.g., as opposed to a branch executing
2323    /// a turn).
2324    ///
2325    /// If `end` has no default-branch at this BranchPoint, the return
2326    /// value will be None.
2327    ///
2328    /// # Arguments
2329    /// * `end` - The [LaneEnd] for which to get the default branch.
2330    ///
2331    /// # Returns
2332    /// An `Option<LaneEnd>` containing the default branch if it exists.
2333    /// If no default branch exists, it returns None.
2334    pub fn get_default_branch(&self, end: &LaneEnd) -> Option<LaneEnd<'_>> {
2335        let lane_end = maliput_sys::api::ffi::BranchPoint_GetDefaultBranch(
2336            self.branch_point,
2337            BranchPoint::from_lane_end_to_ffi(end)
2338                .as_ref()
2339                .expect("Underlying LaneEnd is null"),
2340        );
2341        match lane_end.is_null() {
2342            true => None,
2343            false => {
2344                let lane_end_ref: &maliput_sys::api::ffi::LaneEnd =
2345                    lane_end.as_ref().expect("Underlying LaneEnd is null");
2346                let is_start = maliput_sys::api::ffi::LaneEnd_is_start(lane_end_ref);
2347                let lane_ref = unsafe {
2348                    maliput_sys::api::ffi::LaneEnd_lane(lane_end_ref)
2349                        .as_ref()
2350                        .expect("Underlying LaneEnd is null")
2351                };
2352                match is_start {
2353                    true => Some(LaneEnd::Start(Lane { lane: lane_ref })),
2354                    false => Some(LaneEnd::Finish(Lane { lane: lane_ref })),
2355                }
2356            }
2357        }
2358    }
2359    /// Returns the set of LaneEnds grouped together on the "A-side".
2360    ///
2361    /// # Returns
2362    /// A [LaneEndSet] containing the LaneEnds on the "A-side" of the BranchPoint.
2363    pub fn get_a_side(&self) -> LaneEndSet<'_> {
2364        let lane_end_set_ptr = self.branch_point.GetASide();
2365        LaneEndSet {
2366            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
2367        }
2368    }
2369    /// Returns the set of LaneEnds grouped together on the "B-side".
2370    ///
2371    /// # Returns
2372    /// A [LaneEndSet] containing the LaneEnds on the "B-side" of the BranchPoint.
2373    /// This is the opposite side of the "A-side".
2374    pub fn get_b_side(&self) -> LaneEndSet<'_> {
2375        let lane_end_set_ptr = self.branch_point.GetBSide();
2376        LaneEndSet {
2377            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
2378        }
2379    }
2380    /// Converts LaneEnd enum to LaneEnd ffi.
2381    fn from_lane_end_to_ffi(end: &LaneEnd) -> cxx::UniquePtr<maliput_sys::api::ffi::LaneEnd> {
2382        match end {
2383            LaneEnd::Start(lane) => unsafe { maliput_sys::api::ffi::LaneEnd_new(lane.lane, true) },
2384            LaneEnd::Finish(lane) => unsafe { maliput_sys::api::ffi::LaneEnd_new(lane.lane, false) },
2385        }
2386    }
2387}
2388
2389/// An abstract convenience class that aggregates information pertaining to an
2390/// intersection. Its primary purpose is to serve as a single source of this
2391/// information and to remove the need for users to query numerous disparate
2392/// data structures and state providers.
2393pub struct Intersection<'a> {
2394    intersection: &'a maliput_sys::api::ffi::Intersection,
2395}
2396
2397impl<'a> Intersection<'a> {
2398    /// Returns the id of the `Intersection` as a string.
2399    pub fn id(&self) -> String {
2400        maliput_sys::api::ffi::Intersection_id(self.intersection)
2401    }
2402    /// Returns the current `phase` of the [Intersection].
2403    ///
2404    /// Based on the current `phase`, it returns a [rules::StateProviderQuery] with the phase's ID
2405    /// and the next state.
2406    ///
2407    /// # Returns
2408    /// A [rules::StateProviderQuery] for the current [rules::Phase].
2409    pub fn phase(&self) -> rules::StateProviderQuery<String> {
2410        let query = maliput_sys::api::ffi::Intersection_Phase(self.intersection);
2411        let next_state = maliput_sys::api::rules::ffi::PhaseStateProvider_next(&query);
2412        let next_state = if next_state.is_null() {
2413            None
2414        } else {
2415            Some(rules::NextState {
2416                next_state: next_state.phase_id.clone(),
2417                duration_until: if next_state.duration_until.is_null() {
2418                    None
2419                } else {
2420                    Some(next_state.duration_until.value)
2421                },
2422            })
2423        };
2424        rules::StateProviderQuery {
2425            state: maliput_sys::api::rules::ffi::PhaseStateProvider_state(&query),
2426            next: next_state,
2427        }
2428    }
2429    /// Returns the region of the `RoadNetwork` that is considered part of the `Intersection`.
2430    ///
2431    /// # Returns
2432    /// A vector of [LaneSRange]s where the intersection lives.
2433    pub fn region(&self) -> Vec<LaneSRange> {
2434        self.intersection
2435            .region()
2436            .iter()
2437            .map(|region| LaneSRange {
2438                lane_s_range: maliput_sys::api::ffi::LaneSRange_new(
2439                    &maliput_sys::api::ffi::LaneSRange_lane_id(region),
2440                    &maliput_sys::api::ffi::LaneSRange_s_range(region),
2441                ),
2442            })
2443            .collect::<Vec<LaneSRange>>()
2444    }
2445    /// Returns the ID of the [rules::PhaseRing] that applies to this intersection.
2446    ///
2447    /// # Returns
2448    /// A `String` with the ID of a [rules::PhaseRing].
2449    pub fn phase_ring_id(&self) -> String {
2450        maliput_sys::api::ffi::Intersection_ring_id(self.intersection)
2451    }
2452    pub fn bulb_ids(&self) -> Vec<rules::UniqueBulbId> {
2453        maliput_sys::api::ffi::Intersection_unique_bulb_ids(self.intersection)
2454            .iter()
2455            .map(|unique_bulb_id| rules::UniqueBulbId {
2456                unique_bulb_id: maliput_sys::api::rules::ffi::UniqueBulbId_create_unique_ptr(unique_bulb_id),
2457            })
2458            .collect()
2459    }
2460    /// Returns the current [rules::BulbState]s within the `Intersection`.
2461    ///
2462    /// # Returns
2463    /// A vector of [rules::BulbState]s.
2464    pub fn get_bulb_state(&self, unique_bulb_id: &rules::UniqueBulbId) -> Option<rules::BulbState> {
2465        let bulb_state =
2466            maliput_sys::api::ffi::Intersection_bulb_state(self.intersection, &unique_bulb_id.unique_bulb_id);
2467        if bulb_state.is_null() {
2468            return None;
2469        }
2470        match *bulb_state {
2471            maliput_sys::api::ffi::BulbState::kOn => Some(rules::BulbState::On),
2472            maliput_sys::api::ffi::BulbState::kOff => Some(rules::BulbState::Off),
2473            maliput_sys::api::ffi::BulbState::kBlinking => Some(rules::BulbState::Blinking),
2474            _ => None,
2475        }
2476    }
2477    /// Returns the current discrete value rule states within the intersection.
2478    pub fn discrete_value_rule_states(&self) -> Vec<rules::DiscreteValueRuleState> {
2479        maliput_sys::api::ffi::Intersection_DiscreteValueRuleStates(self.intersection)
2480            .iter()
2481            .map(|dvrs| rules::DiscreteValueRuleState {
2482                rule_id: dvrs.rule_id.clone(),
2483                state: rules::discrete_value_from_discrete_value_cxx(&dvrs.state),
2484            })
2485            .collect::<Vec<rules::DiscreteValueRuleState>>()
2486    }
2487    /// Determines whether the [rules::TrafficLight] is within this [Intersection].
2488    ///
2489    /// # Arguments
2490    /// * `traffic_light_id` - A [rules::TrafficLight] ID.
2491    ///
2492    /// # Returns
2493    /// True when `traffic_light_id` is within this [Intersection].
2494    pub fn includes_traffic_light(&self, traffic_light_id: &str) -> bool {
2495        maliput_sys::api::ffi::Intersection_IncludesTrafficLight(self.intersection, &traffic_light_id.to_string())
2496    }
2497    /// Determines whether the [rules::DiscreteValueRule] is within this [Intersection].
2498    ///
2499    /// # Arguments
2500    /// * `rule_id` - A [rules::DiscreteValueRule] ID.
2501    ///
2502    /// # Returns
2503    /// True when `rule_id` is within this [Intersection].
2504    pub fn includes_discrete_value_rule(&self, rule_id: &str) -> bool {
2505        maliput_sys::api::ffi::Intersection_IncludesDiscreteValueRule(self.intersection, &rule_id.to_string())
2506    }
2507    /// Determines whether `inertial_position` is within this [Intersection::region].
2508    ///
2509    /// `inertial_position` is contained if the distance to the closest LanePosition in
2510    /// [Intersection::region] is less or equal than the linear tolerance of the `road_geometry`.
2511    ///
2512    /// # Arguments
2513    /// * `inertial_position` -  An [InertialPosition] in the `Inertial`-frame.
2514    /// * `road_geometry` - The [RoadGeometry].
2515    ///
2516    /// # Returns
2517    /// True when `inertial_position` is within [Intersection::region]. False otherwise.
2518    pub fn includes_inertial_position(
2519        &self,
2520        inertial_position: &InertialPosition,
2521        road_geometry: &RoadGeometry,
2522    ) -> bool {
2523        maliput_sys::api::ffi::Intersection_IncludesInertialPosition(
2524            self.intersection,
2525            &maliput_sys::api::ffi::InertialPosition_new(
2526                inertial_position.x(),
2527                inertial_position.y(),
2528                inertial_position.z(),
2529            ),
2530            road_geometry.rg,
2531        )
2532    }
2533}
2534
2535/// A book of Intersections.
2536pub struct IntersectionBook<'a> {
2537    intersection_book: &'a maliput_sys::api::ffi::IntersectionBook,
2538}
2539
2540impl<'a> IntersectionBook<'a> {
2541    /// Returns all Intersections in the book.
2542    ///
2543    /// # Returns
2544    /// A vector of [Intersection]s containing all Intersections in the book.
2545    pub fn get_intersections(&self) -> Vec<Intersection<'_>> {
2546        let intersections_cpp = maliput_sys::api::ffi::IntersectionBook_GetIntersections(self.intersection_book);
2547        unsafe {
2548            intersections_cpp
2549                .into_iter()
2550                .map(|intersection| Intersection {
2551                    intersection: intersection
2552                        .intersection
2553                        .as_ref()
2554                        .expect("Underlying Intersection is null"),
2555                })
2556                .collect::<Vec<Intersection>>()
2557        }
2558    }
2559
2560    /// Gets the specified Intersection.
2561    ///
2562    /// # Arguments
2563    ///   * `id` - The id of the Intersection to get.
2564    ///
2565    /// # Returns
2566    ///   * An `Option<Intersection>`
2567    ///     * Some(Intersection) - The Intersection with the specified id.
2568    ///     * None - If the Intersection with the specified id does not exist.
2569    pub fn get_intersection(&self, id: &str) -> Option<Intersection<'_>> {
2570        let intersection_option = unsafe {
2571            maliput_sys::api::ffi::IntersectionBook_GetIntersection(self.intersection_book, &String::from(id))
2572                .intersection
2573                .as_ref()
2574        };
2575        intersection_option.map(|intersection| Intersection { intersection })
2576    }
2577
2578    /// Finds the [Intersection] which contains the `traffic_light_id`.
2579    ///
2580    /// # Arguments
2581    /// * `traffic_light_id` - A String with the ID of a [rules::TrafficLight].
2582    ///
2583    /// # Returns
2584    /// The [Intersection] which contains the `traffic_light_id`.
2585    pub fn find_intersection_with_traffic_light(&self, traffic_light_id: &str) -> Option<Intersection<'_>> {
2586        let intersection = maliput_sys::api::ffi::IntersectionBook_FindIntersectionTrafficLight(
2587            self.intersection_book,
2588            &String::from(traffic_light_id),
2589        );
2590        if intersection.intersection.is_null() {
2591            return None;
2592        }
2593        unsafe {
2594            Some(Intersection {
2595                intersection: intersection
2596                    .intersection
2597                    .as_ref()
2598                    .expect("Underlying Intersection is null"),
2599            })
2600        }
2601    }
2602
2603    /// Finds the [Intersection] which contains the `rule_id`.
2604    ///
2605    /// # Arguments
2606    /// * `rule_id` - A String with the ID of a [rules::DiscreteValueRule].
2607    ///
2608    /// # Returns
2609    /// The [Intersection] which contains the `rule_id`.
2610    pub fn find_intersection_with_discrete_value_rule(&self, rule_id: &str) -> Option<Intersection<'_>> {
2611        let intersection = maliput_sys::api::ffi::IntersectionBook_FindIntersectionDiscreteValueRule(
2612            self.intersection_book,
2613            &String::from(rule_id),
2614        );
2615        if intersection.intersection.is_null() {
2616            return None;
2617        }
2618        unsafe {
2619            Some(Intersection {
2620                intersection: intersection
2621                    .intersection
2622                    .as_ref()
2623                    .expect("Underlying Intersection is null"),
2624            })
2625        }
2626    }
2627
2628    /// Finds the [Intersection] which contains the `inertial_position`.
2629    ///
2630    /// # Arguments
2631    /// * `inertial_position` - An [InertialPosition] to find the [Intersection] for.
2632    ///
2633    /// # Returns
2634    /// The [Intersection] which contains the `inertial_position`.
2635    pub fn find_intersection_with_inertial_position(
2636        &self,
2637        inertial_position: &InertialPosition,
2638    ) -> Option<Intersection<'_>> {
2639        let intersection = maliput_sys::api::ffi::IntersectionBook_FindIntersectionInertialPosition(
2640            self.intersection_book,
2641            &inertial_position.ip,
2642        );
2643        if intersection.intersection.is_null() {
2644            return None;
2645        }
2646        unsafe {
2647            Some(Intersection {
2648                intersection: intersection
2649                    .intersection
2650                    .as_ref()
2651                    .expect("Underlying Intersection is null"),
2652            })
2653        }
2654    }
2655}
2656
2657#[derive(Debug, Copy, Clone, PartialEq)]
2658pub struct LaneMarkingLine {
2659    /// Length of the visible (painted) part of each dash.
2660    /// For solid lines, this should be 0 (value is ignored).
2661    pub length: f64,
2662
2663    /// Length of the gap between visible parts.
2664    /// For solid lines, this should be 0.
2665    pub space: f64,
2666
2667    /// Width of this line, in meters.
2668    pub width: f64,
2669
2670    /// Lateral offset from the lane boundary.
2671    /// Positive values offset in the positive r-direction (towards the lane's
2672    /// left edge when facing the positive s-direction).
2673    /// This allows positioning multiple lines relative to each other.
2674    pub r_offset: f64,
2675
2676    /// Color of this specific line.
2677    /// If set to kUnknown, the parent LaneMarking's color should be used.
2678    pub color: LaneMarkingColor,
2679}
2680
2681impl LaneMarkingLine {
2682    /// Creates a new LaneMarkingLine.
2683    pub fn new(length: f64, space: f64, width: f64, r_offset: f64, color: LaneMarkingColor) -> LaneMarkingLine {
2684        LaneMarkingLine {
2685            length,
2686            space,
2687            width,
2688            r_offset,
2689            color,
2690        }
2691    }
2692}
2693
2694/// LaneMarking classification options.
2695///
2696/// LaneMarkingType defines types of lane markings on the road.
2697#[derive(strum_macros::Display, Debug, Copy, Clone, PartialEq, Eq)]
2698pub enum LaneMarkingType {
2699    Unknown,
2700    None,
2701    Solid,
2702    Broken,
2703    SolidSolid,
2704    SolidBroken,
2705    BrokenSolid,
2706    BrokenBroken,
2707    BottsDots,
2708    Grass,
2709    Curb,
2710    Edge,
2711}
2712
2713#[derive(strum_macros::Display, Debug, Copy, Clone, PartialEq, Eq)]
2714pub enum LaneMarkingWeight {
2715    Unknown,
2716    Standard,
2717    Bold,
2718}
2719
2720#[derive(strum_macros::Display, Debug, Copy, Clone, PartialEq, Eq)]
2721pub enum LaneMarkingColor {
2722    Unknown,
2723    White,
2724    Yellow,
2725    Orange,
2726    Red,
2727    Blue,
2728    Green,
2729    Violet,
2730}
2731
2732#[derive(strum_macros::Display, Debug, Copy, Clone, PartialEq, Eq)]
2733pub enum LaneChangePermission {
2734    Unknown,
2735    Allowed,
2736    ToLeft,
2737    ToRight,
2738    Prohibited,
2739}
2740
2741/// Describes the complete lane marking at a lane boundary.
2742///
2743/// A LaneMarking describes all properties of the road marking at a lane's
2744/// boundary. The marking can vary along the lane's s-coordinate, so this
2745/// structure represents the marking for a specific s-range.
2746///
2747/// **Simple markings:** For single-line markings (e.g., a solid white edge line),
2748/// the `type`, `color`, `width`, and `weight` fields are sufficient. The `lines`
2749/// vector can be left empty.
2750///
2751/// **Complex markings:** For compound markings (e.g., double lines with different
2752/// patterns like `kSolidBroken`), the `lines` vector provides detailed information
2753/// about each component line. When `lines` is non-empty, the individual line
2754/// definitions take precedence for geometry and per-line colors. The top-level
2755/// `type`, `color`, and `width` fields remain useful as summary/fallback values.
2756pub struct LaneMarking {
2757    lane_marking: cxx::UniquePtr<maliput_sys::api::ffi::LaneMarking>,
2758}
2759
2760impl LaneMarking {
2761    /// Returns the total width of the marking.
2762    pub fn width(&self) -> f64 {
2763        maliput_sys::api::ffi::LaneMarking_width(&self.lane_marking)
2764    }
2765
2766    /// Returns the total height of the marking.
2767    pub fn height(&self) -> f64 {
2768        maliput_sys::api::ffi::LaneMarking_height(&self.lane_marking)
2769    }
2770
2771    /// Returns the marking material.
2772    ///
2773    /// # Returns
2774    /// A [String] describing the marking material.
2775    pub fn material(&self) -> String {
2776        maliput_sys::api::ffi::LaneMarking_material(&self.lane_marking)
2777    }
2778
2779    /// Returns the type of marking.
2780    ///
2781    /// # Returns
2782    /// A [LaneMarkingType] representing the pattern or type of marking.
2783    pub fn get_type(&self) -> LaneMarkingType {
2784        let marking_type = maliput_sys::api::ffi::LaneMarking_type(&self.lane_marking);
2785        match marking_type {
2786            maliput_sys::api::ffi::LaneMarkingType::kUnknown => LaneMarkingType::Unknown,
2787            maliput_sys::api::ffi::LaneMarkingType::kNone => LaneMarkingType::None,
2788            maliput_sys::api::ffi::LaneMarkingType::kSolid => LaneMarkingType::Solid,
2789            maliput_sys::api::ffi::LaneMarkingType::kBroken => LaneMarkingType::Broken,
2790            maliput_sys::api::ffi::LaneMarkingType::kSolidSolid => LaneMarkingType::SolidSolid,
2791            maliput_sys::api::ffi::LaneMarkingType::kSolidBroken => LaneMarkingType::SolidBroken,
2792            maliput_sys::api::ffi::LaneMarkingType::kBrokenSolid => LaneMarkingType::BrokenSolid,
2793            maliput_sys::api::ffi::LaneMarkingType::kBrokenBroken => LaneMarkingType::BrokenBroken,
2794            maliput_sys::api::ffi::LaneMarkingType::kBottsDots => LaneMarkingType::BottsDots,
2795            maliput_sys::api::ffi::LaneMarkingType::kGrass => LaneMarkingType::Grass,
2796            maliput_sys::api::ffi::LaneMarkingType::kCurb => LaneMarkingType::Curb,
2797            maliput_sys::api::ffi::LaneMarkingType::kEdge => LaneMarkingType::Edge,
2798            _ => LaneMarkingType::Unknown,
2799        }
2800    }
2801
2802    /// Returns the visual weight or thickness type of the marking.
2803    ///
2804    /// # Returns
2805    /// A [LaneMarkingWeight] that indicates the type of visual weight of the marking.
2806    pub fn weight(&self) -> LaneMarkingWeight {
2807        let marking_weight = maliput_sys::api::ffi::LaneMarking_weight(&self.lane_marking);
2808        match marking_weight {
2809            maliput_sys::api::ffi::LaneMarkingWeight::kUnknown => LaneMarkingWeight::Unknown,
2810            maliput_sys::api::ffi::LaneMarkingWeight::kStandard => LaneMarkingWeight::Standard,
2811            maliput_sys::api::ffi::LaneMarkingWeight::kBold => LaneMarkingWeight::Bold,
2812            _ => LaneMarkingWeight::Unknown,
2813        }
2814    }
2815    pub fn color(&self) -> LaneMarkingColor {
2816        self.get_marking_color(maliput_sys::api::ffi::LaneMarking_color(&self.lane_marking))
2817    }
2818
2819    /// Returns the type of lane change the marking allows.
2820    ///
2821    /// # Returns
2822    /// A [LaneChangePermission] that indicates the type of lane change that is allowed.
2823    pub fn lane_change(&self) -> LaneChangePermission {
2824        let lane_change = maliput_sys::api::ffi::LaneMarking_lane_change(&self.lane_marking);
2825        match lane_change {
2826            maliput_sys::api::ffi::LaneChangePermission::kUnknown => LaneChangePermission::Unknown,
2827            maliput_sys::api::ffi::LaneChangePermission::kAllowed => LaneChangePermission::Allowed,
2828            maliput_sys::api::ffi::LaneChangePermission::kToLeft => LaneChangePermission::ToLeft,
2829            maliput_sys::api::ffi::LaneChangePermission::kToRight => LaneChangePermission::ToRight,
2830            maliput_sys::api::ffi::LaneChangePermission::kProhibited => LaneChangePermission::Prohibited,
2831            _ => LaneChangePermission::Unknown,
2832        }
2833    }
2834
2835    /// Returns all lines in the LaneMarking.
2836    ///
2837    /// # Returns
2838    /// A vector of [LaneMarkingLine]s.
2839    pub fn lines(&self) -> Vec<LaneMarkingLine> {
2840        let lines = maliput_sys::api::ffi::LaneMarking_lines(&self.lane_marking);
2841        lines
2842            .into_iter()
2843            .map(|line| LaneMarkingLine {
2844                length: maliput_sys::api::ffi::LaneMarkingLine_length(line),
2845                space: maliput_sys::api::ffi::LaneMarkingLine_space(line),
2846                width: maliput_sys::api::ffi::LaneMarkingLine_width(line),
2847                r_offset: maliput_sys::api::ffi::LaneMarkingLine_r_offset(line),
2848                color: self.get_marking_color(maliput_sys::api::ffi::LaneMarkingLine_color(line)),
2849            })
2850            .collect::<Vec<LaneMarkingLine>>()
2851    }
2852
2853    // Private helper to get marking color and avoid code duplication.
2854    fn get_marking_color(&self, color: maliput_sys::api::ffi::LaneMarkingColor) -> LaneMarkingColor {
2855        match color {
2856            maliput_sys::api::ffi::LaneMarkingColor::kUnknown => LaneMarkingColor::Unknown,
2857            maliput_sys::api::ffi::LaneMarkingColor::kWhite => LaneMarkingColor::White,
2858            maliput_sys::api::ffi::LaneMarkingColor::kYellow => LaneMarkingColor::Yellow,
2859            maliput_sys::api::ffi::LaneMarkingColor::kOrange => LaneMarkingColor::Orange,
2860            maliput_sys::api::ffi::LaneMarkingColor::kRed => LaneMarkingColor::Red,
2861            maliput_sys::api::ffi::LaneMarkingColor::kBlue => LaneMarkingColor::Blue,
2862            maliput_sys::api::ffi::LaneMarkingColor::kGreen => LaneMarkingColor::Green,
2863            maliput_sys::api::ffi::LaneMarkingColor::kViolet => LaneMarkingColor::Violet,
2864            _ => LaneMarkingColor::Unknown,
2865        }
2866    }
2867}
2868
2869/// The result of querying a [LaneMarking] at a specific position or range.
2870/// This structure pairs a [LaneMarking] with the s-range over which it is valid.
2871/// Lane markings can change along the lane (e.g., solid to broken at an
2872/// intersection approach), so the validity range is essential.
2873///
2874/// The range uses half-open interval semantics: `[s_start, s_end)`.
2875pub struct LaneMarkingQuery {
2876    /// LaneMarking description.
2877    pub lane_marking: LaneMarking,
2878    /// Start s-coordinate where the marking begins
2879    /// This is relative to the lane's s-coordinate system..
2880    pub s_start: f64,
2881    /// End s-coordinate where the marking ends.
2882    /// This is relative to the lane's s-coordinate system.
2883    pub s_end: f64,
2884}
2885
2886/// Represents a boundary between adjacent lanes or at the edge of a Segment.
2887///
2888/// A [LaneBoundary] is owned by a [Segment] and serves as the interface between
2889/// two adjacent lanes, or between a lane and the segment edge. For a [Segment]
2890/// with N lanes, there are N+1 boundaries:
2891///
2892/// ```text
2893///                                                        +r direction
2894///                                                      <─────────────
2895///   Boundary N    ...    Boundary 2    Boundary 1    Boundary 0
2896///      |                     |             |             |
2897///      | Lane N-1  |   ...   |   Lane 1    |   Lane 0    |
2898///      |                     |             |             |
2899///  (left edge)                                     (right edge)
2900/// ```
2901///
2902/// Where:
2903/// - Boundary 0 is the right edge (minimum r coordinate).
2904/// - Boundary N is the left edge (maximum r coordinate).
2905/// - Boundaries are indexed with increasing r direction.
2906///
2907/// Each [LaneBoundary] provides:
2908/// - Reference to the lane on its left (if any).
2909/// - Reference to the lane on its right (if any).
2910/// - Query methods for lane markings at specific s-coordinates.
2911///
2912/// The design ensures that adjacent lanes share the same boundary object,
2913/// avoiding redundancy and ensuring consistency. For example, [Lane] 1's right
2914/// boundary is the same object as [Lane] 0's left boundary (Boundary 1).
2915pub struct LaneBoundary<'a> {
2916    lane_boundary: &'a maliput_sys::api::ffi::LaneBoundary,
2917}
2918
2919impl<'a> LaneBoundary<'a> {
2920    /// Returns the ID of the [LaneBoundary].
2921    /// The ID is a unique identifier for the [LaneBoundary] within the Segment.
2922    ///
2923    /// # Returns
2924    /// A `String` containing the ID of the [LaneBoundary].
2925    pub fn id(&self) -> String {
2926        maliput_sys::api::ffi::LaneBoundary_id(self.lane_boundary)
2927    }
2928
2929    /// Returns the segment that contains this [LaneBoundary].
2930    ///
2931    /// # Returns
2932    /// An `Option<Segment>` containing a reference to the [Segment] if it exists,
2933    /// or `None` if the [LaneBoundary] is not associated with a segment.
2934    pub fn segment(&self) -> Option<Segment<'a>> {
2935        let segment = self.lane_boundary.segment();
2936        if segment.is_null() {
2937            return None;
2938        }
2939        Some(unsafe {
2940            Segment {
2941                segment: segment.as_ref().expect(""),
2942            }
2943        })
2944    }
2945
2946    /// Returns the index of this boundary within the parent [Segment].
2947    ///
2948    /// Boundaries are indexed from 0 (rightmost, minimum r) to num_lanes()
2949    /// (leftmost, maximum r).
2950    pub fn index(&self) -> i32 {
2951        self.lane_boundary.index()
2952    }
2953
2954    /// Returns the [Lane] immediately to the left of this boundary (increasing r direction).
2955    ///
2956    /// # Returns
2957    /// An `Option<Lane>` containing the lane to the left, or `None` if this is
2958    /// the leftmost boundary of the [Segment].
2959    pub fn lane_to_left(&self) -> Option<Lane<'a>> {
2960        let lane = self.lane_boundary.lane_to_left();
2961        if lane.is_null() {
2962            return None;
2963        }
2964        Some(unsafe {
2965            Lane {
2966                lane: lane.as_ref().expect("Lane pointer from lane_to_left is null"),
2967            }
2968        })
2969    }
2970
2971    /// Returns the [Lane] immediately to the right of this boundary (decreasing r direction).
2972    ///
2973    /// # Returns
2974    /// An `Option<Lane>` containing the lane to the right, or `None` if this is
2975    /// the rightmost boundary of the Segment.
2976    pub fn lane_to_right(&self) -> Option<Lane<'a>> {
2977        let lane = self.lane_boundary.lane_to_right();
2978        if lane.is_null() {
2979            return None;
2980        }
2981        Some(unsafe {
2982            Lane {
2983                lane: lane.as_ref().expect("Lane pointer from lane_to_right is null"),
2984            }
2985        })
2986    }
2987
2988    /// Gets the lane marking at a specific s-coordinate along this boundary.
2989    ///
2990    /// # Arguments
2991    /// * `s` - The s-coordinate along the boundary (in the lane coordinate system).
2992    ///   Typically in the range [0, segment_length].
2993    ///
2994    /// # Returns
2995    /// A [LaneMarkingQuery] at the specified position, including the marking details and the
2996    /// s-range over which it is valid, or `None` if no marking information is available at that location.
2997    pub fn get_marking(&self, s: f64) -> Option<LaneMarkingQuery> {
2998        let lane_marking_query = maliput_sys::api::ffi::LaneBoundary_GetMarking(self.lane_boundary, s);
2999        if lane_marking_query.is_null() {
3000            return None;
3001        }
3002        Some(self.create_lane_marking_query(&lane_marking_query))
3003    }
3004
3005    /// Gets all lane markings along this boundary.
3006    ///
3007    /// # Returns
3008    /// A vector of [LaneMarkingQuery], each describing a marking and the s-range over which it is valid.
3009    /// The queried results are ordered by increasing s_start. If no markings are available, returns an empty vector.
3010    pub fn get_markings(&self) -> Vec<LaneMarkingQuery> {
3011        let lane_marking_queries = maliput_sys::api::ffi::LaneBoundary_GetMarkings(self.lane_boundary);
3012        lane_marking_queries
3013            .into_iter()
3014            .map(|lane_marking_query| self.create_lane_marking_query(lane_marking_query))
3015            .collect::<Vec<LaneMarkingQuery>>()
3016    }
3017
3018    /// Gets lane markings within a specified s-range.
3019    ///
3020    /// # Arguments
3021    /// * `s_start` - Start of the s-range to query.
3022    /// * `s_end` - End of the s-range to query.
3023    ///
3024    /// # Returns
3025    /// A vector of [LaneMarkingQuery] for markings that overlap with the specified range. Queried results are ordered by increasing `s_start`.
3026    /// If no markings are available in the range, returns an empty vector.
3027    pub fn get_markings_by_range(&self, s_start: f64, s_end: f64) -> Vec<LaneMarkingQuery> {
3028        let lane_marking_queries =
3029            maliput_sys::api::ffi::LaneBoundary_GetMarkingsByRange(self.lane_boundary, s_start, s_end);
3030        lane_marking_queries
3031            .into_iter()
3032            .map(|lane_marking_query| self.create_lane_marking_query(lane_marking_query))
3033            .collect::<Vec<LaneMarkingQuery>>()
3034    }
3035
3036    // Private helper to create a LaneMarkingQuery.
3037    fn create_lane_marking_query(
3038        &self,
3039        lane_marking_query: &maliput_sys::api::ffi::LaneMarkingResult,
3040    ) -> LaneMarkingQuery {
3041        LaneMarkingQuery {
3042            lane_marking: LaneMarking {
3043                lane_marking: maliput_sys::api::ffi::LaneMarkingResult_marking(lane_marking_query),
3044            },
3045            s_start: maliput_sys::api::ffi::LaneMarkingResult_s_start(lane_marking_query),
3046            s_end: maliput_sys::api::ffi::LaneMarkingResult_s_end(lane_marking_query),
3047        }
3048    }
3049}
3050
3051mod tests {
3052    mod road_geometry {
3053        #[test]
3054        fn to_road_position_surface_test() {
3055            let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
3056            let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
3057            let road_network_properties = std::collections::HashMap::from([
3058                ("road_geometry_id", "my_rg_from_rust"),
3059                ("opendrive_file", xodr_path.as_str()),
3060            ]);
3061            let road_network = crate::api::RoadNetwork::new(
3062                crate::api::RoadNetworkBackend::MaliputMalidrive,
3063                &road_network_properties,
3064            )
3065            .unwrap();
3066            let road_geometry = road_network.road_geometry();
3067
3068            // Although this isn't directly on the surface, it is within the RoadGeometry volume.
3069            let inertial_pos = crate::api::InertialPosition::new(1.0, 0.0, 2.0);
3070            let road_pos = road_geometry.to_road_position_surface(&inertial_pos);
3071            assert!(road_pos.is_ok());
3072            let road_pos = road_pos.unwrap();
3073            let tolerance = 1e-3;
3074            assert!((road_pos.pos().s() - 1.0).abs() < tolerance);
3075            assert!((road_pos.pos().r() - -1.75).abs() < tolerance);
3076            assert!((road_pos.pos().h() - 0.0).abs() < tolerance);
3077
3078            // An inertial position that is off the road volume.
3079            let inertial_pos = crate::api::InertialPosition::new(1.0, 0.0, 10.0);
3080            let road_pos = road_geometry.to_road_position_surface(&inertial_pos);
3081            assert!(road_pos.is_err());
3082        }
3083    }
3084    mod lane_position {
3085        #[test]
3086        fn lane_position_new() {
3087            let lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3088            assert_eq!(lane_pos.s(), 1.0);
3089            assert_eq!(lane_pos.r(), 2.0);
3090            assert_eq!(lane_pos.h(), 3.0);
3091        }
3092
3093        #[test]
3094        fn equality() {
3095            let v = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3096            let w = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3097            assert_eq!(v, w);
3098            let z = crate::api::LanePosition::new(4.0, 5.0, 6.0);
3099            assert_ne!(v, z);
3100        }
3101
3102        #[test]
3103        fn set_s() {
3104            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3105            lane_pos.set_s(4.0);
3106            assert_eq!(lane_pos.s(), 4.0);
3107        }
3108
3109        #[test]
3110        fn set_r() {
3111            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3112            lane_pos.set_r(4.0);
3113            assert_eq!(lane_pos.r(), 4.0);
3114        }
3115
3116        #[test]
3117        fn set_h() {
3118            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3119            lane_pos.set_h(4.0);
3120            assert_eq!(lane_pos.h(), 4.0);
3121        }
3122
3123        #[test]
3124        fn set_srh() {
3125            use crate::math::Vector3;
3126            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
3127            let vector = Vector3::new(4.0, 5.0, 6.0);
3128            lane_pos.set_srh(&vector);
3129            assert_eq!(lane_pos.s(), 4.0);
3130            assert_eq!(lane_pos.r(), 5.0);
3131            assert_eq!(lane_pos.h(), 6.0);
3132        }
3133    }
3134
3135    mod inertial_position {
3136
3137        #[test]
3138        fn inertial_position_new() {
3139            let inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3140            assert_eq!(inertial_pos.x(), 1.0);
3141            assert_eq!(inertial_pos.y(), 2.0);
3142            assert_eq!(inertial_pos.z(), 3.0);
3143        }
3144
3145        #[test]
3146        fn equality() {
3147            let v = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3148            let w = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3149            assert_eq!(v, w);
3150            let z = crate::api::InertialPosition::new(4.0, 5.0, 6.0);
3151            assert_ne!(v, z);
3152        }
3153
3154        #[test]
3155        fn set_x() {
3156            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3157            inertial_pos.set_x(4.0);
3158            assert_eq!(inertial_pos.x(), 4.0);
3159        }
3160
3161        #[test]
3162        fn set_y() {
3163            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3164            inertial_pos.set_y(4.0);
3165            assert_eq!(inertial_pos.y(), 4.0);
3166        }
3167
3168        #[test]
3169        fn set_z() {
3170            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3171            inertial_pos.set_z(4.0);
3172            assert_eq!(inertial_pos.z(), 4.0);
3173        }
3174
3175        #[test]
3176        fn set_xyz() {
3177            use crate::math::Vector3;
3178            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3179            let vector = Vector3::new(4.0, 5.0, 6.0);
3180            inertial_pos.set_xyz(&vector);
3181            assert_eq!(inertial_pos.x(), 4.0);
3182            assert_eq!(inertial_pos.y(), 5.0);
3183            assert_eq!(inertial_pos.z(), 6.0);
3184        }
3185
3186        #[test]
3187        fn xyz() {
3188            let inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3189            assert_eq!(inertial_pos.xyz(), crate::math::Vector3::new(1.0, 2.0, 3.0));
3190        }
3191
3192        #[test]
3193        fn length() {
3194            let inertial_pos = crate::api::InertialPosition::new(3.0, 0.0, 4.0);
3195            assert_eq!(inertial_pos.length(), 5.0);
3196        }
3197
3198        #[test]
3199        fn distance() {
3200            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 1.0, 1.0);
3201            let inertial_pos2 = crate::api::InertialPosition::new(5.0, 1.0, 1.0);
3202            assert_eq!(inertial_pos1.distance(&inertial_pos2), 4.0);
3203        }
3204
3205        #[test]
3206        fn str() {
3207            let inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3208            assert_eq!(inertial_pos.to_string(), "(x = 1, y = 2, z = 3)");
3209        }
3210
3211        #[test]
3212        fn add_operation() {
3213            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3214            let inertial_pos2 = crate::api::InertialPosition::new(4.0, 5.0, 6.0);
3215            let inertial_pos3 = inertial_pos1 + inertial_pos2;
3216            assert_eq!(inertial_pos3.x(), 5.0);
3217            assert_eq!(inertial_pos3.y(), 7.0);
3218            assert_eq!(inertial_pos3.z(), 9.0);
3219        }
3220
3221        #[test]
3222        fn sub_operation() {
3223            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3224            let inertial_pos2 = crate::api::InertialPosition::new(4.0, 5.0, 6.0);
3225            let inertial_pos3 = inertial_pos1 - inertial_pos2;
3226            assert_eq!(inertial_pos3.x(), -3.0);
3227            assert_eq!(inertial_pos3.y(), -3.0);
3228            assert_eq!(inertial_pos3.z(), -3.0);
3229        }
3230
3231        #[test]
3232        fn mul_scalar_operation() {
3233            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
3234            let inertial_pos2 = inertial_pos1 * 2.0;
3235            assert_eq!(inertial_pos2.x(), 2.0);
3236            assert_eq!(inertial_pos2.y(), 4.0);
3237            assert_eq!(inertial_pos2.z(), 6.0);
3238        }
3239    }
3240    mod rotation {
3241        #[test]
3242        fn rotation_new() {
3243            let rotation = crate::api::Rotation::new();
3244            assert_eq!(rotation.roll(), 0.0);
3245            assert_eq!(rotation.pitch(), 0.0);
3246            assert_eq!(rotation.yaw(), 0.0);
3247        }
3248
3249        #[test]
3250        fn from_quat() {
3251            let quat = crate::math::Quaternion::new(1.0, 0.0, 0.0, 0.0);
3252            let rotation = crate::api::Rotation::from_quat(&quat);
3253            assert_eq!(rotation.roll(), 0.0);
3254            assert_eq!(rotation.pitch(), 0.0);
3255            assert_eq!(rotation.yaw(), 0.0);
3256        }
3257
3258        #[test]
3259        fn from_rpy() {
3260            let rpy = crate::math::RollPitchYaw::new(0.0, 0.0, 0.0);
3261            let rotation = crate::api::Rotation::from_rpy(&rpy);
3262            assert_eq!(rotation.roll(), 0.0);
3263            assert_eq!(rotation.pitch(), 0.0);
3264            assert_eq!(rotation.yaw(), 0.0);
3265        }
3266
3267        #[test]
3268        fn set_quat() {
3269            let mut rotation = crate::api::Rotation::new();
3270            let quat = crate::math::Quaternion::new(1.0, 0.0, 0.0, 0.0);
3271            rotation.set_quat(&quat);
3272            assert_eq!(rotation.roll(), 0.0);
3273            assert_eq!(rotation.pitch(), 0.0);
3274            assert_eq!(rotation.yaw(), 0.0);
3275        }
3276
3277        #[test]
3278        fn matrix() {
3279            let rotation = crate::api::Rotation::new();
3280            let matrix = rotation.matrix();
3281            assert_eq!(matrix.row(0), crate::math::Vector3::new(1.0, 0.0, 0.0));
3282            assert_eq!(matrix.row(1), crate::math::Vector3::new(0.0, 1.0, 0.0));
3283            assert_eq!(matrix.row(2), crate::math::Vector3::new(0.0, 0.0, 1.0));
3284        }
3285    }
3286
3287    mod s_range {
3288        #[test]
3289        fn s_range_new() {
3290            let s_range = crate::api::SRange::new(1.0, 2.0);
3291            assert_eq!(s_range.s0(), 1.0);
3292            assert_eq!(s_range.s1(), 2.0);
3293        }
3294        #[test]
3295        fn s_range_api() {
3296            let s_range_1 = crate::api::SRange::new(1.0, 3.0);
3297            let s_range_2 = crate::api::SRange::new(2.0, 4.0);
3298            assert_eq!(s_range_1.size(), 2.0);
3299            assert!(s_range_1.with_s());
3300            assert!(s_range_1.intersects(&s_range_2, 0.0));
3301            assert!(!s_range_1.contains(&s_range_2, 0.0));
3302        }
3303        #[test]
3304        fn s_range_setters() {
3305            let mut s_range = crate::api::SRange::new(0.0, 4.0);
3306            s_range.set_s0(1.0);
3307            s_range.set_s1(3.0);
3308            assert_eq!(s_range.s0(), 1.0);
3309            assert_eq!(s_range.s1(), 3.0);
3310        }
3311        #[test]
3312        fn s_range_get_intersection_with_intersection() {
3313            let s_range_1 = crate::api::SRange::new(1.0, 3.0);
3314            let s_range_2 = crate::api::SRange::new(2.0, 4.0);
3315            let intersection = s_range_1.get_intersection(&s_range_2, 0.0);
3316            assert!(intersection.is_some());
3317            let intersection = intersection.unwrap();
3318            assert_eq!(intersection.s0(), 2.0);
3319            assert_eq!(intersection.s1(), 3.0);
3320        }
3321        #[test]
3322        fn s_range_get_intersection_with_no_intersection() {
3323            let s_range_1 = crate::api::SRange::new(1.0, 2.0);
3324            let s_range_2 = crate::api::SRange::new(3.0, 4.0);
3325            let intersection = s_range_1.get_intersection(&s_range_2, 0.0);
3326            assert!(intersection.is_none());
3327        }
3328    }
3329
3330    mod lane_s_range {
3331        #[test]
3332        fn lane_s_range_new() {
3333            let lane_s_range =
3334                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(1.0, 2.0));
3335            assert_eq!(lane_s_range.lane_id(), "lane_test");
3336            assert_eq!(lane_s_range.s_range().s0(), 1.0);
3337            assert_eq!(lane_s_range.s_range().s1(), 2.0);
3338            assert_eq!(lane_s_range.length(), 1.0);
3339        }
3340        #[test]
3341        fn lane_s_range_api() {
3342            let lane_s_range_1 =
3343                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(1.0, 2.0));
3344            let lane_s_range_2 =
3345                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(2.0, 3.0));
3346            assert!(lane_s_range_1.intersects(&lane_s_range_2, 0.0));
3347            assert!(!lane_s_range_1.contains(&lane_s_range_2, 0.0));
3348        }
3349        #[test]
3350        fn lane_s_range_get_intersection_with_intersection() {
3351            let lane_s_range_1 =
3352                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(1.0, 3.0));
3353            let lane_s_range_2 =
3354                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(2.0, 4.0));
3355            let intersection = lane_s_range_1.get_intersection(&lane_s_range_2, 0.0);
3356            assert!(intersection.is_some());
3357            let intersection = intersection.unwrap();
3358            assert_eq!(intersection.lane_id(), "lane_test");
3359            assert_eq!(intersection.s_range().s0(), 2.0);
3360            assert_eq!(intersection.s_range().s1(), 3.0);
3361        }
3362        #[test]
3363        fn lane_s_range_get_intersection_with_no_intersection() {
3364            let lane_s_range_1 =
3365                crate::api::LaneSRange::new(&String::from("lane test_1"), &crate::api::SRange::new(1.0, 3.0));
3366            let lane_s_range_2 =
3367                crate::api::LaneSRange::new(&String::from("lane_test_2"), &crate::api::SRange::new(2.0, 4.0));
3368            let intersection = lane_s_range_1.get_intersection(&lane_s_range_2, 0.0);
3369            assert!(intersection.is_none());
3370        }
3371    }
3372
3373    mod lane_s_route {
3374        // Helper function to create a LaneSRoute
3375        // with two LaneSRange.
3376        // # Arguments
3377        // * `s0_0` - The s0 of the first LaneSRange.
3378        // * `s1_0` - The s1 of the first LaneSRange.
3379        // * `s0_1` - The s0 of the second LaneSRange.
3380        // * `s1_1` - The s1 of the second LaneSRange.
3381        fn _get_lane_s_route(s0_0: f64, s1_0: f64, s0_1: f64, s1_1: f64) -> crate::api::LaneSRoute {
3382            let ranges = vec![
3383                crate::api::LaneSRange::new(&String::from("lane_test_1"), &crate::api::SRange::new(s0_0, s1_0)),
3384                crate::api::LaneSRange::new(&String::from("lane_test_2"), &crate::api::SRange::new(s0_1, s1_1)),
3385            ];
3386            crate::api::LaneSRoute::new(ranges)
3387        }
3388        #[test]
3389        fn lane_s_route_new() {
3390            let lane_s_route = _get_lane_s_route(0., 10., 0., 15.);
3391            assert!(!lane_s_route.lane_s_route.is_null());
3392            let ranges = lane_s_route.ranges();
3393            assert_eq!(ranges.len(), 2);
3394            assert_eq!(ranges[0].lane_id(), "lane_test_1");
3395            assert_eq!(ranges[1].lane_id(), "lane_test_2");
3396        }
3397        #[test]
3398        fn lane_s_route_length() {
3399            let lane_s_route = _get_lane_s_route(0., 10., 0., 15.);
3400            assert_eq!(lane_s_route.length(), 25.0);
3401        }
3402        #[test]
3403        fn lane_s_route_intersects() {
3404            let lane_s_route = _get_lane_s_route(0., 10., 0., 10.);
3405            let lane_s_route_that_intersects = _get_lane_s_route(5., 9., 5., 9.);
3406            let lane_s_route_that_not_intersects = _get_lane_s_route(11., 20., 11., 20.);
3407            assert!(lane_s_route.intersects(&lane_s_route_that_intersects, 0.0));
3408            assert!(!lane_s_route.intersects(&lane_s_route_that_not_intersects, 0.0));
3409        }
3410    }
3411}