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