Skip to main content

maliput/api/objects/
mod.rs

1// BSD 3-Clause License
2//
3// Copyright (c) 2026, 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 std::collections::HashMap;
32
33#[derive(Debug, Copy, Clone, PartialEq, Eq)]
34/// Defines the possible road object types.
35pub enum RoadObjectType {
36    Unknown,
37    Barrier,
38    Building,
39    Crosswalk,
40    Gantry,
41    Obstacle,
42    ParkingSpace,
43    Pole,
44    RoadMark,
45    RoadSurface,
46    StopLine,
47    TrafficIsland,
48    Tree,
49    Vegetation,
50}
51
52fn road_object_type_from_cpp(obj_type: maliput_sys::api::objects::ffi::RoadObjectType) -> RoadObjectType {
53    match obj_type {
54        maliput_sys::api::objects::ffi::RoadObjectType::kUnknown => RoadObjectType::Unknown,
55        maliput_sys::api::objects::ffi::RoadObjectType::kBarrier => RoadObjectType::Barrier,
56        maliput_sys::api::objects::ffi::RoadObjectType::kBuilding => RoadObjectType::Building,
57        maliput_sys::api::objects::ffi::RoadObjectType::kCrosswalk => RoadObjectType::Crosswalk,
58        maliput_sys::api::objects::ffi::RoadObjectType::kGantry => RoadObjectType::Gantry,
59        maliput_sys::api::objects::ffi::RoadObjectType::kObstacle => RoadObjectType::Obstacle,
60        maliput_sys::api::objects::ffi::RoadObjectType::kParkingSpace => RoadObjectType::ParkingSpace,
61        maliput_sys::api::objects::ffi::RoadObjectType::kPole => RoadObjectType::Pole,
62        maliput_sys::api::objects::ffi::RoadObjectType::kRoadMark => RoadObjectType::RoadMark,
63        maliput_sys::api::objects::ffi::RoadObjectType::kRoadSurface => RoadObjectType::RoadSurface,
64        maliput_sys::api::objects::ffi::RoadObjectType::kStopLine => RoadObjectType::StopLine,
65        maliput_sys::api::objects::ffi::RoadObjectType::kTrafficIsland => RoadObjectType::TrafficIsland,
66        maliput_sys::api::objects::ffi::RoadObjectType::kTree => RoadObjectType::Tree,
67        maliput_sys::api::objects::ffi::RoadObjectType::kVegetation => RoadObjectType::Vegetation,
68        _ => RoadObjectType::Unknown,
69    }
70}
71
72fn road_object_type_to_cpp(obj_type: &RoadObjectType) -> maliput_sys::api::objects::ffi::RoadObjectType {
73    match obj_type {
74        RoadObjectType::Unknown => maliput_sys::api::objects::ffi::RoadObjectType::kUnknown,
75        RoadObjectType::Barrier => maliput_sys::api::objects::ffi::RoadObjectType::kBarrier,
76        RoadObjectType::Building => maliput_sys::api::objects::ffi::RoadObjectType::kBuilding,
77        RoadObjectType::Crosswalk => maliput_sys::api::objects::ffi::RoadObjectType::kCrosswalk,
78        RoadObjectType::Gantry => maliput_sys::api::objects::ffi::RoadObjectType::kGantry,
79        RoadObjectType::Obstacle => maliput_sys::api::objects::ffi::RoadObjectType::kObstacle,
80        RoadObjectType::ParkingSpace => maliput_sys::api::objects::ffi::RoadObjectType::kParkingSpace,
81        RoadObjectType::Pole => maliput_sys::api::objects::ffi::RoadObjectType::kPole,
82        RoadObjectType::RoadMark => maliput_sys::api::objects::ffi::RoadObjectType::kRoadMark,
83        RoadObjectType::RoadSurface => maliput_sys::api::objects::ffi::RoadObjectType::kRoadSurface,
84        RoadObjectType::StopLine => maliput_sys::api::objects::ffi::RoadObjectType::kStopLine,
85        RoadObjectType::TrafficIsland => maliput_sys::api::objects::ffi::RoadObjectType::kTrafficIsland,
86        RoadObjectType::Tree => maliput_sys::api::objects::ffi::RoadObjectType::kTree,
87        RoadObjectType::Vegetation => maliput_sys::api::objects::ffi::RoadObjectType::kVegetation,
88    }
89}
90
91/// Represents the position of a [RoadObject] in the road network.
92///
93/// Always contains an inertial position. May also contain a lane position
94/// expressed as `(lane_id, s, r, h)`.
95pub struct RoadObjectPosition {
96    pub inertial_position: crate::api::InertialPosition,
97    pub lane_position: Option<(String, f64, f64, f64)>,
98}
99
100/// Represents a single corner point of an [Outline].
101///
102/// `height` is `Some` when the corner has an explicit height attribute, `None` otherwise.
103pub struct OutlineCorner {
104    pub x: f64,
105    pub y: f64,
106    pub z: f64,
107    pub height: Option<f64>,
108}
109
110/// Represents an outline (a polygon) of a [RoadObject].
111pub struct Outline<'a> {
112    pub(crate) outline: &'a maliput_sys::api::objects::ffi::Outline,
113}
114
115impl<'a> Outline<'a> {
116    /// Returns the unique identifier of this outline.
117    pub fn id(&self) -> String {
118        maliput_sys::api::objects::ffi::Outline_id(self.outline)
119    }
120
121    /// Returns whether this outline is closed (first and last corner coincide).
122    pub fn is_closed(&self) -> bool {
123        maliput_sys::api::objects::ffi::Outline_is_closed(self.outline)
124    }
125
126    /// Returns the number of corners in this outline.
127    pub fn num_corners(&self) -> i32 {
128        maliput_sys::api::objects::ffi::Outline_num_corners(self.outline)
129    }
130
131    /// Returns the corners of this outline.
132    pub fn corners(&self) -> Vec<OutlineCorner> {
133        maliput_sys::api::objects::ffi::Outline_corners(self.outline)
134            .into_iter()
135            .map(|c| OutlineCorner {
136                x: c.x,
137                y: c.y,
138                z: c.z,
139                height: if c.has_height { Some(c.height) } else { None },
140            })
141            .collect()
142    }
143}
144
145/// Models a physical road object in the road network.
146///
147/// A `RoadObject` has a type, position, orientation, bounding box, and optional
148/// outlines and properties.
149pub struct RoadObject<'a> {
150    pub(crate) road_object: &'a maliput_sys::api::objects::ffi::RoadObject,
151}
152
153impl<'a> RoadObject<'a> {
154    /// Returns the unique identifier of this road object.
155    pub fn id(&self) -> String {
156        maliput_sys::api::objects::ffi::RoadObject_id(self.road_object)
157    }
158
159    /// Returns the optional human-readable name of this road object.
160    pub fn name(&self) -> Option<String> {
161        let wrapper = maliput_sys::api::objects::ffi::RoadObject_name(self.road_object);
162        if wrapper.is_null() {
163            return None;
164        }
165        Some(wrapper.value.clone())
166    }
167
168    /// Returns the [RoadObjectType] of this road object.
169    pub fn object_type(&self) -> RoadObjectType {
170        let t = maliput_sys::api::objects::ffi::RoadObject_object_type(self.road_object);
171        road_object_type_from_cpp(t)
172    }
173
174    /// Returns the optional subtype string of this road object.
175    pub fn subtype(&self) -> Option<String> {
176        let wrapper = maliput_sys::api::objects::ffi::RoadObject_subtype(self.road_object);
177        if wrapper.is_null() {
178            return None;
179        }
180        Some(wrapper.value.clone())
181    }
182
183    /// Returns the [RoadObjectPosition] of this road object.
184    pub fn position(&self) -> RoadObjectPosition {
185        let inertial_position = maliput_sys::api::objects::ffi::RoadObject_position_inertial(self.road_object);
186        let has_lane = maliput_sys::api::objects::ffi::RoadObject_position_has_lane_position(self.road_object);
187        let lane_position = if has_lane {
188            Some((
189                maliput_sys::api::objects::ffi::RoadObject_position_lane_id(self.road_object),
190                maliput_sys::api::objects::ffi::RoadObject_position_lane_s(self.road_object),
191                maliput_sys::api::objects::ffi::RoadObject_position_lane_r(self.road_object),
192                maliput_sys::api::objects::ffi::RoadObject_position_lane_h(self.road_object),
193            ))
194        } else {
195            None
196        };
197        RoadObjectPosition {
198            inertial_position: crate::api::InertialPosition { ip: inertial_position },
199            lane_position,
200        }
201    }
202
203    /// Returns the orientation of this road object in the inertial frame.
204    pub fn orientation(&self) -> crate::api::Rotation {
205        let rotation = maliput_sys::api::objects::ffi::RoadObject_orientation(self.road_object);
206        crate::api::Rotation { r: rotation }
207    }
208
209    /// Returns the bounding box of this road object.
210    pub fn bounding_box(&self) -> crate::math::BoundingBox {
211        let b = maliput_sys::api::objects::ffi::RoadObject_bounding_box(self.road_object);
212        crate::math::BoundingBox { b }
213    }
214
215    /// Returns whether this road object is dynamic (i.e., may change position or state).
216    pub fn is_dynamic(&self) -> bool {
217        maliput_sys::api::objects::ffi::RoadObject::is_dynamic(self.road_object)
218    }
219
220    /// Returns the IDs of lanes related to this road object.
221    pub fn related_lanes(&self) -> Vec<String> {
222        maliput_sys::api::objects::ffi::RoadObject_related_lanes(self.road_object)
223    }
224
225    /// Returns the number of outlines of this road object.
226    pub fn num_outlines(&self) -> i32 {
227        maliput_sys::api::objects::ffi::RoadObject::num_outlines(self.road_object)
228    }
229
230    /// Returns the outlines of this road object.
231    pub fn outlines(&self) -> Vec<Outline<'_>> {
232        maliput_sys::api::objects::ffi::RoadObject_outlines(self.road_object)
233            .into_iter()
234            .map(|ptr| Outline {
235                outline: unsafe { ptr.outline.as_ref().expect("Outline pointer is null") },
236            })
237            .collect()
238    }
239
240    /// Returns the key-value properties of this road object.
241    pub fn properties(&self) -> HashMap<String, String> {
242        maliput_sys::api::objects::ffi::RoadObject_properties(self.road_object)
243            .into_iter()
244            .map(|p| (p.key, p.value))
245            .collect()
246    }
247}
248
249/// Interface for accessing [RoadObject]s in the road network.
250pub struct RoadObjectBook<'a> {
251    pub(super) road_object_book: &'a maliput_sys::api::objects::ffi::RoadObjectBook,
252}
253
254impl<'a> RoadObjectBook<'a> {
255    /// Returns all [RoadObject]s in the book.
256    pub fn road_objects(&self) -> Vec<RoadObject<'_>> {
257        maliput_sys::api::objects::ffi::RoadObjectBook_RoadObjects(self.road_object_book)
258            .into_iter()
259            .map(|ptr| RoadObject {
260                road_object: unsafe { ptr.road_object.as_ref().expect("RoadObject pointer is null") },
261            })
262            .collect()
263    }
264
265    /// Returns the [RoadObject] with the given `id`, or `None` if not found.
266    pub fn get_road_object(&self, id: &String) -> Option<RoadObject<'_>> {
267        let ptr = maliput_sys::api::objects::ffi::RoadObjectBook_GetRoadObject(self.road_object_book, id);
268        if ptr.is_null() {
269            return None;
270        }
271        Some(RoadObject {
272            road_object: unsafe { ptr.as_ref().expect("Unable to get underlying RoadObject pointer") },
273        })
274    }
275
276    /// Returns all [RoadObject]s of the given [RoadObjectType].
277    pub fn find_by_type(&self, obj_type: &RoadObjectType) -> Vec<RoadObject<'_>> {
278        let obj_type_ffi = road_object_type_to_cpp(obj_type);
279        maliput_sys::api::objects::ffi::RoadObjectBook_FindByType(self.road_object_book, obj_type_ffi)
280            .into_iter()
281            .map(|ptr| RoadObject {
282                road_object: unsafe { ptr.road_object.as_ref().expect("RoadObject pointer is null") },
283            })
284            .collect()
285    }
286
287    /// Returns all [RoadObject]s whose `related_lanes()` includes the given lane ID.
288    pub fn find_by_lane(&self, lane_id: &String) -> Vec<RoadObject<'_>> {
289        maliput_sys::api::objects::ffi::RoadObjectBook_FindByLane(self.road_object_book, lane_id)
290            .into_iter()
291            .map(|ptr| RoadObject {
292                road_object: unsafe { ptr.road_object.as_ref().expect("RoadObject pointer is null") },
293            })
294            .collect()
295    }
296
297    /// Returns all [RoadObject]s within `radius` meters of position `(x, y, z)`.
298    pub fn find_in_radius(&self, x: f64, y: f64, z: f64, radius: f64) -> Vec<RoadObject<'_>> {
299        maliput_sys::api::objects::ffi::RoadObjectBook_FindInRadius(self.road_object_book, x, y, z, radius)
300            .into_iter()
301            .map(|ptr| RoadObject {
302                road_object: unsafe { ptr.road_object.as_ref().expect("RoadObject pointer is null") },
303            })
304            .collect()
305    }
306}