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