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