Expand description
§maliput
Creates Rustacean API for maliput.
It is implemented on top of maliput-sys
package.
Note: What is maliput? Refer to https://maliput.readthedocs.org.
§Description
maliput
provides a Rust API implemented on top of FFI bindings provided by maliput-sys
package.
§Usage
use maliput::api::RoadNetwork;
use std::collections::HashMap;
fn main() -> Result<(), Box<dyn std::error::Error>> {
// 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()),
]);
let road_network = RoadNetwork::new("maliput_malidrive", &road_network_properties)?;
let road_geometry = road_network.road_geometry();
// Exercise the RoadGeometry API.
println!("linear_tolerance: {}", road_geometry.linear_tolerance());
println!("angular_tolerance: {}", road_geometry.angular_tolerance());
println!("num_junctions: {}", road_geometry.num_junctions());
let lanes = road_geometry.get_lanes();
println!("num_lanes: {}", lanes.len());
println!("lanes: ");
for lane in lanes {
println!("\tlane id: {}", lane.id());
}
Ok(())
}
§Apps
-
maliput_query
: A command-line tool for interactively querying a road network. It loads a road network from an OpenDRIVE file and provides a set of commands to inspect its geometric properties and perform coordinate transformations.To run the application:
cargo run --bin maliput_query -- <path_to_xodr_file>
For example, using one of the provided XODR files:
cargo run --bin maliput_query -- data/xodr/TShapeRoad.xodr
§Examples
- Load
maliput::api::RoadNetwork
and perform some basic queries against the Road Geometry.cargo run --example 01_road_geometry
§Benches
- Evaluate the execution of
maliput::api::RoadGeometry::to_road_position
method.cargo bench to_road_position
§License
Licensed under BSD 3-Clause.
Modules§
Structs§
- Resource
Manager - ResourceManager