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