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/// Represents a complete Maliput road network.
40///
41/// A `RoadNetwork` is the main entry point for interacting with a road map in Maliput.
42/// It serves as a container for all the elements that describe a road network,
43/// including its physical layout and the rules of the road.
44///
45/// It provides access to the following key components:
46///
47/// * [`RoadGeometry`]: The geometric description of the road surfaces.
48/// * [`rules::RoadRulebook`]: The set of traffic rules, like speed limits and right-of-way.
49/// * [`rules::TrafficLightBook`]: A catalog of all traffic lights in the network.
50/// * [`IntersectionBook`]: A collection of logical intersections and their states.
51///   TODO: Complete with other books when available (e.g., `RuleRegistry / PhaseRingBook / etc)
52///
53/// More info can be found at https://maliput.readthedocs.io/en/latest/html/deps/maliput/html/maliput_design.html.
54///
55/// # Example
56///
57/// ```rust, no_run
58/// use maliput::api::RoadNetwork;
59/// use std::collections::HashMap;
60///
61/// // Properties to load an OpenDRIVE file using the "maliput_malidrive" backend.
62/// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
63/// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
64/// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
65///
66/// // Create the RoadNetwork by specifying the loader ID and properties.
67/// let road_network = RoadNetwork::new("maliput_malidrive", &road_network_properties).unwrap();
68/// ```
69pub struct RoadNetwork {
70    pub(crate) rn: cxx::UniquePtr<maliput_sys::api::ffi::RoadNetwork>,
71}
72
73impl RoadNetwork {
74    /// Create a new `RoadNetwork` with the given `road_network_loader_id` and `properties`.
75    ///
76    /// # Arguments
77    ///
78    /// * `road_network_loader_id` - The id of the road network loader. It identifies the backend to be used (e.g., "maliput_malidrive").
79    /// * `properties` - The properties of the road network.
80    ///
81    /// # Details
82    /// It relies on `maliput_sys::plugin::ffi::CreateRoadNetwork` to create a new `RoadNetwork`.
83    ///
84    /// # Returns
85    /// A result containing the `RoadNetwork` or a `MaliputError` if the creation fails.
86    pub fn new(
87        road_network_loader_id: &str,
88        properties: &std::collections::HashMap<&str, &str>,
89    ) -> Result<RoadNetwork, MaliputError> {
90        // Translate the properties to ffi types
91        let mut properties_vec = Vec::new();
92        for (key, value) in properties.iter() {
93            properties_vec.push(format!("{}:{}", key, value));
94        }
95        // If MALIPUT_PLUGIN_PATH is not set, it will be created.
96        let new_path = match std::env::var_os("MALIPUT_PLUGIN_PATH") {
97            Some(current_path) => {
98                // Add the maliput_malidrive plugin path obtained from maliput_sdk to MALIPUT_PLUGIN_PATH.
99                // This is added first in the list as the plugins are loaded sequentally and we
100                // want this to be used only when no others are present. (typically in dev mode).
101                let mut new_paths = vec![maliput_sdk::get_maliput_malidrive_plugin_path()];
102                new_paths.extend(std::env::split_paths(&current_path).collect::<Vec<_>>());
103                std::env::join_paths(new_paths).unwrap()
104            }
105            None => maliput_sdk::get_maliput_malidrive_plugin_path().into(),
106        };
107        std::env::set_var("MALIPUT_PLUGIN_PATH", new_path);
108        let rn = maliput_sys::plugin::ffi::CreateRoadNetwork(&road_network_loader_id.to_string(), &properties_vec)?;
109        Ok(RoadNetwork { rn })
110    }
111
112    /// Get the `RoadGeometry` of the `RoadNetwork`.
113    pub fn road_geometry(&self) -> RoadGeometry<'_> {
114        unsafe {
115            RoadGeometry {
116                rg: self.rn.road_geometry().as_ref().expect(""),
117            }
118        }
119    }
120    /// Get the `IntersectionBook` of the `RoadNetwork`.
121    pub fn intersection_book(&mut self) -> IntersectionBook<'_> {
122        let intersection_book_ffi = self
123            .rn
124            .as_mut()
125            .expect("Underlying RoadNetwork is null")
126            .intersection_book();
127        IntersectionBook {
128            intersection_book: unsafe {
129                intersection_book_ffi
130                    .as_mut()
131                    .expect("Underlying IntersectionBook is null")
132            },
133        }
134    }
135    /// Get the `TrafficLightBook` of the `RoadNetwork`.
136    pub fn traffic_light_book(&self) -> rules::TrafficLightBook<'_> {
137        let traffic_light_book_ffi = self.rn.traffic_light_book();
138        rules::TrafficLightBook {
139            traffic_light_book: unsafe {
140                traffic_light_book_ffi
141                    .as_ref()
142                    .expect("Underlying TrafficLightBook is null")
143            },
144        }
145    }
146    /// Get the `RoadRulebook` of the `RoadNetwork`.
147    pub fn rulebook(&self) -> rules::RoadRulebook<'_> {
148        let rulebook_ffi = self.rn.rulebook();
149        rules::RoadRulebook {
150            road_rulebook: unsafe { rulebook_ffi.as_ref().expect("Underlying RoadRulebook is null") },
151        }
152    }
153
154    /// Get the `PhaseRingBook` of the `RoadNetwork`.
155    pub fn phase_ring_book(&self) -> rules::PhaseRingBook<'_> {
156        let phase_ring_book_ffi = self.rn.phase_ring_book();
157        rules::PhaseRingBook {
158            phase_ring_book: unsafe { phase_ring_book_ffi.as_ref().expect("Underlying PhaseRingBook is null") },
159        }
160    }
161
162    /// Get the `RuleRegistry` of the `RoadNetwork`.
163    pub fn rule_registry(&self) -> rules::RuleRegistry<'_> {
164        let rule_registry_ffi = self.rn.rule_registry();
165        rules::RuleRegistry {
166            rule_registry: unsafe { rule_registry_ffi.as_ref().expect("Underlying RuleRegistry is null") },
167        }
168    }
169}
170
171/// Represents the geometry of a road network.
172///
173/// `RoadGeometry` is the top-level container for the road network's geometric
174/// description. It is composed of a set of `Junction`s, which in turn contain
175/// `Segment`s and `Lane`s.
176///
177/// It provides access to the entire road network's geometric structure,
178/// allowing for queries about its components (e.g., finding a `Lane` by its ID)
179/// and for coordinate conversions between the inertial frame and the road network's
180/// intrinsic coordinate systems (lane coordinates).
181///
182/// An instance of `RoadGeometry` is typically obtained from a `RoadNetwork`.
183///
184/// More info can be found at https://maliput.readthedocs.io/en/latest/html/deps/maliput/html/maliput_design.html.
185///
186/// # Example of obtaining a `RoadGeometry`
187///
188/// ```rust, no_run
189/// use maliput::api::RoadNetwork;
190/// use std::collections::HashMap;
191///
192/// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
193/// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
194/// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
195/// let road_network = RoadNetwork::new("maliput_malidrive", &road_network_properties).unwrap();
196/// let road_geometry = road_network.road_geometry();
197/// println!("RoadGeometry ID: {}", road_geometry.id());
198/// ```
199pub struct RoadGeometry<'a> {
200    rg: &'a maliput_sys::api::ffi::RoadGeometry,
201}
202
203impl<'a> RoadGeometry<'a> {
204    /// Returns the id of the RoadGeometry.
205    pub fn id(&self) -> String {
206        maliput_sys::api::ffi::RoadGeometry_id(self.rg)
207    }
208    /// Returns the number of Junctions in the RoadGeometry.
209    ///
210    /// Return value is non-negative.
211    pub fn num_junctions(&self) -> i32 {
212        self.rg.num_junctions()
213    }
214    /// Returns the tolerance guaranteed for linear measurements (positions).
215    pub fn linear_tolerance(&self) -> f64 {
216        self.rg.linear_tolerance()
217    }
218    /// Returns the tolerance guaranteed for angular measurements (orientations).
219    pub fn angular_tolerance(&self) -> f64 {
220        self.rg.angular_tolerance()
221    }
222    /// Returns the number of BranchPoints in the RoadGeometry.
223    ///
224    /// Return value is non-negative.
225    pub fn num_branch_points(&self) -> i32 {
226        self.rg.num_branch_points()
227    }
228    /// Determines the [RoadPosition] on the 3D road manifold that corresponds to
229    /// [InertialPosition] `inertial_position`.
230    ///
231    /// The [RoadGeometry]'s manifold is a 3D volume, with each point defined by (s, r, h)
232    /// coordinates. This method returns a [RoadPositionQuery]. Its [RoadPosition] is the
233    /// point in the [RoadGeometry]'s manifold which is, in the `Inertial`-frame, closest to
234    /// `inertial_position`. Its InertialPosition is the `Inertial`-frame equivalent of the
235    /// [RoadPosition] and its distance is the Cartesian distance from
236    /// `inertial_position` to the nearest point.
237    ///
238    /// This method guarantees that its result satisfies the condition that
239    /// `result.lane.to_lane_position(result.pos)` is within `linear_tolerance()`
240    /// of the returned [InertialPosition].
241    ///
242    /// The map from [RoadGeometry] to the `Inertial`-frame is not onto (as a bounded
243    /// [RoadGeometry] cannot completely cover the unbounded Cartesian universe).
244    /// If `inertial_position` does represent a point contained within the volume
245    /// of the RoadGeometry, then result distance is guaranteed to be less
246    /// than or equal to `linear_tolerance()`.
247    ///
248    /// The map from [RoadGeometry] to `Inertial`-frame is not necessarily one-to-one.
249    /// Different `(s,r,h)` coordinates from different Lanes, potentially from
250    /// different Segments, may map to the same `(x,y,z)` `Inertial`-frame location.
251    ///
252    /// If `inertial_position` is contained within the volumes of multiple Segments,
253    /// then to_road_position() will choose a [Segment] which yields the minimum
254    /// height `h` value in the result.  If the chosen [Segment] has multiple
255    /// Lanes, then to_road_position() will choose a [Lane] which contains
256    /// `inertial_position` within its `lane_bounds()` if possible, and if that is
257    /// still ambiguous, it will further select a [Lane] which minimizes the
258    /// absolute value of the lateral `r` coordinate in the result.
259    ///
260    /// # Arguments
261    /// * `inertial_position` - The [InertialPosition] to convert into a [RoadPosition].
262    ///
263    /// # Return
264    /// A [RoadPositionQuery] with the nearest [RoadPosition], the corresponding [InertialPosition]
265    /// to that [RoadPosition] and the distance between the input and output [InertialPosition]s.
266    pub fn to_road_position(&self, inertial_position: &InertialPosition) -> Result<RoadPositionQuery, MaliputError> {
267        let rpr = maliput_sys::api::ffi::RoadGeometry_ToRoadPosition(self.rg, &inertial_position.ip)?;
268        Ok(RoadPositionQuery {
269            road_position: RoadPosition {
270                rp: maliput_sys::api::ffi::RoadPositionResult_road_position(&rpr),
271            },
272            nearest_position: InertialPosition {
273                ip: maliput_sys::api::ffi::RoadPositionResult_nearest_position(&rpr),
274            },
275            distance: maliput_sys::api::ffi::RoadPositionResult_distance(&rpr),
276        })
277    }
278
279    /// Determines the [RoadPosition] on the road surface that corresponds to
280    /// [InertialPosition] `inertial_position`.
281    ///
282    /// This method is similar to [RoadGeometry::to_road_position], in a way that it determines if
283    /// `inertial_position` is within the [RoadGeometry]'s 3D volume. If it is, a [RoadPosition] is
284    /// returned where the height `h` is set to 0, effectively placing the point on the road
285    /// surface.
286    ///
287    /// # Arguments
288    /// * `inertial_position` - The [InertialPosition] to convert into a [RoadPosition].
289    ///
290    /// # Return
291    /// 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`).
292    ///
293    /// # Example
294    ///
295    /// ```rust, no_run
296    /// use maliput::api::{RoadNetwork, InertialPosition};
297    /// use std::collections::HashMap;
298    ///
299    /// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
300    /// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
301    /// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
302    /// let road_network = RoadNetwork::new("maliput_malidrive", &road_network_properties).unwrap();
303    /// let road_geometry = road_network.road_geometry();
304    ///
305    /// // Although this isn't directly on the surface, it is within the RoadGeometry volume.
306    /// let inertial_pos = InertialPosition::new(1.0, 0.0, 1.0);
307    /// let road_pos = road_geometry.to_road_position_surface(&inertial_pos);
308    /// assert!(road_pos.is_ok());
309    /// let road_pos = road_pos.unwrap();
310    /// println!("Road position on surface: s={}, r={}, h={}", road_pos.pos().s(), road_pos.pos().r(), road_pos.pos().h());
311    /// assert_eq!(road_pos.pos().s(), 1.0);
312    /// assert_eq!(road_pos.pos().r(), 0.0);
313    /// assert_eq!(road_pos.pos().h(), 0.0);  // h is set to 0.
314    ///
315    /// // An inertial position that is off the road volume.
316    /// let inertial_pos= InertialPosition::new(1.0, 0.0, 10.0);
317    /// let road_pos= road_geometry.to_road_position_surface(&inertial_pos);
318    /// assert!(road_pos.is_err());
319    /// ```
320    pub fn to_road_position_surface(&self, inertial_position: &InertialPosition) -> Result<RoadPosition, MaliputError> {
321        let rpr = maliput_sys::api::ffi::RoadGeometry_ToRoadPosition(self.rg, &inertial_position.ip)?;
322        let road_position = RoadPosition {
323            rp: maliput_sys::api::ffi::RoadPositionResult_road_position(&rpr),
324        };
325
326        let distance = maliput_sys::api::ffi::RoadPositionResult_distance(&rpr);
327        if distance > self.linear_tolerance() {
328            return Err(MaliputError::Other(format!(
329                "InertialPosition {} does not correspond to a RoadPosition. It is off by {}m to the closest lane {} at {}.",
330                maliput_sys::api::ffi::InertialPosition_to_str(&inertial_position.ip),
331                distance, road_position.lane().id(), road_position.pos())));
332        }
333
334        let lane_position =
335            maliput_sys::api::ffi::LanePosition_new(road_position.pos().s(), road_position.pos().r(), 0.);
336        unsafe {
337            Ok(RoadPosition {
338                rp: maliput_sys::api::ffi::RoadPosition_new(road_position.lane().lane, &lane_position),
339            })
340        }
341    }
342
343    /// Obtains all [RoadPosition]s within a radius of the inertial_position.
344    ///
345    /// Only Lanes whose segment regions include points that are within radius of
346    /// inertial position are included in the search. For each of these Lanes,
347    /// include the [RoadPosition] or [RoadPosition]s with the minimum distance to
348    /// inertial position in the returned result.
349    ///
350    /// # Arguments
351    ///
352    /// * `inertial_position` - The [InertialPosition] to search around.
353    /// * `radius` - The radius around the [InertialPosition] to search for [RoadPosition]s.
354    ///
355    /// # Return
356    ///
357    /// A vector of [RoadPositionQuery]s.
358    pub fn find_road_positions(
359        &self,
360        inertial_position: &InertialPosition,
361        radius: f64,
362    ) -> Result<Vec<RoadPositionQuery>, MaliputError> {
363        let positions = maliput_sys::api::ffi::RoadGeometry_FindRoadPositions(self.rg, &inertial_position.ip, radius)?;
364        Ok(positions
365            .iter()
366            .map(|rpr| RoadPositionQuery {
367                road_position: RoadPosition {
368                    rp: maliput_sys::api::ffi::RoadPositionResult_road_position(rpr),
369                },
370                nearest_position: InertialPosition {
371                    ip: maliput_sys::api::ffi::RoadPositionResult_nearest_position(rpr),
372                },
373                distance: maliput_sys::api::ffi::RoadPositionResult_distance(rpr),
374            })
375            .collect())
376    }
377
378    /// Get the lane matching given `lane_id`.
379    ///
380    /// # Arguments
381    /// * `lane_id` - The id of the lane.
382    ///
383    /// # Return
384    /// The lane with the given id.
385    /// If no lane is found with the given id, return None.
386    pub fn get_lane(&self, lane_id: &String) -> Option<Lane<'_>> {
387        let lane = maliput_sys::api::ffi::RoadGeometry_GetLane(self.rg, lane_id);
388        if lane.lane.is_null() {
389            return None;
390        }
391        Some(Lane {
392            lane: unsafe { lane.lane.as_ref().expect("") },
393        })
394    }
395    /// Get all lanes of the `RoadGeometry`.
396    /// Returns a vector of `Lane`.
397    /// # Example
398    /// ```rust, no_run
399    /// use maliput::api::RoadNetwork;
400    /// use std::collections::HashMap;
401    ///
402    /// let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
403    /// let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
404    /// let road_network_properties = HashMap::from([("road_geometry_id", "my_rg_from_rust"), ("opendrive_file", xodr_path.as_str())]);
405    /// let road_network = RoadNetwork::new("maliput_malidrive", &road_network_properties).unwrap();
406    /// let road_geometry = road_network.road_geometry();
407    /// let lanes = road_geometry.get_lanes();
408    /// for lane in lanes {
409    ///    println!("lane_id: {}", lane.id());
410    /// }
411    /// ```
412    pub fn get_lanes(&self) -> Vec<Lane<'_>> {
413        let lanes = maliput_sys::api::ffi::RoadGeometry_GetLanes(self.rg);
414        lanes
415            .into_iter()
416            .map(|l| Lane {
417                lane: unsafe { l.lane.as_ref().expect("") },
418            })
419            .collect::<Vec<Lane>>()
420    }
421    /// Get the segment matching given `segment_id`.
422    ///
423    /// # Arguments
424    /// * `segment_id` - The id of the segment.
425    ///
426    /// # Return
427    /// The segment with the given id.
428    /// If no segment is found with the given id, return None.
429    pub fn get_segment(&self, segment_id: &String) -> Option<Segment<'_>> {
430        let segment = maliput_sys::api::ffi::RoadGeometry_GetSegment(self.rg, segment_id);
431        if segment.is_null() {
432            return None;
433        }
434        unsafe {
435            Some(Segment {
436                segment: segment.as_ref().expect(""),
437            })
438        }
439    }
440    /// Get the junction matching given `junction_id`.
441    ///
442    /// # Arguments
443    /// * `junction_id` - The id of the junction.
444    ///
445    /// # Return
446    /// The junction with the given id.
447    /// If no junction is found with the given id, return None.
448    pub fn get_junction(&self, junction_id: &String) -> Option<Junction<'_>> {
449        let junction = maliput_sys::api::ffi::RoadGeometry_GetJunction(self.rg, junction_id);
450        if junction.is_null() {
451            return None;
452        }
453        unsafe {
454            Some(Junction {
455                junction: junction.as_ref().expect(""),
456            })
457        }
458    }
459    /// Get the branch point matching given `branch_point_id`.
460    ///
461    /// # Arguments
462    /// * `branch_point_id` - The id of the branch point.
463    ///
464    /// # Return
465    /// The branch point with the given id.
466    /// If no branch point is found with the given id, return None.
467    pub fn get_branch_point(&self, branch_point_id: &String) -> Option<BranchPoint<'_>> {
468        let branch_point = maliput_sys::api::ffi::RoadGeometry_GetBranchPoint(self.rg, branch_point_id);
469        if branch_point.is_null() {
470            return None;
471        }
472        unsafe {
473            Some(BranchPoint {
474                branch_point: branch_point.as_ref().expect(""),
475            })
476        }
477    }
478    /// Execute a custom command on the backend.
479    ///
480    /// # Details
481    /// 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
482    ///
483    /// # Arguments
484    /// * `command` - The command to execute.
485    ///
486    /// # Return
487    /// The result of the command.
488    // pub fn backend_custom_command(&self, command: &String) -> String {
489    pub fn backend_custom_command(&self, command: &String) -> Result<String, MaliputError> {
490        Ok(maliput_sys::api::ffi::RoadGeometry_BackendCustomCommand(
491            self.rg, command,
492        )?)
493    }
494    /// Obtains the Geo Reference info of this RoadGeometry.
495    ///
496    /// # Return
497    /// A string containing the Geo Reference projection, if any.
498    pub fn geo_reference_info(&self) -> String {
499        maliput_sys::api::ffi::RoadGeometry_GeoReferenceInfo(self.rg)
500    }
501}
502
503/// A 3-dimensional position in a `Lane`-frame, consisting of three components:
504///
505/// * s is longitudinal position, as arc-length along a Lane's reference line.
506/// * r is lateral position, perpendicular to the reference line at s. +r is to
507///   to the left when traveling in the direction of +s.
508/// * h is height above the road surface.
509///
510/// # Example
511///
512/// ```rust, no_run
513/// use maliput::api::LanePosition;
514///
515/// let lane_pos = LanePosition::new(1.0, 2.0, 3.0);
516/// println!("lane_pos = {}", lane_pos);
517/// assert_eq!(lane_pos.s(), 1.0);
518/// assert_eq!(lane_pos.r(), 2.0);
519/// assert_eq!(lane_pos.h(), 3.0);
520/// ```
521pub struct LanePosition {
522    lp: cxx::UniquePtr<maliput_sys::api::ffi::LanePosition>,
523}
524
525impl LanePosition {
526    /// Create a new `LanePosition` with the given `s`, `r`, and `h` components.
527    pub fn new(s: f64, r: f64, h: f64) -> LanePosition {
528        LanePosition {
529            lp: maliput_sys::api::ffi::LanePosition_new(s, r, h),
530        }
531    }
532    /// Get the `s` component of the `LanePosition`.
533    pub fn s(&self) -> f64 {
534        self.lp.s()
535    }
536    /// Get the `r` component of the `LanePosition`.
537    pub fn r(&self) -> f64 {
538        self.lp.r()
539    }
540    /// Get the `h` component of the `LanePosition`.
541    pub fn h(&self) -> f64 {
542        self.lp.h()
543    }
544
545    /// Returns all components as 3-vector `[s, r, h]`.
546    pub fn srh(&self) -> Vector3 {
547        let srh = self.lp.srh();
548        Vector3::new(srh.x(), srh.y(), srh.z())
549    }
550
551    /// Set the `s` component of the `LanePosition`.
552    pub fn set_s(&mut self, s: f64) {
553        self.lp.as_mut().expect("Underlying LanePosition is null").set_s(s);
554    }
555
556    /// Set the `r` component of the `LanePosition`.
557    pub fn set_r(&mut self, r: f64) {
558        self.lp.as_mut().expect("Underlying LanePosition is null").set_r(r);
559    }
560
561    /// Set the `h` component of the `LanePosition`.
562    pub fn set_h(&mut self, h: f64) {
563        self.lp.as_mut().expect("Underlying LanePosition is null").set_h(h);
564    }
565
566    /// Set all components from 3-vector `[s, r, h]`.
567    pub fn set_srh(&mut self, srh: &Vector3) {
568        let ffi_vec = maliput_sys::math::ffi::Vector3_new(srh.x(), srh.y(), srh.z());
569        self.lp
570            .as_mut()
571            .expect("Underlying LanePosition is null")
572            .set_srh(&ffi_vec);
573    }
574}
575
576impl PartialEq for LanePosition {
577    fn eq(&self, other: &Self) -> bool {
578        self.srh() == other.srh()
579    }
580}
581
582impl Eq for LanePosition {}
583
584impl std::fmt::Display for LanePosition {
585    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
586        write!(f, "{}", maliput_sys::api::ffi::LanePosition_to_str(&self.lp))
587    }
588}
589
590impl std::fmt::Debug for LanePosition {
591    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
592        f.debug_struct("LanePosition")
593            .field("s", &self.s())
594            .field("r", &self.r())
595            .field("h", &self.h())
596            .finish()
597    }
598}
599
600/// A position in 3-dimensional geographical Cartesian space, i.e., in the
601/// `Inertial`-frame, consisting of three components x, y, and z.
602///
603/// # Example
604///
605/// ```rust, no_run
606/// use maliput::api::InertialPosition;
607///
608/// let inertial_pos = InertialPosition::new(1.0, 2.0, 3.0);
609/// println!("inertial_pos = {}", inertial_pos);
610/// assert_eq!(inertial_pos.x(), 1.0);
611/// assert_eq!(inertial_pos.y(), 2.0);
612/// assert_eq!(inertial_pos.z(), 3.0);
613/// ```
614pub struct InertialPosition {
615    ip: cxx::UniquePtr<maliput_sys::api::ffi::InertialPosition>,
616}
617
618impl InertialPosition {
619    /// Create a new `InertialPosition` with the given `x`, `y`, and `z` components.
620    pub fn new(x: f64, y: f64, z: f64) -> InertialPosition {
621        InertialPosition {
622            ip: maliput_sys::api::ffi::InertialPosition_new(x, y, z),
623        }
624    }
625    /// Get the `x` component of the `InertialPosition`.
626    pub fn x(&self) -> f64 {
627        self.ip.x()
628    }
629    /// Get the `y` component of the `InertialPosition`.
630    pub fn y(&self) -> f64 {
631        self.ip.y()
632    }
633    /// Get the `z` component of the `InertialPosition`.
634    pub fn z(&self) -> f64 {
635        self.ip.z()
636    }
637
638    /// Returns all components as 3-vector `[x, y, z]`.
639    pub fn xyz(&self) -> Vector3 {
640        let xyz = self.ip.xyz();
641        Vector3::new(xyz.x(), xyz.y(), xyz.z())
642    }
643
644    /// Set the `x` component of the `InertialPosition`.
645    pub fn set_x(&mut self, x: f64) {
646        self.ip.as_mut().expect("Underlying InertialPosition is null").set_x(x);
647    }
648
649    /// Set the `y` component of the `InertialPosition`.
650    pub fn set_y(&mut self, y: f64) {
651        self.ip.as_mut().expect("Underlying InertialPosition is null").set_y(y);
652    }
653
654    /// Set the `z` component of the `InertialPosition`.
655    pub fn set_z(&mut self, z: f64) {
656        self.ip.as_mut().expect("Underlying InertialPosition is null").set_z(z);
657    }
658
659    /// Set all components from 3-vector `[x, y, z]`.
660    pub fn set_xyz(&mut self, xyz: &Vector3) {
661        let ffi_vec = maliput_sys::math::ffi::Vector3_new(xyz.x(), xyz.y(), xyz.z());
662        self.ip
663            .as_mut()
664            .expect("Underlying InertialPosition is null")
665            .set_xyz(&ffi_vec);
666    }
667
668    /// Get the length of `InertialPosition`.
669    pub fn length(&self) -> f64 {
670        self.ip.length()
671    }
672
673    /// Get the distance between two `InertialPosition`.
674    pub fn distance(&self, other: &InertialPosition) -> f64 {
675        self.ip.Distance(&other.ip)
676    }
677}
678
679impl PartialEq for InertialPosition {
680    fn eq(&self, other: &Self) -> bool {
681        maliput_sys::api::ffi::InertialPosition_operator_eq(&self.ip, &other.ip)
682    }
683}
684
685impl Eq for InertialPosition {}
686
687impl std::fmt::Display for InertialPosition {
688    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
689        write!(f, "{}", maliput_sys::api::ffi::InertialPosition_to_str(&self.ip))
690    }
691}
692
693impl std::fmt::Debug for InertialPosition {
694    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
695        f.debug_struct("InertialPosition")
696            .field("x", &self.x())
697            .field("y", &self.y())
698            .field("z", &self.z())
699            .finish()
700    }
701}
702
703impl std::ops::Add for InertialPosition {
704    type Output = InertialPosition;
705
706    fn add(self, other: InertialPosition) -> InertialPosition {
707        InertialPosition {
708            ip: maliput_sys::api::ffi::InertialPosition_operator_sum(&self.ip, &other.ip),
709        }
710    }
711}
712
713impl std::ops::Sub for InertialPosition {
714    type Output = InertialPosition;
715
716    fn sub(self, other: InertialPosition) -> InertialPosition {
717        InertialPosition {
718            ip: maliput_sys::api::ffi::InertialPosition_operator_sub(&self.ip, &other.ip),
719        }
720    }
721}
722
723impl std::ops::Mul<f64> for InertialPosition {
724    type Output = InertialPosition;
725
726    fn mul(self, scalar: f64) -> InertialPosition {
727        InertialPosition {
728            ip: maliput_sys::api::ffi::InertialPosition_operator_mul_scalar(&self.ip, scalar),
729        }
730    }
731}
732
733/// Bounds in the lateral dimension (r component) of a `Lane`-frame, consisting
734/// of a pair of minimum and maximum r value.  The bounds must straddle r = 0,
735/// i.e., the minimum must be <= 0 and the maximum must be >= 0.
736pub struct RBounds {
737    min: f64,
738    max: f64,
739}
740
741impl RBounds {
742    /// Create a new `RBounds` with the given `min` and `max` values.
743    pub fn new(min: f64, max: f64) -> RBounds {
744        RBounds { min, max }
745    }
746    /// Get the `min` value of the `RBounds`.
747    pub fn min(&self) -> f64 {
748        self.min
749    }
750    /// Get the `max` value of the `RBounds`.
751    pub fn max(&self) -> f64 {
752        self.max
753    }
754    /// Set the `min` value of the `RBounds`.
755    pub fn set_min(&mut self, min: f64) {
756        self.min = min;
757    }
758    /// Set the `max` value of the `RBounds`.
759    pub fn set_max(&mut self, max: f64) {
760        self.max = max;
761    }
762}
763
764/// Bounds in the elevation dimension (`h` component) of a `Lane`-frame,
765/// consisting of a pair of minimum and maximum `h` value.  The bounds
766/// must straddle `h = 0`, i.e., the minimum must be `<= 0` and the
767/// maximum must be `>= 0`.
768pub struct HBounds {
769    min: f64,
770    max: f64,
771}
772
773impl HBounds {
774    /// Create a new `HBounds` with the given `min` and `max` values.
775    pub fn new(min: f64, max: f64) -> HBounds {
776        HBounds { min, max }
777    }
778    /// Get the `min` value of the `HBounds`.
779    pub fn min(&self) -> f64 {
780        self.min
781    }
782    /// Get the `max` value of the `HBounds`.
783    pub fn max(&self) -> f64 {
784        self.max
785    }
786    /// Set the `min` value of the `HBounds`.
787    pub fn set_min(&mut self, min: f64) {
788        self.min = min;
789    }
790    /// Set the `max` value of the `HBounds`.
791    pub fn set_max(&mut self, max: f64) {
792        self.max = max;
793    }
794}
795
796/// Isometric velocity vector in a `Lane`-frame.
797///
798/// sigma_v, rho_v, and eta_v are the components of velocity in a
799/// (sigma, rho, eta) coordinate system.  (sigma, rho, eta) have the same
800/// orientation as the (s, r, h) at any given point in space, however they
801/// form an isometric system with a Cartesian distance metric.  Hence,
802/// IsoLaneVelocity represents a "real" physical velocity vector (albeit
803/// with an orientation relative to the road surface).
804#[derive(Default, Copy, Clone, Debug, PartialEq)]
805pub struct IsoLaneVelocity {
806    pub sigma_v: f64,
807    pub rho_v: f64,
808    pub eta_v: f64,
809}
810
811impl IsoLaneVelocity {
812    /// Create a new `IsoLaneVelocity` with the given `sigma_v`, `rho_v`, and `eta_v` components.
813    pub fn new(sigma_v: f64, rho_v: f64, eta_v: f64) -> IsoLaneVelocity {
814        IsoLaneVelocity { sigma_v, rho_v, eta_v }
815    }
816}
817
818/// A Lane represents a lane of travel in a road network.  A Lane defines
819/// a curvilinear coordinate system covering the road surface, with a
820/// longitudinal 's' coordinate that expresses the arc-length along a
821/// central reference curve.  The reference curve nominally represents
822/// an ideal travel trajectory along the Lane.
823///
824/// Lanes are grouped by Segment.  All Lanes belonging to a Segment
825/// represent the same road surface, but with different coordinate
826/// parameterizations (e.g., each Lane has its own reference curve).
827pub struct Lane<'a> {
828    lane: &'a maliput_sys::api::ffi::Lane,
829}
830
831impl<'a> Lane<'a> {
832    /// Returns the id of the Lane.
833    ///
834    /// The id is a unique identifier for the Lane within the RoadGeometry.
835    ///
836    /// # Returns
837    /// A `String` containing the id of the Lane.
838    pub fn id(&self) -> String {
839        maliput_sys::api::ffi::Lane_id(self.lane)
840    }
841    /// Returns the index of this Lane within the Segment which owns it.
842    pub fn index(&self) -> i32 {
843        self.lane.index()
844    }
845    /// Returns the Segment to which this Lane belongs.
846    ///
847    /// # Returns
848    /// A [`Segment`] containing the Segment to which this Lane belongs.
849    pub fn segment(&self) -> Segment<'a> {
850        unsafe {
851            Segment {
852                segment: self.lane.segment().as_ref().expect(""),
853            }
854        }
855    }
856    /// Returns the adjacent lane to the left, if one exists.
857    ///
858    /// "Left" is defined as the direction of `+r` in the `(s, r, h)` lane-coordinate frame.
859    ///
860    /// # Returns
861    ///
862    /// An [`Option<Lane>`] containing the left lane, or `None` if this is the
863    /// leftmost lane.
864    pub fn to_left(&self) -> Option<Lane<'_>> {
865        let lane = self.lane.to_left();
866        if lane.is_null() {
867            None
868        } else {
869            unsafe {
870                Some(Lane {
871                    lane: lane.as_ref().expect(""),
872                })
873            }
874        }
875    }
876    /// Returns the adjacent lane to the right, if one exists.
877    ///
878    /// "Right" is defined as the direction of `-r` in the `(s, r, h)` lane-coordinate
879    /// frame.
880    ///
881    /// # Returns
882    ///
883    /// An [`Option<Lane>`] containing the right lane, or `None` if this is the
884    /// rightmost lane.
885    pub fn to_right(&self) -> Option<Lane<'_>> {
886        let lane = self.lane.to_right();
887        if lane.is_null() {
888            None
889        } else {
890            unsafe {
891                Some(Lane {
892                    lane: lane.as_ref().expect(""),
893                })
894            }
895        }
896    }
897    /// Returns the arc-length of the Lane along its reference curve.
898    ///
899    /// The value of length() is also the maximum s-coordinate for this Lane;
900    /// i.e., the domain of s is [0, length()].
901    ///
902    /// # Returns
903    ///
904    /// The length of the Lane in meters.
905    pub fn length(&self) -> f64 {
906        self.lane.length()
907    }
908
909    /// Get the orientation of the `Lane` at the given `LanePosition`.
910    pub fn get_orientation(&self, lane_position: &LanePosition) -> Result<Rotation, MaliputError> {
911        Ok(Rotation {
912            r: maliput_sys::api::ffi::Lane_GetOrientation(self.lane, lane_position.lp.as_ref().expect(""))?,
913        })
914    }
915    /// # Brief
916    /// Get the [InertialPosition] of the [Lane] at the given [LanePosition].
917    ///
918    /// # Notes
919    /// Note there is no constraint for the `r` coordinate, as it can be outside the lane boundaries.
920    /// In that scenario, the resultant inertial position represents a point in the `s-r` plane at the given `s` and `h`
921    /// coordinates. It's on the user side to verify, if needed, that the lane position is within lane boundaries.
922    /// Bare in mind that the inertial position will be a point in the `s-r` plane, but *not* necessarily on the road surface.
923    ///
924    /// # Arguments
925    /// * `lane_position` - A maliput [LanePosition].
926    ///
927    /// # Precondition
928    /// The s component of `lane_position` must be in domain [0, Lane::length()].
929    ///
930    /// # Return
931    /// The [InertialPosition] corresponding to the input [LanePosition].
932    pub fn to_inertial_position(&self, lane_position: &LanePosition) -> Result<InertialPosition, MaliputError> {
933        Ok(InertialPosition {
934            ip: maliput_sys::api::ffi::Lane_ToInertialPosition(self.lane, lane_position.lp.as_ref().expect(""))?,
935        })
936    }
937    /// Determines the LanePosition corresponding to InertialPosition `inertial_position`.
938    /// The LanePosition is expected to be contained within the lane's 3D boundaries (s, r, h).
939    /// See [Lane::to_segment_position] method.
940    ///
941    /// This method guarantees that its result satisfies the condition that
942    /// `to_inertial_position(result.lane_position)` is within `linear_tolerance()`
943    ///  of `result.nearest_position`.
944    ///
945    /// # Arguments
946    /// * `inertial_position` - A [InertialPosition] to get a [LanePosition] from.
947    ///
948    /// # Return
949    /// A [LanePositionQuery] with the closest [LanePosition], the corresponding [InertialPosition] to that [LanePosition]
950    /// and the distance between the input and output [InertialPosition]s.
951    pub fn to_lane_position(&self, inertial_position: &InertialPosition) -> Result<LanePositionQuery, MaliputError> {
952        let lpr = maliput_sys::api::ffi::Lane_ToLanePosition(self.lane, inertial_position.ip.as_ref().expect(""))?;
953        Ok(LanePositionQuery {
954            lane_position: LanePosition {
955                lp: maliput_sys::api::ffi::LanePositionResult_road_position(&lpr),
956            },
957            nearest_position: InertialPosition {
958                ip: maliput_sys::api::ffi::LanePositionResult_nearest_position(&lpr),
959            },
960            distance: maliput_sys::api::ffi::LanePositionResult_distance(&lpr),
961        })
962    }
963    /// Determines the [LanePosition] corresponding to [InertialPosition] `inertial_position`.
964    /// The [LanePosition] is expected to be contained within the segment's 3D boundaries (s, r, h).
965    /// See [Lane::to_lane_position] method.
966    ///
967    /// This method guarantees that its result satisfies the condition that
968    /// `to_inertial_position(result.lane_position)` is within `linear_tolerance()`
969    ///  of `result.nearest_position`.
970    ///
971    /// # Arguments
972    /// * `inertial_position` - A [InertialPosition] to get a SegmentPosition from.
973    ///
974    /// # Return
975    /// A [LanePositionQuery] with the closest [LanePosition] within the segment, the corresponding
976    /// [InertialPosition] to that [LanePosition] and the distance between the input and output
977    /// [InertialPosition]s.
978    pub fn to_segment_position(&self, inertial_position: &InertialPosition) -> Result<LanePositionQuery, MaliputError> {
979        let spr = maliput_sys::api::ffi::Lane_ToSegmentPosition(self.lane, inertial_position.ip.as_ref().expect(""))?;
980        Ok(LanePositionQuery {
981            lane_position: LanePosition {
982                lp: maliput_sys::api::ffi::LanePositionResult_road_position(&spr),
983            },
984            nearest_position: InertialPosition {
985                ip: maliput_sys::api::ffi::LanePositionResult_nearest_position(&spr),
986            },
987            distance: maliput_sys::api::ffi::LanePositionResult_distance(&spr),
988        })
989    }
990    /// Returns the nominal lateral (r) bounds for the lane as a function of s.
991    ///
992    /// These are the lateral bounds for a position that is considered to be
993    /// "staying in the lane".
994    ///
995    /// See also [Lane::segment_bounds] that defines the whole surface.
996    ///
997    /// # Arguments
998    /// * `s` - The longitudinal position along the lane's reference line.
999    ///
1000    /// # Returns
1001    /// A [RBounds] containing the lateral bounds of the lane at the given `s.
1002    ///
1003    /// # Errors
1004    /// If lane bounds cannot be computed, an error is returned. This can happen if the
1005    /// `s` value is out of bounds (i.e., not in the range [0, Lane::length()]).
1006    pub fn lane_bounds(&self, s: f64) -> Result<RBounds, MaliputError> {
1007        let bounds = maliput_sys::api::ffi::Lane_lane_bounds(self.lane, s)?;
1008        Ok(RBounds::new(bounds.min(), bounds.max()))
1009    }
1010    /// Returns the lateral segment (r) bounds of the lane as a function of s.
1011    ///
1012    /// These are the lateral bounds for a position that is considered to be
1013    /// "on segment", reflecting the physical extent of the surface of the
1014    /// lane's segment.
1015    ///
1016    /// See also [Lane::lane_bounds] that defines what's considered to be "staying
1017    /// in the lane".
1018    ///
1019    /// # Arguments
1020    /// * `s` - The longitudinal position along the lane's reference line.
1021    ///
1022    /// # Returns
1023    /// A [RBounds] containing the lateral segment bounds of the lane at the given `
1024    /// s`.
1025    ///
1026    /// # Errors
1027    /// If segment bounds cannot be computed, an error is returned. This can happen if the
1028    /// `s` value is out of bounds (i.e., not in the range [0, Lane::length()]).
1029    pub fn segment_bounds(&self, s: f64) -> Result<RBounds, MaliputError> {
1030        let bounds = maliput_sys::api::ffi::Lane_segment_bounds(self.lane, s)?;
1031        Ok(RBounds::new(bounds.min(), bounds.max()))
1032    }
1033    /// Returns the elevation (`h`) bounds of the lane as a function of `(s, r)`.
1034    ///
1035    /// These are the elevation bounds for a position that is considered to be
1036    /// within the Lane's volume modeled by the RoadGeometry.
1037    ///
1038    /// `s` is within [0, `length()`] of this Lane and `r` is within
1039    /// `lane_bounds(s)`.
1040    ///
1041    /// # Arguments
1042    /// * `s` - The longitudinal position along the lane's reference line.
1043    /// * `r` - The lateral position perpendicular to the reference line at `s`.
1044    ///
1045    /// # Returns
1046    /// A [HBounds] containing the elevation bounds of the lane at the given `(s, r)`.
1047    ///
1048    /// # Errors
1049    /// If elevation bounds cannot be computed, an error is returned. This can happen if the
1050    /// `s` value is out of bounds (i.e., not in the range [0, Lane::length()]) or if `r` is not within the
1051    /// lane bounds at `s`.
1052    pub fn elevation_bounds(&self, s: f64, r: f64) -> Result<HBounds, MaliputError> {
1053        let bounds = maliput_sys::api::ffi::Lane_elevation_bounds(self.lane, s, r)?;
1054        Ok(HBounds::new(bounds.min(), bounds.max()))
1055    }
1056    /// Computes derivatives of [LanePosition] given a velocity vector `velocity`.
1057    /// `velocity` is a isometric velocity vector oriented in the `Lane`-frame
1058    /// at `position`.
1059    ///
1060    /// # Arguments
1061    /// * `lane_position` - A [LanePosition] at which to evaluate the derivatives.
1062    /// * `velocity` - An [IsoLaneVelocity] representing the velocity vector in the `Lane`-frame
1063    ///   at `lane_position`.
1064    ///
1065    /// # Returns
1066    /// Returns `Lane`-frame derivatives packed into a [LanePosition] struct.
1067    pub fn eval_motion_derivatives(&self, lane_position: &LanePosition, velocity: &IsoLaneVelocity) -> LanePosition {
1068        LanePosition {
1069            lp: maliput_sys::api::ffi::Lane_EvalMotionDerivatives(
1070                self.lane,
1071                lane_position.lp.as_ref().expect(""),
1072                velocity.sigma_v,
1073                velocity.rho_v,
1074                velocity.eta_v,
1075            ),
1076        }
1077    }
1078    /// Returns the lane's [BranchPoint] for the specified end.
1079    ///
1080    /// # Argument
1081    /// * `end` - This lane's start or end [LaneEnd].
1082    ///
1083    /// # Return
1084    /// The lane's [BranchPoint] for the specified end.
1085    pub fn get_branch_point(&self, end: &LaneEnd) -> Result<BranchPoint<'_>, MaliputError> {
1086        if end != &LaneEnd::Start(self.clone()) && end != &LaneEnd::Finish(self.clone()) {
1087            return Err(MaliputError::AssertionError(format!(
1088                "LaneEnd must be an end of this lane {:?}",
1089                end
1090            )));
1091        }
1092        Ok(BranchPoint {
1093            branch_point: unsafe {
1094                maliput_sys::api::ffi::Lane_GetBranchPoint(self.lane, end == &LaneEnd::Start(self.clone()))
1095                    .as_ref()
1096                    .expect("Underlying BranchPoint is null")
1097            },
1098        })
1099    }
1100    /// Returns the set of [LaneEnd]'s which connect with this lane on the
1101    /// same side of the [BranchPoint] at `end`. At a minimum,
1102    /// this set will include this [Lane].
1103    ///
1104    /// # Arguments
1105    /// * `end` - This lane's start or end [LaneEnd].
1106    ///
1107    /// # Return
1108    /// A [LaneEndSet] with all the [LaneEnd]s at the same side of the [BranchPoint] at `end`.
1109    pub fn get_confluent_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
1110        if end != &LaneEnd::Start(self.clone()) && end != &LaneEnd::Finish(self.clone()) {
1111            return Err(MaliputError::AssertionError(format!(
1112                "LaneEnd must be an end of this lane {:?}",
1113                end
1114            )));
1115        }
1116        Ok(LaneEndSet {
1117            lane_end_set: unsafe {
1118                maliput_sys::api::ffi::Lane_GetConfluentBranches(self.lane, end == &LaneEnd::Start(self.clone()))?
1119                    .as_ref()
1120                    .expect("Underlying LaneEndSet is null")
1121            },
1122        })
1123    }
1124    /// Returns the set of [LaneEnd]s which continue onward from this lane at the
1125    /// [BranchPoint] at `end`.
1126    ///
1127    /// # Arguments
1128    /// * `end` - This lane's start or end [LaneEnd].
1129    ///
1130    /// # Return
1131    /// A [LaneEndSet] with all the [LaneEnd]s at the opposite side of the [BranchPoint] at `end`.
1132    pub fn get_ongoing_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
1133        if end != &LaneEnd::Start(self.clone()) && end != &LaneEnd::Finish(self.clone()) {
1134            return Err(MaliputError::AssertionError(format!(
1135                "LaneEnd must be an end of this lane {:?}",
1136                end
1137            )));
1138        }
1139        Ok(LaneEndSet {
1140            lane_end_set: unsafe {
1141                maliput_sys::api::ffi::Lane_GetOngoingBranches(self.lane, end == &LaneEnd::Start(self.clone()))?
1142                    .as_ref()
1143                    .expect("Underlying LaneEndSet is null")
1144            },
1145        })
1146    }
1147    /// Returns the default ongoing LaneEnd connected at `end`,
1148    /// or None if no default branch has been established.
1149    ///
1150    /// # Arguments
1151    /// * `end` - This lane's start or end [LaneEnd].
1152    ///
1153    /// # Return
1154    /// An `Option<LaneEnd>` containing the default branch if it exists, or None
1155    /// if no default branch has been established.
1156    pub fn get_default_branch(&self, end: &LaneEnd) -> Option<LaneEnd<'_>> {
1157        assert! {
1158            end == &LaneEnd::Start(self.clone()) || end == &LaneEnd::Finish(self.clone()),
1159            "LaneEnd must be an end of this lane {:?}",
1160           end
1161        }
1162        let lane_end = maliput_sys::api::ffi::Lane_GetDefaultBranch(self.lane, end == &LaneEnd::Start(self.clone()));
1163        match lane_end.is_null() {
1164            true => None,
1165            false => {
1166                let lane_end_ref: &maliput_sys::api::ffi::LaneEnd =
1167                    lane_end.as_ref().expect("Underlying LaneEnd is null");
1168                let is_start = maliput_sys::api::ffi::LaneEnd_is_start(lane_end_ref);
1169                let lane_ref = unsafe {
1170                    maliput_sys::api::ffi::LaneEnd_lane(lane_end_ref)
1171                        .as_ref()
1172                        .expect("Underlying LaneEnd is null")
1173                };
1174                match is_start {
1175                    true => Some(LaneEnd::Start(Lane { lane: lane_ref })),
1176                    false => Some(LaneEnd::Finish(Lane { lane: lane_ref })),
1177                }
1178            }
1179        }
1180    }
1181    /// Evaluates if the `Lane` contains the given `LanePosition`.
1182    ///
1183    /// # Arguments
1184    /// * `lane_position` - A [LanePosition] to check if it is contained within the `Lane`.
1185    ///
1186    /// # Returns
1187    /// A boolean indicating whether the `Lane` contains the `LanePosition`.
1188    pub fn contains(&self, lane_position: &LanePosition) -> bool {
1189        self.lane.Contains(lane_position.lp.as_ref().expect(""))
1190    }
1191}
1192
1193/// Copy trait for Lane.
1194/// A reference to the Lane is copied.
1195impl Clone for Lane<'_> {
1196    fn clone(&self) -> Self {
1197        Lane { lane: self.lane }
1198    }
1199}
1200
1201/// A Segment represents a bundle of adjacent Lanes which share a
1202/// continuously traversable road surface. Every [LanePosition] on a
1203/// given [Lane] of a Segment has a corresponding [LanePosition] on each
1204/// other [Lane], all with the same height-above-surface h, that all
1205/// map to the same GeoPoint in 3-space.
1206///
1207/// Segments are grouped by [Junction].
1208pub struct Segment<'a> {
1209    segment: &'a maliput_sys::api::ffi::Segment,
1210}
1211
1212impl<'a> Segment<'a> {
1213    /// Returns the id of the Segment.
1214    /// The id is a unique identifier for the Segment within the RoadGeometry.
1215    ///
1216    /// # Returns
1217    /// A `String` containing the id of the Segment.
1218    pub fn id(&self) -> String {
1219        maliput_sys::api::ffi::Segment_id(self.segment)
1220    }
1221    /// Returns the [Junction] to which this Segment belongs.
1222    ///
1223    /// # Returns
1224    /// An [`Result<Junction, MaliputError>`] containing the Junction to which this Segment belongs.
1225    /// If the Segment does not belong to a Junction, an error is returned.
1226    pub fn junction(&self) -> Result<Junction<'_>, MaliputError> {
1227        let junction = self.segment.junction()?;
1228        if junction.is_null() {
1229            return Err(MaliputError::AssertionError(
1230                "Segment does not belong to a Junction".to_string(),
1231            ));
1232        }
1233        unsafe {
1234            Ok(Junction {
1235                junction: junction.as_ref().expect(""),
1236            })
1237        }
1238    }
1239    /// Returns the number of lanes in the Segment.
1240    ///
1241    /// # Returns
1242    /// The number of lanes in the Segment.
1243    pub fn num_lanes(&self) -> i32 {
1244        self.segment.num_lanes()
1245    }
1246    /// Returns the lane at the given `index`.
1247    ///
1248    /// # Arguments
1249    /// * `index` - The index of the lane to retrieve.
1250    ///
1251    /// # Returns
1252    /// A [`Lane`] containing the lane at the given index.
1253    pub fn lane(&self, index: i32) -> Result<Lane<'_>, MaliputError> {
1254        if index < 0 || index >= self.num_lanes() {
1255            return Err(MaliputError::AssertionError(format!(
1256                "Index {} is out of bounds for Segment with {} lanes",
1257                index,
1258                self.num_lanes()
1259            )));
1260        }
1261        let lane = self.segment.lane(index)?;
1262        unsafe {
1263            Ok(Lane {
1264                lane: lane.as_ref().expect(""),
1265            })
1266        }
1267    }
1268}
1269
1270/// A Junction is a closed set of [Segment]s which have physically
1271/// coplanar road surfaces, in the sense that [RoadPosition]s with the
1272/// same h value (height above surface) in the domains of two [Segment]s
1273/// map to the same [InertialPosition].  The [Segment]s need not be directly
1274/// connected to one another in the network topology.
1275///
1276/// Junctions are grouped by [RoadGeometry].
1277pub struct Junction<'a> {
1278    junction: &'a maliput_sys::api::ffi::Junction,
1279}
1280
1281impl<'a> Junction<'a> {
1282    /// Returns the id of the Junction.
1283    /// The id is a unique identifier for the Junction within the RoadGeometry.
1284    ///
1285    /// # Returns
1286    /// A `String` containing the id of the Junction.
1287    pub fn id(&self) -> String {
1288        maliput_sys::api::ffi::Junction_id(self.junction)
1289    }
1290    /// Returns the [RoadGeometry] to which this Junction belongs.
1291    ///
1292    /// # Returns
1293    /// A [`RoadGeometry`] containing the RoadGeometry to which this Junction belongs.
1294    pub fn road_geometry(&self) -> RoadGeometry<'_> {
1295        unsafe {
1296            RoadGeometry {
1297                rg: self.junction.road_geometry().as_ref().expect(""),
1298            }
1299        }
1300    }
1301    /// Returns the number of segments in the Junction.
1302    ///
1303    /// # Returns
1304    /// The number of segments in the Junction.
1305    pub fn num_segments(&self) -> i32 {
1306        self.junction.num_segments()
1307    }
1308    /// Returns the segment at the given `index`.
1309    ///
1310    /// # Arguments
1311    /// * `index` - The index of the segment to retrieve.
1312    ///
1313    /// # Returns
1314    /// A [Result<Segment, MaliputError>] containing the segment at the given index.
1315    /// If the index is out of bounds, an error is returned.
1316    pub fn segment(&self, index: i32) -> Result<Segment<'_>, MaliputError> {
1317        unsafe {
1318            Ok(Segment {
1319                segment: self.junction.segment(index)?.as_ref().expect(""),
1320            })
1321        }
1322    }
1323}
1324
1325/// A position in the road network compound by a specific lane and a lane-frame position in that lane.
1326/// This position is defined by a [Lane] and a [LanePosition].
1327pub struct RoadPosition {
1328    rp: cxx::UniquePtr<maliput_sys::api::ffi::RoadPosition>,
1329}
1330
1331impl RoadPosition {
1332    /// Create a new `RoadPosition` with the given `lane` and `lane_pos`.
1333    ///
1334    /// # Arguments
1335    /// * `lane` - A reference to a [Lane] that this `RoadPosition` is associated with.
1336    /// * `lane_pos` - A reference to a [LanePosition] that defines the position within the lane.
1337    ///
1338    /// # Returns
1339    /// A new `RoadPosition` instance.
1340    pub fn new(lane: &Lane, lane_pos: &LanePosition) -> RoadPosition {
1341        unsafe {
1342            RoadPosition {
1343                rp: maliput_sys::api::ffi::RoadPosition_new(lane.lane, &lane_pos.lp),
1344            }
1345        }
1346    }
1347    /// Computes the [InertialPosition] corresponding to this `RoadPosition`.
1348    ///
1349    /// # Notes
1350    /// This is an indirection to [Lane::to_inertial_position] method.
1351    ///
1352    /// # Returns
1353    /// An [InertialPosition] corresponding to this `RoadPosition`.
1354    pub fn to_inertial_position(&self) -> Result<InertialPosition, MaliputError> {
1355        Ok(InertialPosition {
1356            ip: maliput_sys::api::ffi::RoadPosition_ToInertialPosition(&self.rp)?,
1357        })
1358    }
1359    /// Gets the [Lane] associated with this `RoadPosition`.
1360    ///
1361    /// # Returns
1362    /// A [Lane] that this `RoadPosition` is associated with.
1363    pub fn lane(&self) -> Lane<'_> {
1364        unsafe {
1365            Lane {
1366                lane: maliput_sys::api::ffi::RoadPosition_lane(&self.rp).as_ref().expect(""),
1367            }
1368        }
1369    }
1370    /// Gets the [LanePosition] associated with this `RoadPosition`.
1371    ///
1372    /// # Returns
1373    /// A [LanePosition] that defines the position within the lane for this `RoadPosition`.
1374    pub fn pos(&self) -> LanePosition {
1375        LanePosition {
1376            lp: maliput_sys::api::ffi::RoadPosition_pos(&self.rp),
1377        }
1378    }
1379}
1380
1381/// Represents the result of a RoadPosition query.
1382/// This struct contains the `RoadPosition`, the nearest `InertialPosition` to that `RoadPosition`,
1383/// and the distance between the input `InertialPosition` and the nearest `InertialPosition`.
1384///
1385/// This struct is typically used as return type for the methods: [RoadGeometry::to_road_position] and [RoadGeometry::find_road_positions].
1386pub struct RoadPositionQuery {
1387    /// The candidate RoadPosition returned by the query.
1388    pub road_position: RoadPosition,
1389    /// The nearest InertialPosition to the candidate RoadPosition.
1390    /// This is the position in the inertial frame that is closest to the candidate RoadPosition
1391    pub nearest_position: InertialPosition,
1392    /// The distance between the input InertialPosition and the nearest InertialPosition.
1393    pub distance: f64,
1394}
1395
1396impl RoadPositionQuery {
1397    /// Create a new `RoadPositionQuery` with the given `road_position`, `nearest_position`, and `distance`.
1398    pub fn new(road_position: RoadPosition, nearest_position: InertialPosition, distance: f64) -> RoadPositionQuery {
1399        RoadPositionQuery {
1400            road_position,
1401            nearest_position,
1402            distance,
1403        }
1404    }
1405}
1406
1407/// Represents the result of a LanePosition query.
1408/// This struct contains the `LanePosition`, the nearest `InertialPosition` to that `LanePosition`,
1409/// and the distance between the input `InertialPosition` and the nearest `InertialPosition`.
1410///
1411/// This struct is typically used as return type for the methods: [Lane::to_lane_position] and [Lane::to_segment_position].
1412pub struct LanePositionQuery {
1413    /// The candidate LanePosition within the Lane' lane-bounds or segment-bounds
1414    /// depending if [Lane::to_lane_position] or [Lane::to_segment_position] respectively, was called.
1415    /// The LanePosition is closest to a `inertial_position` supplied to [Lane::to_lane_position]
1416    /// (measured by the Cartesian metric in the `Inertial`-frame).
1417    pub lane_position: LanePosition,
1418    /// The position that exactly corresponds to `lane_position`.
1419    pub nearest_position: InertialPosition,
1420    /// The Cartesian distance between `nearest_position` and the
1421    /// `inertial_position` supplied to [Lane::to_lane_position] / [Lane::to_segment_position].
1422    pub distance: f64,
1423}
1424
1425impl LanePositionQuery {
1426    /// Create a new `LanePositionQuery` with the given `lane_position`, `nearest_position`, and `distance`.
1427    pub fn new(lane_position: LanePosition, nearest_position: InertialPosition, distance: f64) -> LanePositionQuery {
1428        LanePositionQuery {
1429            lane_position,
1430            nearest_position,
1431            distance,
1432        }
1433    }
1434}
1435
1436/// A 3-dimensional rotation in the road network.
1437/// This struct represents a rotation in the road network, which can be defined
1438/// using a quaternion or roll-pitch-yaw angles.
1439/// It provides methods to create a rotation, convert between representations,
1440/// and apply the rotation to an inertial position.
1441pub struct Rotation {
1442    r: cxx::UniquePtr<maliput_sys::api::ffi::Rotation>,
1443}
1444
1445impl Default for Rotation {
1446    fn default() -> Self {
1447        Self::new()
1448    }
1449}
1450
1451impl Rotation {
1452    /// Create a new `Rotation`.
1453    pub fn new() -> Rotation {
1454        Rotation {
1455            r: maliput_sys::api::ffi::Rotation_new(),
1456        }
1457    }
1458    /// Create a new `Rotation` from a `Quaternion`.
1459    pub fn from_quat(q: &Quaternion) -> Rotation {
1460        let q_ffi = maliput_sys::math::ffi::Quaternion_new(q.w(), q.x(), q.y(), q.z());
1461        Rotation {
1462            r: maliput_sys::api::ffi::Rotation_from_quat(&q_ffi),
1463        }
1464    }
1465    /// Create a new `Rotation` from a `RollPitchYaw`.
1466    pub fn from_rpy(rpy: &RollPitchYaw) -> Rotation {
1467        let rpy_ffi = maliput_sys::math::ffi::RollPitchYaw_new(rpy.roll_angle(), rpy.pitch_angle(), rpy.yaw_angle());
1468        Rotation {
1469            r: maliput_sys::api::ffi::Rotation_from_rpy(&rpy_ffi),
1470        }
1471    }
1472    /// Get the roll of the `Rotation`.
1473    pub fn roll(&self) -> f64 {
1474        self.r.roll()
1475    }
1476    /// Get the pitch of the `Rotation`.
1477    pub fn pitch(&self) -> f64 {
1478        self.r.pitch()
1479    }
1480    /// Get the yaw of the `Rotation`.
1481    pub fn yaw(&self) -> f64 {
1482        self.r.yaw()
1483    }
1484    /// Get a quaternion representation of the `Rotation`.
1485    pub fn quat(&self) -> Quaternion {
1486        let q_ffi = self.r.quat();
1487        Quaternion::new(q_ffi.w(), q_ffi.x(), q_ffi.y(), q_ffi.z())
1488    }
1489    /// Get a roll-pitch-yaw representation of the `Rotation`.
1490    pub fn rpy(&self) -> RollPitchYaw {
1491        let rpy_ffi = maliput_sys::api::ffi::Rotation_rpy(&self.r);
1492        RollPitchYaw::new(rpy_ffi.roll_angle(), rpy_ffi.pitch_angle(), rpy_ffi.yaw_angle())
1493    }
1494    /// Set the `Rotation` from a `Quaternion`.
1495    pub fn set_quat(&mut self, q: &Quaternion) {
1496        let q_ffi = maliput_sys::math::ffi::Quaternion_new(q.w(), q.x(), q.y(), q.z());
1497        maliput_sys::api::ffi::Rotation_set_quat(self.r.pin_mut(), &q_ffi);
1498    }
1499    /// Get the matrix representation of the `Rotation`.
1500    pub fn matrix(&self) -> Matrix3 {
1501        let matrix_ffi: cxx::UniquePtr<maliput_sys::math::ffi::Matrix3> =
1502            maliput_sys::api::ffi::Rotation_matrix(&self.r);
1503        let row_0 = maliput_sys::math::ffi::Matrix3_row(matrix_ffi.as_ref().expect(""), 0);
1504        let row_1 = maliput_sys::math::ffi::Matrix3_row(matrix_ffi.as_ref().expect(""), 1);
1505        let row_2 = maliput_sys::math::ffi::Matrix3_row(matrix_ffi.as_ref().expect(""), 2);
1506        Matrix3::new(
1507            Vector3::new(row_0.x(), row_0.y(), row_0.z()),
1508            Vector3::new(row_1.x(), row_1.y(), row_1.z()),
1509            Vector3::new(row_2.x(), row_2.y(), row_2.z()),
1510        )
1511    }
1512    /// Get the distance between two `Rotation`.
1513    pub fn distance(&self, other: &Rotation) -> f64 {
1514        self.r.Distance(&other.r)
1515    }
1516    /// Apply the `Rotation` to an `InertialPosition`.
1517    pub fn apply(&self, v: &InertialPosition) -> InertialPosition {
1518        InertialPosition {
1519            ip: maliput_sys::api::ffi::Rotation_Apply(&self.r, &v.ip),
1520        }
1521    }
1522    /// Get the reverse of the `Rotation`.
1523    pub fn reverse(&self) -> Rotation {
1524        Rotation {
1525            r: maliput_sys::api::ffi::Rotation_Reverse(&self.r),
1526        }
1527    }
1528}
1529
1530/// Directed, inclusive longitudinal (s value) range from s0 to s1.
1531pub struct SRange {
1532    s_range: cxx::UniquePtr<maliput_sys::api::ffi::SRange>,
1533}
1534
1535impl SRange {
1536    /// Creates a new `SRange` with the given `s0` and `s1`.
1537    ///
1538    /// # Arguments
1539    /// * `s0` - The starting value of the range.
1540    /// * `s1` - The ending value of the range.
1541    ///
1542    /// # Returns
1543    /// A new `SRange` instance.
1544    pub fn new(s0: f64, s1: f64) -> SRange {
1545        SRange {
1546            s_range: maliput_sys::api::ffi::SRange_new(s0, s1),
1547        }
1548    }
1549    /// Returns the s0 of the `SRange`.
1550    ///
1551    /// # Returns
1552    /// The starting value of the range.
1553    pub fn s0(&self) -> f64 {
1554        self.s_range.s0()
1555    }
1556    /// Returns the s1 of the `SRange`.
1557    ///
1558    /// # Returns
1559    /// The ending value of the range.
1560    pub fn s1(&self) -> f64 {
1561        self.s_range.s1()
1562    }
1563    /// Sets the s0 of the `SRange`.
1564    ///
1565    /// # Arguments
1566    /// * `s0` - The new starting value of the range.
1567    pub fn set_s0(&mut self, s0: f64) {
1568        self.s_range.as_mut().expect("Underlying SRange is null").set_s0(s0);
1569    }
1570    /// Sets the s1 of the `SRange`.
1571    ///
1572    /// # Arguments
1573    /// * `s1` - The new ending value of the range.
1574    pub fn set_s1(&mut self, s1: f64) {
1575        self.s_range.as_mut().expect("Underlying SRange is null").set_s1(s1);
1576    }
1577    /// Get the size of the `SRange`.
1578    ///
1579    /// # Returns
1580    /// The size of the range, which is the difference between s1 and s0.
1581    pub fn size(&self) -> f64 {
1582        self.s_range.size()
1583    }
1584    /// Defines whether this SRange is in the direction of +s (i.e., s1() > s0()).
1585    ///
1586    /// # Returns
1587    /// A boolean indicating whether the SRange is in the direction of +s.
1588    pub fn with_s(&self) -> bool {
1589        self.s_range.WithS()
1590    }
1591    /// Determines whether this SRange intersects with `s_range`.
1592    ///
1593    /// # Arguments
1594    /// * `s_range` - Another `SRange` to check for intersection.
1595    /// * `tolerance` - A tolerance value to consider when checking for intersection.
1596    ///
1597    /// # Returns
1598    /// A boolean indicating whether this SRange intersects with `s_range`.
1599    pub fn intersects(&self, s_range: &SRange, tolerance: f64) -> bool {
1600        self.s_range.Intersects(&s_range.s_range, tolerance)
1601    }
1602    /// Determines whether this SRange contains `s_range`.
1603    ///
1604    /// # Arguments
1605    /// * `s_range` - Another `SRange` to check if it is contained within this SRange.
1606    /// * `tolerance` - A tolerance value to consider when checking for containment.
1607    pub fn contains(&self, s_range: &SRange, tolerance: f64) -> bool {
1608        self.s_range.Contains(&s_range.s_range, tolerance)
1609    }
1610    /// Get the intersection of this SRange with `s_range`.
1611    ///
1612    /// # Arguments
1613    /// * `s_range` - Another `SRange` to get the intersection with.
1614    /// * `tolerance` - A tolerance value to consider when checking for intersection.
1615    ///
1616    /// # Returns
1617    /// An `Option<SRange>` containing the intersection of this SRange with `s_range`.
1618    /// If the intersection is empty, it returns None.
1619    pub fn get_intersection(&self, s_range: &SRange, tolerance: f64) -> Option<SRange> {
1620        let intersection = maliput_sys::api::ffi::SRange_GetIntersection(&self.s_range, &s_range.s_range, tolerance);
1621        match intersection.is_null() {
1622            true => None,
1623            false => Some(SRange { s_range: intersection }),
1624        }
1625    }
1626}
1627
1628impl std::fmt::Debug for SRange {
1629    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
1630        write!(f, "SRange {{ s0: {}, s1: {} }}", self.s0(), self.s1())
1631    }
1632}
1633
1634/// Directed longitudinal range of a specific Lane, identified by a LaneId.
1635/// Similar to [SRange], but associated with a specific Lane.
1636pub struct LaneSRange {
1637    pub(crate) lane_s_range: cxx::UniquePtr<maliput_sys::api::ffi::LaneSRange>,
1638}
1639
1640impl LaneSRange {
1641    /// Creates a new `LaneSRange` with the given `lane_id` and `s_range`.
1642    /// # Arguments
1643    /// * `lane_id` - A `String` representing the id of the lane.
1644    /// * `s_range` - A reference to an [SRange] that defines the longitudinal range of the lane.
1645    ///
1646    /// # Returns
1647    /// A new `LaneSRange` instance.
1648    pub fn new(lane_id: &String, s_range: &SRange) -> LaneSRange {
1649        LaneSRange {
1650            lane_s_range: maliput_sys::api::ffi::LaneSRange_new(lane_id, &s_range.s_range),
1651        }
1652    }
1653    /// Returns the lane id of the `LaneSRange`.
1654    ///
1655    /// # Returns
1656    /// A `String` containing the id of the lane associated with this `LaneSRange`.
1657    pub fn lane_id(&self) -> String {
1658        maliput_sys::api::ffi::LaneSRange_lane_id(&self.lane_s_range)
1659    }
1660    /// Returns the [SRange] of the `LaneSRange`.
1661    ///
1662    /// # Returns
1663    /// An [SRange] containing the longitudinal range of the lane associated with this `LaneSRange`.
1664    pub fn s_range(&self) -> SRange {
1665        SRange {
1666            s_range: maliput_sys::api::ffi::LaneSRange_s_range(&self.lane_s_range),
1667        }
1668    }
1669    /// Returns the length of the `LaneSRange`.
1670    ///
1671    /// This is equivalent to `s_range.size()`.
1672    ///
1673    /// # Returns
1674    /// A `f64` representing the length of the `LaneSRange`.
1675    pub fn length(&self) -> f64 {
1676        self.lane_s_range.length()
1677    }
1678    /// Determines whether this LaneSRange intersects with `lane_s_range`.
1679    ///
1680    /// # Arguments
1681    /// * `lane_s_range` - Another `LaneSRange` to check for intersection.
1682    /// * `tolerance` - A tolerance value to consider when checking for intersection.
1683    ///
1684    /// # Returns
1685    /// A boolean indicating whether this LaneSRange intersects with `lane_s_range`.
1686    pub fn intersects(&self, lane_s_range: &LaneSRange, tolerance: f64) -> bool {
1687        self.lane_s_range.Intersects(&lane_s_range.lane_s_range, tolerance)
1688    }
1689    /// Determines whether this LaneSRange contains `lane_s_range`.
1690    ///
1691    /// # Arguments
1692    /// * `lane_s_range` - Another `LaneSRange` to check if it is contained within this LaneSRange.
1693    /// * `tolerance` - A tolerance value to consider when checking for containment.
1694    ///
1695    /// # Returns
1696    /// A boolean indicating whether this LaneSRange contains `lane_s_range`.
1697    /// This checks if the `s_range` of `lane_s_range` is fully contained
1698    /// within the `s_range` of this `LaneSRange`, considering the lane id.
1699    /// If the lane id does not match, it returns false.
1700    pub fn contains(&self, lane_s_range: &LaneSRange, tolerance: f64) -> bool {
1701        self.lane_s_range.Contains(&lane_s_range.lane_s_range, tolerance)
1702    }
1703    /// Computes the intersection of this `LaneSRange` with `lane_s_range`.
1704    ///
1705    /// # Arguments
1706    /// * `lane_s_range` - Another `LaneSRange` to get the intersection with.
1707    /// * `tolerance` - A tolerance value to consider when checking for intersection.
1708    ///
1709    /// # Returns
1710    /// An `Option<LaneSRange>` containing the intersection of this `LaneSRange` with `lane_s_range`.
1711    /// If the lane ids do not match, it returns None.
1712    /// If the intersection is empty, it returns None.
1713    pub fn get_intersection(&self, lane_s_range: &LaneSRange, tolerance: f64) -> Option<LaneSRange> {
1714        let intersection = maliput_sys::api::ffi::LaneSRange_GetIntersection(
1715            &self.lane_s_range,
1716            &lane_s_range.lane_s_range,
1717            tolerance,
1718        );
1719        match intersection.is_null() {
1720            true => None,
1721            false => Some(LaneSRange {
1722                lane_s_range: intersection,
1723            }),
1724        }
1725    }
1726}
1727
1728impl std::fmt::Debug for LaneSRange {
1729    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
1730        write!(
1731            f,
1732            "LaneSRange {{ lane_id: {}, s_range: {:?} }}",
1733            self.lane_id(),
1734            self.s_range()
1735        )
1736    }
1737}
1738
1739/// A route, possibly spanning multiple (end-to-end) lanes.
1740///
1741/// The sequence of [LaneSRange]s should be contiguous by either presenting
1742/// laterally adjacent [LaneSRange]s, or consecutive [LaneSRange]s. (In other words,
1743/// taken as a Lane-space path with r=0 and h=0, it should present a
1744/// G1-continuous curve.)
1745pub struct LaneSRoute {
1746    lane_s_route: cxx::UniquePtr<maliput_sys::api::ffi::LaneSRoute>,
1747}
1748
1749impl LaneSRoute {
1750    /// Creates a new `LaneSRoute` with the given `ranges`.
1751    ///
1752    /// # Arguments
1753    /// * `ranges` - A vector of [LaneSRange] to create the [LaneSRoute].
1754    ///
1755    /// # Returns
1756    /// A new `LaneSRoute` instance containing the provided ranges.
1757    pub fn new(ranges: Vec<LaneSRange>) -> LaneSRoute {
1758        let mut lane_s_ranges_cpp = cxx::CxxVector::new();
1759        for range in &ranges {
1760            lane_s_ranges_cpp
1761                .as_mut()
1762                .unwrap()
1763                .push(maliput_sys::api::ffi::ConstLaneSRangeRef {
1764                    lane_s_range: &range.lane_s_range,
1765                });
1766        }
1767        LaneSRoute {
1768            lane_s_route: maliput_sys::api::ffi::LaneSRoute_new(&lane_s_ranges_cpp),
1769        }
1770    }
1771
1772    /// Returns the sequence of [LaneSRange]s.
1773    ///
1774    /// # Returns
1775    /// A vector of [LaneSRange]s that make up this [LaneSRoute].
1776    pub fn ranges(&self) -> Vec<LaneSRange> {
1777        let mut ranges = Vec::new();
1778        let lane_s_ranges = self.lane_s_route.ranges();
1779        for range in lane_s_ranges {
1780            ranges.push(LaneSRange {
1781                lane_s_range: maliput_sys::api::ffi::LaneSRange_new(
1782                    &maliput_sys::api::ffi::LaneSRange_lane_id(range),
1783                    maliput_sys::api::ffi::LaneSRange_s_range(range).as_ref().expect(""),
1784                ),
1785            })
1786        }
1787        ranges
1788    }
1789
1790    /// Computes the accumulated length of all [LaneSRange]s.
1791    ///
1792    /// # Returns
1793    /// A `f64` representing the total length of the [LaneSRoute].
1794    pub fn length(&self) -> f64 {
1795        self.lane_s_route.length()
1796    }
1797
1798    /// Determines whether this LaneSRoute intersects with `other`.
1799    ///
1800    /// # Arguments
1801    /// * `other` - The other LaneSRoute to check for intersection.
1802    /// * `tolerance` - The tolerance to use for intersection checks.
1803    ///
1804    /// # Returns
1805    /// * `true` if the two LaneSRoute intersect, `false` otherwise.
1806    pub fn intersects(&self, other: &LaneSRoute, tolerance: f64) -> bool {
1807        self.lane_s_route.Intersects(&other.lane_s_route, tolerance)
1808    }
1809}
1810
1811impl std::fmt::Debug for LaneSRoute {
1812    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
1813        write!(f, "LaneSRoute {{ ranges: {:?} }}", self.ranges())
1814    }
1815}
1816
1817/// A specific endpoint of a specific Lane.
1818pub enum LaneEnd<'a> {
1819    /// The start of the Lane. ("s == 0")
1820    Start(Lane<'a>),
1821    /// The end of the Lane. ("s == length")
1822    Finish(Lane<'a>),
1823}
1824
1825impl LaneEnd<'_> {
1826    /// Gets the Lane of the `LaneEnd`.
1827    ///
1828    /// # Returns
1829    /// A reference to the [Lane] associated with this `LaneEnd`.
1830    /// This will return the Lane for both Start and Finish variants.
1831    pub fn lane(&self) -> &Lane<'_> {
1832        match self {
1833            LaneEnd::Start(lane) => lane,
1834            LaneEnd::Finish(lane) => lane,
1835        }
1836    }
1837}
1838
1839impl PartialEq for LaneEnd<'_> {
1840    fn eq(&self, other: &Self) -> bool {
1841        match self {
1842            LaneEnd::Start(lane) => match other {
1843                LaneEnd::Start(other_lane) => lane.id() == other_lane.id(),
1844                _ => false,
1845            },
1846            LaneEnd::Finish(lane) => match other {
1847                LaneEnd::Finish(other_lane) => lane.id() == other_lane.id(),
1848                _ => false,
1849            },
1850        }
1851    }
1852}
1853
1854impl Eq for LaneEnd<'_> {}
1855
1856impl std::fmt::Display for LaneEnd<'_> {
1857    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
1858        match self {
1859            LaneEnd::Start(lane) => write!(f, "LaneEnd::Start({})", lane.id()),
1860            LaneEnd::Finish(lane) => write!(f, "LaneEnd::Finish({})", lane.id()),
1861        }
1862    }
1863}
1864
1865impl std::fmt::Debug for LaneEnd<'_> {
1866    fn fmt(&self, f: &mut std::fmt::Formatter) -> std::fmt::Result {
1867        match self {
1868            LaneEnd::Start(lane) => write!(f, "LaneEnd::Start({})", lane.id()),
1869            LaneEnd::Finish(lane) => write!(f, "LaneEnd::Finish({})", lane.id()),
1870        }
1871    }
1872}
1873
1874/// A set of LaneEnds.
1875pub struct LaneEndSet<'a> {
1876    lane_end_set: &'a maliput_sys::api::ffi::LaneEndSet,
1877}
1878
1879impl<'a> LaneEndSet<'a> {
1880    /// Obtains the size of the LaneEndSet.
1881    ///
1882    /// # Returns
1883    /// The number of LaneEnds in the set.
1884    pub fn size(&self) -> i32 {
1885        self.lane_end_set.size()
1886    }
1887    /// Gets the [LaneEnd] at the given index.
1888    ///
1889    /// # Arguments
1890    /// * `index` - The index of the LaneEnd to retrieve.
1891    ///
1892    /// # Returns
1893    /// A [Result<LaneEnd, MaliputError>] containing the LaneEnd at the given index.
1894    /// If the index is out of bounds, an error is returned.
1895    pub fn get(&self, index: i32) -> Result<LaneEnd<'_>, MaliputError> {
1896        let lane_end = self.lane_end_set.get(index)?;
1897        // Obtain end type and lane reference.
1898        let is_start = maliput_sys::api::ffi::LaneEnd_is_start(lane_end);
1899        let lane_ref = unsafe {
1900            maliput_sys::api::ffi::LaneEnd_lane(lane_end)
1901                .as_ref()
1902                .expect("Underlying LaneEnd is null")
1903        };
1904        // Create a LaneEnd enum variant.
1905        Ok(match is_start {
1906            true => LaneEnd::Start(Lane { lane: lane_ref }),
1907            false => LaneEnd::Finish(Lane { lane: lane_ref }),
1908        })
1909    }
1910
1911    /// Converts the LaneEndSet to a map of lane-id to LaneEnd.
1912    ///
1913    /// # Returns
1914    /// A `HashMap<String, LaneEnd>` where the key is the lane id and
1915    /// the value is the corresponding LaneEnd.
1916    pub fn to_lane_map(&self) -> std::collections::HashMap<String, LaneEnd<'_>> {
1917        (0..self.size())
1918            .map(|i| {
1919                let end = self.get(i).unwrap();
1920                (end.lane().id(), end)
1921            })
1922            .collect()
1923    }
1924}
1925
1926/// A BranchPoint is a node in the network of a RoadGeometry at which
1927/// Lanes connect to one another.  A BranchPoint is a collection of LaneEnds
1928/// specifying the Lanes (and, in particular, which ends of the Lanes) are
1929/// connected at the BranchPoint.
1930///
1931/// LaneEnds participating in a BranchPoint are grouped into two sets,
1932/// arbitrarily named "A-side" and "B-side". LaneEnds on the same "side"
1933/// have coincident into-the-lane tangent vectors, which are anti-parallel
1934/// to those of LaneEnds on the other side.
1935pub struct BranchPoint<'a> {
1936    branch_point: &'a maliput_sys::api::ffi::BranchPoint,
1937}
1938
1939impl<'a> BranchPoint<'a> {
1940    /// Returns the id of the BranchPoint.
1941    ///
1942    /// # Returns
1943    /// A `String` containing the id of the BranchPoint.
1944    pub fn id(&self) -> String {
1945        maliput_sys::api::ffi::BranchPoint_id(self.branch_point)
1946    }
1947    /// Returns the [RoadGeometry] to which this BranchPoint belongs.
1948    ///
1949    /// # Returns
1950    /// A [RoadGeometry] containing the RoadGeometry to which this BranchPoint belongs.
1951    pub fn road_geometry(&self) -> RoadGeometry<'_> {
1952        unsafe {
1953            RoadGeometry {
1954                rg: self.branch_point.road_geometry().as_ref().expect(""),
1955            }
1956        }
1957    }
1958    /// Returns the set of [LaneEnd]s on the same side as the given [LaneEnd].
1959    /// E.g: For a T-junction, this would return the set of LaneEnds on the merging side.
1960    ///
1961    /// # Arguments
1962    /// * `end` - This branch's start or end [LaneEnd].
1963    ///
1964    /// # Return
1965    /// A [LaneEndSet] of [LaneEnd]s on the same side as the given [LaneEnd].
1966    pub fn get_confluent_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
1967        let lane_end_set_ptr = self.branch_point.GetConfluentBranches(
1968            BranchPoint::from_lane_end_to_ffi(end)
1969                .as_ref()
1970                .expect("Underlying LaneEnd is null"),
1971        )?;
1972        Ok(LaneEndSet {
1973            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
1974        })
1975    }
1976    /// Returns the set of [LaneEnd]s on the opposite side as the given [LaneEnd].
1977    /// E.g: For a T-junction, this would return the [LaneEnd]s which end flows into the junction.
1978    ///
1979    /// # Arguments
1980    /// * `end` - This branch's start or end [LaneEnd].
1981    ///
1982    /// # Return
1983    /// A [LaneEndSet] of [LaneEnd]s on the opposite side as the given [LaneEnd].
1984    pub fn get_ongoing_branches(&self, end: &LaneEnd) -> Result<LaneEndSet<'_>, MaliputError> {
1985        let lane_end_set_ptr = self.branch_point.GetOngoingBranches(
1986            BranchPoint::from_lane_end_to_ffi(end)
1987                .as_ref()
1988                .expect("Underlying LaneEnd is null"),
1989        )?;
1990        Ok(LaneEndSet {
1991            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
1992        })
1993    }
1994    /// Returns the default ongoing branch (if any) for the given `end`.
1995    /// This typically represents what would be considered "continuing
1996    /// through-traffic" from `end` (e.g., as opposed to a branch executing
1997    /// a turn).
1998    ///
1999    /// If `end` has no default-branch at this BranchPoint, the return
2000    /// value will be None.
2001    ///
2002    /// # Arguments
2003    /// * `end` - The [LaneEnd] for which to get the default branch.
2004    ///
2005    /// # Returns
2006    /// An `Option<LaneEnd>` containing the default branch if it exists.
2007    /// If no default branch exists, it returns None.
2008    pub fn get_default_branch(&self, end: &LaneEnd) -> Option<LaneEnd<'_>> {
2009        let lane_end = maliput_sys::api::ffi::BranchPoint_GetDefaultBranch(
2010            self.branch_point,
2011            BranchPoint::from_lane_end_to_ffi(end)
2012                .as_ref()
2013                .expect("Underlying LaneEnd is null"),
2014        );
2015        match lane_end.is_null() {
2016            true => None,
2017            false => {
2018                let lane_end_ref: &maliput_sys::api::ffi::LaneEnd =
2019                    lane_end.as_ref().expect("Underlying LaneEnd is null");
2020                let is_start = maliput_sys::api::ffi::LaneEnd_is_start(lane_end_ref);
2021                let lane_ref = unsafe {
2022                    maliput_sys::api::ffi::LaneEnd_lane(lane_end_ref)
2023                        .as_ref()
2024                        .expect("Underlying LaneEnd is null")
2025                };
2026                match is_start {
2027                    true => Some(LaneEnd::Start(Lane { lane: lane_ref })),
2028                    false => Some(LaneEnd::Finish(Lane { lane: lane_ref })),
2029                }
2030            }
2031        }
2032    }
2033    /// Returns the set of LaneEnds grouped together on the "A-side".
2034    ///
2035    /// # Returns
2036    /// A [LaneEndSet] containing the LaneEnds on the "A-side" of the BranchPoint.
2037    pub fn get_a_side(&self) -> LaneEndSet<'_> {
2038        let lane_end_set_ptr = self.branch_point.GetASide();
2039        LaneEndSet {
2040            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
2041        }
2042    }
2043    /// Returns the set of LaneEnds grouped together on the "B-side".
2044    ///
2045    /// # Returns
2046    /// A [LaneEndSet] containing the LaneEnds on the "B-side" of the BranchPoint.
2047    /// This is the opposite side of the "A-side".
2048    pub fn get_b_side(&self) -> LaneEndSet<'_> {
2049        let lane_end_set_ptr = self.branch_point.GetBSide();
2050        LaneEndSet {
2051            lane_end_set: unsafe { lane_end_set_ptr.as_ref().expect("Underlying LaneEndSet is null") },
2052        }
2053    }
2054    /// Converts LaneEnd enum to LaneEnd ffi.
2055    fn from_lane_end_to_ffi(end: &LaneEnd) -> cxx::UniquePtr<maliput_sys::api::ffi::LaneEnd> {
2056        match end {
2057            LaneEnd::Start(lane) => unsafe { maliput_sys::api::ffi::LaneEnd_new(lane.lane, true) },
2058            LaneEnd::Finish(lane) => unsafe { maliput_sys::api::ffi::LaneEnd_new(lane.lane, false) },
2059        }
2060    }
2061}
2062
2063/// An abstract convenience class that aggregates information pertaining to an
2064/// intersection. Its primary purpose is to serve as a single source of this
2065/// information and to remove the need for users to query numerous disparate
2066/// data structures and state providers.
2067pub struct Intersection<'a> {
2068    intersection: &'a mut maliput_sys::api::ffi::Intersection,
2069}
2070
2071impl<'a> Intersection<'a> {
2072    /// Returns the id of the `Intersection` as a string.
2073    pub fn id(&self) -> String {
2074        maliput_sys::api::ffi::Intersection_id(self.intersection)
2075    }
2076}
2077
2078/// A book of Intersections.
2079pub struct IntersectionBook<'a> {
2080    intersection_book: &'a mut maliput_sys::api::ffi::IntersectionBook,
2081}
2082
2083impl<'a> IntersectionBook<'a> {
2084    /// Returns all Intersections in the book.
2085    ///
2086    /// # Returns
2087    /// A vector of [Intersection]s containing all Intersections in the book.
2088    pub fn get_intersections(&mut self) -> Vec<Intersection<'_>> {
2089        let book_pin = unsafe { std::pin::Pin::new_unchecked(&mut *self.intersection_book) };
2090        let intersections_cpp = maliput_sys::api::ffi::IntersectionBook_GetIntersections(book_pin);
2091        unsafe {
2092            intersections_cpp
2093                .into_iter()
2094                .map(|intersection| Intersection {
2095                    intersection: intersection
2096                        .intersection
2097                        .as_mut()
2098                        .expect("Underlying Intersection is null"),
2099                })
2100                .collect::<Vec<Intersection>>()
2101        }
2102    }
2103
2104    /// Gets the specified Intersection.
2105    ///
2106    /// # Arguments
2107    ///   * `id` - The id of the Intersection to get.
2108    ///
2109    /// # Returns
2110    ///   * An `Option<Intersection>`
2111    ///     * Some(Intersection) - The Intersection with the specified id.
2112    ///     * None - If the Intersection with the specified id does not exist.
2113    pub fn get_intersection(&mut self, id: &str) -> Option<Intersection<'_>> {
2114        let book_pin = unsafe { std::pin::Pin::new_unchecked(&mut *self.intersection_book) };
2115        let intersection_option = unsafe {
2116            maliput_sys::api::ffi::IntersectionBook_GetIntersection(book_pin, &String::from(id))
2117                .intersection
2118                .as_mut()
2119        };
2120        match &intersection_option {
2121            None => None,
2122            Some(_) => Some(Intersection {
2123                intersection: intersection_option.expect("Underlying Intersection is null"),
2124            }),
2125        }
2126    }
2127}
2128
2129mod tests {
2130    mod road_geometry {
2131        #[test]
2132        fn to_road_position_surface_test() {
2133            let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
2134            let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);
2135            let road_network_properties = std::collections::HashMap::from([
2136                ("road_geometry_id", "my_rg_from_rust"),
2137                ("opendrive_file", xodr_path.as_str()),
2138            ]);
2139            let road_network = crate::api::RoadNetwork::new("maliput_malidrive", &road_network_properties).unwrap();
2140            let road_geometry = road_network.road_geometry();
2141
2142            // Although this isn't directly on the surface, it is within the RoadGeometry volume.
2143            let inertial_pos = crate::api::InertialPosition::new(1.0, 0.0, 2.0);
2144            let road_pos = road_geometry.to_road_position_surface(&inertial_pos);
2145            assert!(road_pos.is_ok());
2146            let road_pos = road_pos.unwrap();
2147            let tolerance = 1e-3;
2148            assert!((road_pos.pos().s() - 1.0).abs() < tolerance);
2149            assert!((road_pos.pos().r() - -1.75).abs() < tolerance);
2150            assert!((road_pos.pos().h() - 0.0).abs() < tolerance);
2151
2152            // An inertial position that is off the road volume.
2153            let inertial_pos = crate::api::InertialPosition::new(1.0, 0.0, 10.0);
2154            let road_pos = road_geometry.to_road_position_surface(&inertial_pos);
2155            assert!(road_pos.is_err());
2156        }
2157    }
2158    mod lane_position {
2159        #[test]
2160        fn lane_position_new() {
2161            let lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2162            assert_eq!(lane_pos.s(), 1.0);
2163            assert_eq!(lane_pos.r(), 2.0);
2164            assert_eq!(lane_pos.h(), 3.0);
2165        }
2166
2167        #[test]
2168        fn equality() {
2169            let v = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2170            let w = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2171            assert_eq!(v, w);
2172            let z = crate::api::LanePosition::new(4.0, 5.0, 6.0);
2173            assert_ne!(v, z);
2174        }
2175
2176        #[test]
2177        fn set_s() {
2178            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2179            lane_pos.set_s(4.0);
2180            assert_eq!(lane_pos.s(), 4.0);
2181        }
2182
2183        #[test]
2184        fn set_r() {
2185            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2186            lane_pos.set_r(4.0);
2187            assert_eq!(lane_pos.r(), 4.0);
2188        }
2189
2190        #[test]
2191        fn set_h() {
2192            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2193            lane_pos.set_h(4.0);
2194            assert_eq!(lane_pos.h(), 4.0);
2195        }
2196
2197        #[test]
2198        fn set_srh() {
2199            use crate::math::Vector3;
2200            let mut lane_pos = crate::api::LanePosition::new(1.0, 2.0, 3.0);
2201            let vector = Vector3::new(4.0, 5.0, 6.0);
2202            lane_pos.set_srh(&vector);
2203            assert_eq!(lane_pos.s(), 4.0);
2204            assert_eq!(lane_pos.r(), 5.0);
2205            assert_eq!(lane_pos.h(), 6.0);
2206        }
2207    }
2208
2209    mod inertial_position {
2210
2211        #[test]
2212        fn inertial_position_new() {
2213            let inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2214            assert_eq!(inertial_pos.x(), 1.0);
2215            assert_eq!(inertial_pos.y(), 2.0);
2216            assert_eq!(inertial_pos.z(), 3.0);
2217        }
2218
2219        #[test]
2220        fn equality() {
2221            let v = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2222            let w = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2223            assert_eq!(v, w);
2224            let z = crate::api::InertialPosition::new(4.0, 5.0, 6.0);
2225            assert_ne!(v, z);
2226        }
2227
2228        #[test]
2229        fn set_x() {
2230            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2231            inertial_pos.set_x(4.0);
2232            assert_eq!(inertial_pos.x(), 4.0);
2233        }
2234
2235        #[test]
2236        fn set_y() {
2237            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2238            inertial_pos.set_y(4.0);
2239            assert_eq!(inertial_pos.y(), 4.0);
2240        }
2241
2242        #[test]
2243        fn set_z() {
2244            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2245            inertial_pos.set_z(4.0);
2246            assert_eq!(inertial_pos.z(), 4.0);
2247        }
2248
2249        #[test]
2250        fn set_xyz() {
2251            use crate::math::Vector3;
2252            let mut inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2253            let vector = Vector3::new(4.0, 5.0, 6.0);
2254            inertial_pos.set_xyz(&vector);
2255            assert_eq!(inertial_pos.x(), 4.0);
2256            assert_eq!(inertial_pos.y(), 5.0);
2257            assert_eq!(inertial_pos.z(), 6.0);
2258        }
2259
2260        #[test]
2261        fn xyz() {
2262            let inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2263            assert_eq!(inertial_pos.xyz(), crate::math::Vector3::new(1.0, 2.0, 3.0));
2264        }
2265
2266        #[test]
2267        fn length() {
2268            let inertial_pos = crate::api::InertialPosition::new(3.0, 0.0, 4.0);
2269            assert_eq!(inertial_pos.length(), 5.0);
2270        }
2271
2272        #[test]
2273        fn distance() {
2274            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 1.0, 1.0);
2275            let inertial_pos2 = crate::api::InertialPosition::new(5.0, 1.0, 1.0);
2276            assert_eq!(inertial_pos1.distance(&inertial_pos2), 4.0);
2277        }
2278
2279        #[test]
2280        fn str() {
2281            let inertial_pos = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2282            assert_eq!(inertial_pos.to_string(), "(x = 1, y = 2, z = 3)");
2283        }
2284
2285        #[test]
2286        fn add_operation() {
2287            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2288            let inertial_pos2 = crate::api::InertialPosition::new(4.0, 5.0, 6.0);
2289            let inertial_pos3 = inertial_pos1 + inertial_pos2;
2290            assert_eq!(inertial_pos3.x(), 5.0);
2291            assert_eq!(inertial_pos3.y(), 7.0);
2292            assert_eq!(inertial_pos3.z(), 9.0);
2293        }
2294
2295        #[test]
2296        fn sub_operation() {
2297            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2298            let inertial_pos2 = crate::api::InertialPosition::new(4.0, 5.0, 6.0);
2299            let inertial_pos3 = inertial_pos1 - inertial_pos2;
2300            assert_eq!(inertial_pos3.x(), -3.0);
2301            assert_eq!(inertial_pos3.y(), -3.0);
2302            assert_eq!(inertial_pos3.z(), -3.0);
2303        }
2304
2305        #[test]
2306        fn mul_scalar_operation() {
2307            let inertial_pos1 = crate::api::InertialPosition::new(1.0, 2.0, 3.0);
2308            let inertial_pos2 = inertial_pos1 * 2.0;
2309            assert_eq!(inertial_pos2.x(), 2.0);
2310            assert_eq!(inertial_pos2.y(), 4.0);
2311            assert_eq!(inertial_pos2.z(), 6.0);
2312        }
2313    }
2314    mod rotation {
2315        #[test]
2316        fn rotation_new() {
2317            let rotation = crate::api::Rotation::new();
2318            assert_eq!(rotation.roll(), 0.0);
2319            assert_eq!(rotation.pitch(), 0.0);
2320            assert_eq!(rotation.yaw(), 0.0);
2321        }
2322
2323        #[test]
2324        fn from_quat() {
2325            let quat = crate::math::Quaternion::new(1.0, 0.0, 0.0, 0.0);
2326            let rotation = crate::api::Rotation::from_quat(&quat);
2327            assert_eq!(rotation.roll(), 0.0);
2328            assert_eq!(rotation.pitch(), 0.0);
2329            assert_eq!(rotation.yaw(), 0.0);
2330        }
2331
2332        #[test]
2333        fn from_rpy() {
2334            let rpy = crate::math::RollPitchYaw::new(0.0, 0.0, 0.0);
2335            let rotation = crate::api::Rotation::from_rpy(&rpy);
2336            assert_eq!(rotation.roll(), 0.0);
2337            assert_eq!(rotation.pitch(), 0.0);
2338            assert_eq!(rotation.yaw(), 0.0);
2339        }
2340
2341        #[test]
2342        fn set_quat() {
2343            let mut rotation = crate::api::Rotation::new();
2344            let quat = crate::math::Quaternion::new(1.0, 0.0, 0.0, 0.0);
2345            rotation.set_quat(&quat);
2346            assert_eq!(rotation.roll(), 0.0);
2347            assert_eq!(rotation.pitch(), 0.0);
2348            assert_eq!(rotation.yaw(), 0.0);
2349        }
2350
2351        #[test]
2352        fn matrix() {
2353            let rotation = crate::api::Rotation::new();
2354            let matrix = rotation.matrix();
2355            assert_eq!(matrix.row(0), crate::math::Vector3::new(1.0, 0.0, 0.0));
2356            assert_eq!(matrix.row(1), crate::math::Vector3::new(0.0, 1.0, 0.0));
2357            assert_eq!(matrix.row(2), crate::math::Vector3::new(0.0, 0.0, 1.0));
2358        }
2359    }
2360
2361    mod s_range {
2362        #[test]
2363        fn s_range_new() {
2364            let s_range = crate::api::SRange::new(1.0, 2.0);
2365            assert_eq!(s_range.s0(), 1.0);
2366            assert_eq!(s_range.s1(), 2.0);
2367        }
2368        #[test]
2369        fn s_range_api() {
2370            let s_range_1 = crate::api::SRange::new(1.0, 3.0);
2371            let s_range_2 = crate::api::SRange::new(2.0, 4.0);
2372            assert_eq!(s_range_1.size(), 2.0);
2373            assert!(s_range_1.with_s());
2374            assert!(s_range_1.intersects(&s_range_2, 0.0));
2375            assert!(!s_range_1.contains(&s_range_2, 0.0));
2376        }
2377        #[test]
2378        fn s_range_setters() {
2379            let mut s_range = crate::api::SRange::new(0.0, 4.0);
2380            s_range.set_s0(1.0);
2381            s_range.set_s1(3.0);
2382            assert_eq!(s_range.s0(), 1.0);
2383            assert_eq!(s_range.s1(), 3.0);
2384        }
2385        #[test]
2386        fn s_range_get_intersection_with_intersection() {
2387            let s_range_1 = crate::api::SRange::new(1.0, 3.0);
2388            let s_range_2 = crate::api::SRange::new(2.0, 4.0);
2389            let intersection = s_range_1.get_intersection(&s_range_2, 0.0);
2390            assert!(intersection.is_some());
2391            let intersection = intersection.unwrap();
2392            assert_eq!(intersection.s0(), 2.0);
2393            assert_eq!(intersection.s1(), 3.0);
2394        }
2395        #[test]
2396        fn s_range_get_intersection_with_no_intersection() {
2397            let s_range_1 = crate::api::SRange::new(1.0, 2.0);
2398            let s_range_2 = crate::api::SRange::new(3.0, 4.0);
2399            let intersection = s_range_1.get_intersection(&s_range_2, 0.0);
2400            assert!(intersection.is_none());
2401        }
2402    }
2403
2404    mod lane_s_range {
2405        #[test]
2406        fn lane_s_range_new() {
2407            let lane_s_range =
2408                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(1.0, 2.0));
2409            assert_eq!(lane_s_range.lane_id(), "lane_test");
2410            assert_eq!(lane_s_range.s_range().s0(), 1.0);
2411            assert_eq!(lane_s_range.s_range().s1(), 2.0);
2412            assert_eq!(lane_s_range.length(), 1.0);
2413        }
2414        #[test]
2415        fn lane_s_range_api() {
2416            let lane_s_range_1 =
2417                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(1.0, 2.0));
2418            let lane_s_range_2 =
2419                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(2.0, 3.0));
2420            assert!(lane_s_range_1.intersects(&lane_s_range_2, 0.0));
2421            assert!(!lane_s_range_1.contains(&lane_s_range_2, 0.0));
2422        }
2423        #[test]
2424        fn lane_s_range_get_intersection_with_intersection() {
2425            let lane_s_range_1 =
2426                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(1.0, 3.0));
2427            let lane_s_range_2 =
2428                crate::api::LaneSRange::new(&String::from("lane_test"), &crate::api::SRange::new(2.0, 4.0));
2429            let intersection = lane_s_range_1.get_intersection(&lane_s_range_2, 0.0);
2430            assert!(intersection.is_some());
2431            let intersection = intersection.unwrap();
2432            assert_eq!(intersection.lane_id(), "lane_test");
2433            assert_eq!(intersection.s_range().s0(), 2.0);
2434            assert_eq!(intersection.s_range().s1(), 3.0);
2435        }
2436        #[test]
2437        fn lane_s_range_get_intersection_with_no_intersection() {
2438            let lane_s_range_1 =
2439                crate::api::LaneSRange::new(&String::from("lane test_1"), &crate::api::SRange::new(1.0, 3.0));
2440            let lane_s_range_2 =
2441                crate::api::LaneSRange::new(&String::from("lane_test_2"), &crate::api::SRange::new(2.0, 4.0));
2442            let intersection = lane_s_range_1.get_intersection(&lane_s_range_2, 0.0);
2443            assert!(intersection.is_none());
2444        }
2445    }
2446
2447    mod lane_s_route {
2448        // Helper function to create a LaneSRoute
2449        // with two LaneSRange.
2450        // # Arguments
2451        // * `s0_0` - The s0 of the first LaneSRange.
2452        // * `s1_0` - The s1 of the first LaneSRange.
2453        // * `s0_1` - The s0 of the second LaneSRange.
2454        // * `s1_1` - The s1 of the second LaneSRange.
2455        fn _get_lane_s_route(s0_0: f64, s1_0: f64, s0_1: f64, s1_1: f64) -> crate::api::LaneSRoute {
2456            let ranges = vec![
2457                crate::api::LaneSRange::new(&String::from("lane_test_1"), &crate::api::SRange::new(s0_0, s1_0)),
2458                crate::api::LaneSRange::new(&String::from("lane_test_2"), &crate::api::SRange::new(s0_1, s1_1)),
2459            ];
2460            crate::api::LaneSRoute::new(ranges)
2461        }
2462        #[test]
2463        fn lane_s_route_new() {
2464            let lane_s_route = _get_lane_s_route(0., 10., 0., 15.);
2465            assert!(!lane_s_route.lane_s_route.is_null());
2466            let ranges = lane_s_route.ranges();
2467            assert_eq!(ranges.len(), 2);
2468            assert_eq!(ranges[0].lane_id(), "lane_test_1");
2469            assert_eq!(ranges[1].lane_id(), "lane_test_2");
2470        }
2471        #[test]
2472        fn lane_s_route_length() {
2473            let lane_s_route = _get_lane_s_route(0., 10., 0., 15.);
2474            assert_eq!(lane_s_route.length(), 25.0);
2475        }
2476        #[test]
2477        fn lane_s_route_intersects() {
2478            let lane_s_route = _get_lane_s_route(0., 10., 0., 10.);
2479            let lane_s_route_that_intersects = _get_lane_s_route(5., 9., 5., 9.);
2480            let lane_s_route_that_not_intersects = _get_lane_s_route(11., 20., 11., 20.);
2481            assert!(lane_s_route.intersects(&lane_s_route_that_intersects, 0.0));
2482            assert!(!lane_s_route.intersects(&lane_s_route_that_not_intersects, 0.0));
2483        }
2484    }
2485}