1use std::collections::HashMap;
32
33#[derive(Debug, Copy, Clone, PartialEq, Eq)]
34pub 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
91pub struct RoadObjectPosition {
96 pub inertial_position: crate::api::InertialPosition,
97 pub lane_position: Option<(String, f64, f64, f64)>,
98}
99
100pub struct OutlineCorner {
104 pub x: f64,
105 pub y: f64,
106 pub z: f64,
107 pub height: Option<f64>,
108}
109
110pub struct Outline<'a> {
112 pub(crate) outline: &'a maliput_sys::api::objects::ffi::Outline,
113}
114
115impl<'a> Outline<'a> {
116 pub fn id(&self) -> String {
118 maliput_sys::api::objects::ffi::Outline_id(self.outline)
119 }
120
121 pub fn is_closed(&self) -> bool {
123 maliput_sys::api::objects::ffi::Outline_is_closed(self.outline)
124 }
125
126 pub fn num_corners(&self) -> i32 {
128 maliput_sys::api::objects::ffi::Outline_num_corners(self.outline)
129 }
130
131 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
145pub struct RoadObject<'a> {
150 pub(crate) road_object: &'a maliput_sys::api::objects::ffi::RoadObject,
151}
152
153impl<'a> RoadObject<'a> {
154 pub fn id(&self) -> String {
156 maliput_sys::api::objects::ffi::RoadObject_id(self.road_object)
157 }
158
159 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 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 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 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 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 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 pub fn is_dynamic(&self) -> bool {
217 maliput_sys::api::objects::ffi::RoadObject::is_dynamic(self.road_object)
218 }
219
220 pub fn related_lanes(&self) -> Vec<String> {
222 maliput_sys::api::objects::ffi::RoadObject_related_lanes(self.road_object)
223 }
224
225 pub fn num_outlines(&self) -> i32 {
227 maliput_sys::api::objects::ffi::RoadObject::num_outlines(self.road_object)
228 }
229
230 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 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
249pub struct RoadObjectBook<'a> {
251 pub(super) road_object_book: &'a maliput_sys::api::objects::ffi::RoadObjectBook,
252}
253
254impl<'a> RoadObjectBook<'a> {
255 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 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 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 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 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}