#[cxx::bridge(namespace = "maliput::api::objects")]
#[allow(clippy::needless_lifetimes)] pub mod ffi {
struct ConstRoadObjectPtr {
pub road_object: *const RoadObject,
}
struct ConstOutlinePtr {
pub outline: *const Outline,
}
struct ConstRoadMarkingPtr {
pub road_marking: *const RoadMarking,
}
struct RoadMarkingValueData {
pub has_value: bool,
pub value: f64,
pub unit: RoadMarkingValueUnit,
}
struct OutlineCornerData {
pub x: f64,
pub y: f64,
pub z: f64,
pub has_height: bool,
pub height: f64,
}
struct StringPair {
pub key: String,
pub value: String,
}
#[repr(i32)]
enum RoadObjectType {
kUnknown = 0,
kBarrier,
kBuilding,
kGantry,
kObstacle,
kPole,
kTrafficIsland,
kTree,
kVegetation,
}
#[repr(i32)]
enum RoadMarkingType {
kStop = 0,
kStopLine,
kCrosswalk,
kParkingSpace,
kEmergencyLane,
kSpeedLimit,
kDoNotStop,
kRailRoad,
kGiveWay,
kArrowTurnRight,
kArrowTurnLeft,
kArrowForwardTurnRight,
kArrowForwardTurnLeft,
kArrowForward,
kArrowForwardTurnRightTurnLeft,
kArrowTurnRightTurnLeft,
kArrowUTurnRight,
kArrowUTurnLeft,
kUnknown,
}
#[repr(i32)]
enum RoadMarkingValueUnit {
kMetersPerSecond = 0,
kKilometersPerHour,
kMilesPerHour,
}
unsafe extern "C++" {
include!("api/objects/objects.h");
include!("cxx_utils/error_handling.h");
#[namespace = "maliput::api"]
type InertialPosition = crate::api::ffi::InertialPosition;
#[namespace = "maliput::api"]
type Rotation = crate::api::ffi::Rotation;
#[namespace = "maliput::math"]
type Vector3 = crate::math::ffi::Vector3;
#[namespace = "maliput::math"]
type BoundingBox = crate::math::ffi::BoundingBox;
#[namespace = "maliput::api::rules"]
type StringWrapper = crate::api::rules::ffi::StringWrapper;
type RoadObjectType;
type RoadObjectBook;
fn RoadObjectBook_RoadObjects(book: &RoadObjectBook) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
fn RoadObjectBook_GetRoadObject(book: &RoadObjectBook, id: &String) -> *const RoadObject;
fn RoadObjectBook_FindByType(
book: &RoadObjectBook,
obj_type: RoadObjectType,
) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
fn RoadObjectBook_FindByLane(
book: &RoadObjectBook,
lane_id: &String,
) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
fn RoadObjectBook_FindInRadius(
book: &RoadObjectBook,
x: f64,
y: f64,
z: f64,
radius: f64,
) -> UniquePtr<CxxVector<ConstRoadObjectPtr>>;
type RoadObject;
fn RoadObject_id(obj: &RoadObject) -> String;
fn RoadObject_name(obj: &RoadObject) -> UniquePtr<StringWrapper>;
fn RoadObject_object_type(obj: &RoadObject) -> RoadObjectType;
fn RoadObject_subtype(obj: &RoadObject) -> UniquePtr<StringWrapper>;
fn RoadObject_position_inertial(obj: &RoadObject) -> UniquePtr<InertialPosition>;
fn RoadObject_position_has_lane_position(obj: &RoadObject) -> bool;
fn RoadObject_position_lane_id(obj: &RoadObject) -> String;
fn RoadObject_position_lane_s(obj: &RoadObject) -> f64;
fn RoadObject_position_lane_r(obj: &RoadObject) -> f64;
fn RoadObject_position_lane_h(obj: &RoadObject) -> f64;
fn RoadObject_orientation(obj: &RoadObject) -> UniquePtr<Rotation>;
fn RoadObject_bounding_box(obj: &RoadObject) -> UniquePtr<BoundingBox>;
fn is_dynamic(self: &RoadObject) -> bool;
fn RoadObject_related_lanes(obj: &RoadObject) -> Vec<String>;
fn num_outlines(self: &RoadObject) -> i32;
fn RoadObject_outlines(obj: &RoadObject) -> UniquePtr<CxxVector<ConstOutlinePtr>>;
fn RoadObject_properties(obj: &RoadObject) -> Vec<StringPair>;
type Outline;
fn Outline_id(outline: &Outline) -> String;
fn Outline_is_closed(outline: &Outline) -> bool;
fn Outline_num_corners(outline: &Outline) -> i32;
fn Outline_corners(outline: &Outline) -> Vec<OutlineCornerData>;
type RoadMarkingType;
type RoadMarkingValueUnit;
type RoadMarkingBook;
fn RoadMarkingBook_RoadMarkings(book: &RoadMarkingBook) -> UniquePtr<CxxVector<ConstRoadMarkingPtr>>;
fn RoadMarkingBook_GetRoadMarking(book: &RoadMarkingBook, id: &String) -> *const RoadMarking;
fn RoadMarkingBook_FindByLane(
book: &RoadMarkingBook,
lane_id: &String,
) -> UniquePtr<CxxVector<ConstRoadMarkingPtr>>;
fn RoadMarkingBook_FindByType(
book: &RoadMarkingBook,
marking_type: RoadMarkingType,
) -> UniquePtr<CxxVector<ConstRoadMarkingPtr>>;
type RoadMarking;
fn RoadMarking_id(marking: &RoadMarking) -> String;
fn RoadMarking_name(marking: &RoadMarking) -> UniquePtr<StringWrapper>;
fn RoadMarking_marking_type(marking: &RoadMarking) -> RoadMarkingType;
fn RoadMarking_position_inertial(marking: &RoadMarking) -> UniquePtr<InertialPosition>;
fn RoadMarking_position_has_lane_position(marking: &RoadMarking) -> bool;
fn RoadMarking_position_lane_id(marking: &RoadMarking) -> String;
fn RoadMarking_position_lane_s(marking: &RoadMarking) -> f64;
fn RoadMarking_position_lane_r(marking: &RoadMarking) -> f64;
fn RoadMarking_position_lane_h(marking: &RoadMarking) -> f64;
fn RoadMarking_orientation(marking: &RoadMarking) -> UniquePtr<Rotation>;
fn RoadMarking_bounding_box(marking: &RoadMarking) -> UniquePtr<BoundingBox>;
fn RoadMarking_related_lanes(marking: &RoadMarking) -> Vec<String>;
fn num_outlines(self: &RoadMarking) -> i32;
fn RoadMarking_outlines(marking: &RoadMarking) -> UniquePtr<CxxVector<ConstOutlinePtr>>;
fn RoadMarking_value(marking: &RoadMarking) -> RoadMarkingValueData;
}
}