Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adds Rust API for Lane, RoadPosition, RoadPositionResult. #39

Merged
merged 2 commits into from
Mar 14, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 32 additions & 0 deletions maliput-sys/src/api/api.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include <memory>
#include <sstream>

#include <maliput/api/lane.h>
#include <maliput/api/lane_data.h>
#include <maliput/api/road_network.h>
#include <maliput/api/road_geometry.h>
Expand Down Expand Up @@ -84,6 +85,37 @@ bool InertialPosition_operator_eq(const InertialPosition& lhs, const InertialPos
return lhs == rhs;
}

rust::String Lane_id(const Lane& lane) {
return lane.id().string();
}

std::unique_ptr<RoadPosition> RoadPosition_new(const Lane* lane, const LanePosition& pos) {
return std::make_unique<RoadPosition>(lane, pos);
}

std::unique_ptr<InertialPosition> RoadPosition_ToInertialPosition(const RoadPosition& road_pos) {
return std::make_unique<InertialPosition>(road_pos.ToInertialPosition());
}

const Lane* RoadPosition_lane(const RoadPosition& road_pos) {
return road_pos.lane;
}

std::unique_ptr<LanePosition> RoadPosition_pos(const RoadPosition& road_pos) {
return std::make_unique<LanePosition>(road_pos.pos);
}

std::unique_ptr<RoadPosition> RoadPositionResult_road_position(const RoadPositionResult& road_pos_res) {
return std::make_unique<RoadPosition>(road_pos_res.road_position);
}

std::unique_ptr<InertialPosition> RoadPositionResult_nearest_position (const RoadPositionResult& road_pos_res) {
return std::make_unique<InertialPosition>(road_pos_res.nearest_position);
}

double RoadPositionResult_distance(const RoadPositionResult& road_pos_res) {
return road_pos_res.distance;
}

} // namespace api
} // namespace maliput
21 changes: 21 additions & 0 deletions maliput-sys/src/api/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,27 @@ pub mod ffi {
-> UniquePtr<InertialPosition>;
fn InertialPosition_operator_mul_scalar(lhs: &InertialPosition, scalar: f64) -> UniquePtr<InertialPosition>;

// Lane bindings definitions
type Lane;
fn to_left(self: &Lane) -> *const Lane;
fn to_right(self: &Lane) -> *const Lane;
fn length(self: &Lane) -> f64;
fn Lane_id(lane: &Lane) -> String;

// RoadPosition bindings definitions
type RoadPosition;
/// # Safety
/// This function is unsafe because it dereferences `lane` pointers.
unsafe fn RoadPosition_new(lane: *const Lane, lane_pos: &LanePosition) -> UniquePtr<RoadPosition>;
fn RoadPosition_ToInertialPosition(road_position: &RoadPosition) -> UniquePtr<InertialPosition>;
fn RoadPosition_lane(road_position: &RoadPosition) -> *const Lane;
fn RoadPosition_pos(road_position: &RoadPosition) -> UniquePtr<LanePosition>;

// RoadPositionResult bindings definitions
type RoadPositionResult;
fn RoadPositionResult_road_position(result: &RoadPositionResult) -> UniquePtr<RoadPosition>;
fn RoadPositionResult_nearest_position(result: &RoadPositionResult) -> UniquePtr<InertialPosition>;
fn RoadPositionResult_distance(result: &RoadPositionResult) -> f64;
}
impl UniquePtr<RoadNetwork> {}
impl UniquePtr<LanePosition> {}
Expand Down
98 changes: 98 additions & 0 deletions maliput/src/api/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -335,6 +335,104 @@ impl std::ops::Mul<f64> for InertialPosition {
}
}

/// A maliput::api::Lane
/// Wrapper around C++ implementation `maliput::api::Lane`.
pub struct Lane<'a> {
lane: &'a maliput_sys::api::ffi::Lane,
}

