maliput_sys/api/objects/
mod.rs1#[cxx::bridge(namespace = "maliput::api::objects")]
32#[allow(clippy::needless_lifetimes)] pub mod ffi {
34 struct ConstRoadObjectPtr {
37 pub road_object: *const RoadObject,
38 }
39 struct ConstOutlinePtr {
42 pub outline: *const Outline,
43 }
44 struct ConstRoadMarkingPtr {
47 pub road_marking: *const RoadMarking,
48 }
49 struct RoadMarkingValueData {
52 pub has_value: bool,
53 pub value: f64,
54 pub unit: RoadMarkingValueUnit,
55 }
56 struct OutlineCornerData {
60 pub x: f64,
61 pub y: f64,
62 pub z: f64,
63 pub has_height: bool,
64 pub height: f64,
65 }
66 struct StringPair {
69 pub key: String,
70 pub value: String,
71 }
72
73 #[repr(i32)]
77 enum RoadObjectType {
78 kUnknown = 0,
79 kBarrier,
80 kGuardWall,
81 kGuardRail,
82 kBuilding,
83 kGantry,
84 kObstacle,
85 kPole,
86 kTrafficIsland,
87 kTree,
88 kVegetation,
89 }
90
91 #[repr(i32)]
95 enum RoadMarkingType {
96 kStop = 0,
97 kStopLine,
98 kCrosswalk,
99 kParkingSpace,
100 kEmergencyLane,
101 kSpeedLimit,
102 kDoNotStop,
103 kRailRoad,
104 kGiveWay,
105 kArrowTurnRight,
106 kArrowTurnLeft,
107 kArrowForwardTurnRight,
108 kArrowForwardTurnLeft,
109 kArrowForward,
110 kArrowForwardTurnRightTurnLeft,
111 kArrowTurnRightTurnLeft,
112 kArrowUTurnRight,
113 kArrowUTurnLeft,
114 kUnknown,
115 }
116
117 #[repr(i32)]
120 enum RoadMarkingValueUnit {
121 kMetersPerSecond = 0,
122 kKilometersPerHour,
123 kMilesPerHour,
124 }
125
126 unsafe extern "C++" {
127 include!("api/objects/objects.h");
128 include!("cxx_utils/error_handling.h");
129
130 #[namespace = "maliput::api"]
132 type InertialPosition = crate::api::ffi::InertialPosition;
133 #[namespace = "maliput::api"]
134 type Rotation = crate::api::ffi::Rotation;
135 #[namespace = "maliput::math"]
136 type Vector3 = crate::math::ffi::Vector3;
137 #[namespace = "maliput::math"]
138 type BoundingBox = crate::math::ffi::BoundingBox;
139 #[namespace = "maliput::api::rules"]
141 type StringWrapper = crate::api::rules::ffi::StringWrapper;
142
143 type RoadObjectType;
145
146 type RoadObjectBook;
148 fn RoadObjectBook_RoadObjects(book: &RoadObjectBook) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
149 fn RoadObjectBook_GetRoadObject(book: &RoadObjectBook, id: &String) -> *const RoadObject;
150 fn RoadObjectBook_FindByType(
151 book: &RoadObjectBook,
152 obj_type: RoadObjectType,
153 ) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
154 fn RoadObjectBook_FindByLane(
155 book: &RoadObjectBook,
156 lane_id: &String,
157 ) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
158 fn RoadObjectBook_FindInRadius(
159 book: &RoadObjectBook,
160 x: f64,
161 y: f64,
162 z: f64,
163 radius: f64,
164 ) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
165
166 type RoadObject;
168 fn RoadObject_id(obj: &RoadObject) -> String;
169 fn RoadObject_name(obj: &RoadObject) -> UniquePtr<StringWrapper>;
170 fn RoadObject_object_type(obj: &RoadObject) -> RoadObjectType;
173 fn RoadObject_subtype(obj: &RoadObject) -> UniquePtr<StringWrapper>;
174 fn RoadObject_position_inertial(obj: &RoadObject) -> UniquePtr<InertialPosition>;
175 fn RoadObject_position_has_lane_position(obj: &RoadObject) -> bool;
176 fn RoadObject_position_lane_id(obj: &RoadObject) -> String;
177 fn RoadObject_position_lane_s(obj: &RoadObject) -> f64;
178 fn RoadObject_position_lane_r(obj: &RoadObject) -> f64;
179 fn RoadObject_position_lane_h(obj: &RoadObject) -> f64;
180 fn RoadObject_orientation(obj: &RoadObject) -> UniquePtr<Rotation>;
181 fn RoadObject_bounding_box(obj: &RoadObject) -> UniquePtr<BoundingBox>;
182 fn is_dynamic(self: &RoadObject) -> bool;
183 fn is_movable(self: &RoadObject) -> bool;
184 fn RoadObject_related_lanes(obj: &RoadObject) -> Vec<String>;
185 fn num_outlines(self: &RoadObject) -> i32;
186 fn RoadObject_outlines(obj: &RoadObject) -> UniquePtr<CxxVector<ConstOutlinePtr>>;
187 fn RoadObject_properties(obj: &RoadObject) -> Vec<StringPair>;
188
189 type Outline;
191 fn Outline_id(outline: &Outline) -> String;
192 fn Outline_is_closed(outline: &Outline) -> bool;
193 fn Outline_num_corners(outline: &Outline) -> i32;
194 fn Outline_corners(outline: &Outline) -> Vec<OutlineCornerData>;
195
196 type RoadMarkingType;
198 type RoadMarkingValueUnit;
200
201 type RoadMarkingBook;
203 fn RoadMarkingBook_RoadMarkings(book: &RoadMarkingBook) -> UniquePtr<CxxVector<ConstRoadMarkingPtr>>;
204 fn RoadMarkingBook_GetRoadMarking(book: &RoadMarkingBook, id: &String) -> *const RoadMarking;
205 fn RoadMarkingBook_FindByLane(
206 book: &RoadMarkingBook,
207 lane_id: &String,
208 ) -> UniquePtr<CxxVector<ConstRoadMarkingPtr>>;
209 fn RoadMarkingBook_FindByType(
210 book: &RoadMarkingBook,
211 marking_type: RoadMarkingType,
212 ) -> UniquePtr<CxxVector<ConstRoadMarkingPtr>>;
213
214 type RoadMarking;
216 fn RoadMarking_id(marking: &RoadMarking) -> String;
217 fn RoadMarking_name(marking: &RoadMarking) -> UniquePtr<StringWrapper>;
218 fn RoadMarking_marking_type(marking: &RoadMarking) -> RoadMarkingType;
220 fn RoadMarking_position_inertial(marking: &RoadMarking) -> UniquePtr<InertialPosition>;
221 fn RoadMarking_position_has_lane_position(marking: &RoadMarking) -> bool;
222 fn RoadMarking_position_lane_id(marking: &RoadMarking) -> String;
223 fn RoadMarking_position_lane_s(marking: &RoadMarking) -> f64;
224 fn RoadMarking_position_lane_r(marking: &RoadMarking) -> f64;
225 fn RoadMarking_position_lane_h(marking: &RoadMarking) -> f64;
226 fn RoadMarking_orientation(marking: &RoadMarking) -> UniquePtr<Rotation>;
227 fn RoadMarking_bounding_box(marking: &RoadMarking) -> UniquePtr<BoundingBox>;
228 fn RoadMarking_related_lanes(marking: &RoadMarking) -> Vec<String>;
229 fn num_outlines(self: &RoadMarking) -> i32;
230 fn RoadMarking_outlines(marking: &RoadMarking) -> UniquePtr<CxxVector<ConstOutlinePtr>>;
231 fn RoadMarking_value(marking: &RoadMarking) -> RoadMarkingValueData;
232 }
233}