impl<'a> Lane<'a> {
/// Get the left lane of the `Lane`.
pub fn to_left(&self) -> Option<Lane> {
let lane = self.lane.to_left();
if lane.is_null() {
None
} else {
unsafe {
Some(Lane {
lane: lane.as_ref().expect(""),
})
}
}
}
/// Get the right lane of the `Lane`.
pub fn to_right(&self) -> Option<Lane> {
let lane = self.lane.to_right();
if lane.is_null() {
None
} else {
unsafe {
Some(Lane {
lane: lane.as_ref().expect(""),
})
}
}
}
/// Get the length of the `Lane`.
pub fn length(&self) -> f64 {
self.lane.length()
}
/// Get the id of the `Lane` as a string.
pub fn id(&self) -> String {
maliput_sys::api::ffi::Lane_id(self.lane)
}
}

/// A maliput::api::RoadPosition
/// Wrapper around C++ implementation `maliput::api::RoadPosition`.
pub struct RoadPosition {
rp: cxx::UniquePtr<maliput_sys::api::ffi::RoadPosition>,
}

impl RoadPosition {
/// Create a new `RoadPosition` with the given `lane` and `lane_pos`.
pub fn new(lane: &Lane, lane_pos: &LanePosition) -> RoadPosition {
unsafe {
RoadPosition {
rp: maliput_sys::api::ffi::RoadPosition_new(lane.lane, &lane_pos.lp),
}
}
}
/// Get the inertial position of the `RoadPosition` via doing a Lane::ToInertialPosition query call.
pub fn to_inertial_position(&self) -> InertialPosition {
InertialPosition {
ip: maliput_sys::api::ffi::RoadPosition_ToInertialPosition(&self.rp),
}
}
/// Get the lane of the `RoadPosition`.
pub fn lane(&self) -> Lane {
unsafe {
Lane {
lane: maliput_sys::api::ffi::RoadPosition_lane(&self.rp).as_ref().expect(""),
}
}
}
/// Get the lane position of the `RoadPosition`.
pub fn pos(&self) -> LanePosition {
LanePosition {
lp: maliput_sys::api::ffi::RoadPosition_pos(&self.rp),
}
}
}

/// Represents the result of a RoadPosition query.
pub struct RoadPositionResult {
pub road_position: RoadPosition,
pub nearest_position: InertialPosition,
pub distance: f64,
}

impl RoadPositionResult {
/// Create a new `RoadPositionResult` with the given `road_position`, `nearest_position`, and `distance`.
pub fn new(road_position: RoadPosition, nearest_position: InertialPosition, distance: f64) -> RoadPositionResult {
RoadPositionResult {
road_position,
nearest_position,
distance,
}
}
}

mod tests {
mod lane_position {
#[test]
Expand Down
71 changes: 71 additions & 0 deletions maliput/tests/common/mod.rs
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// BSD 3-Clause License
//
// Copyright (c) 2024, Woven by Toyota.
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright notice, this
// list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// * Neither the name of the copyright holder nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
// DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

use maliput::api::RoadNetwork;
use std::collections::HashMap;

pub fn create_t_shape_road_network() -> RoadNetwork {
// Set MALIPUT_PLUGIN_PATH
let maliput_malidrive_plugin_path = maliput_sdk::get_maliput_malidrive_plugin_path();
std::env::set_var("MALIPUT_PLUGIN_PATH", maliput_malidrive_plugin_path);

// Get location of odr resources
let package_location = std::env::var("CARGO_MANIFEST_DIR").unwrap();
let xodr_path = format!("{}/data/xodr/TShapeRoad.xodr", package_location);

let road_network_properties = HashMap::from([
("road_geometry_id", "my_rg_from_rust"),
("opendrive_file", xodr_path.as_str()),
("linear_tolerance", "0.01"),
]);
RoadNetwork::new("maliput_malidrive", &road_network_properties)
}

#[allow(dead_code)]
pub fn assert_inertial_position_equality(
left: &maliput::api::InertialPosition,
right: &maliput::api::InertialPosition,
tolerance: f64,
) {
assert!((left.x() - right.x()).abs() < tolerance);
assert!((left.y() - right.y()).abs() < tolerance);
assert!((left.z() - right.z()).abs() < tolerance);
}

#[allow(dead_code)]
pub fn assert_lane_position_equality(
left: &maliput::api::LanePosition,
right: &maliput::api::LanePosition,
tolerance: f64,
) {
assert!((left.s() - right.s()).abs() < tolerance);
assert!((left.r() - right.r()).abs() < tolerance);
assert!((left.h() - right.h()).abs() < tolerance);
}