pub struct RoadNetwork { /* private fields */ }
Expand description
Represents a complete Maliput road network.
A RoadNetwork
is the main entry point for interacting with a road map in Maliput.
It serves as a container for all the elements that describe a road network,
including its physical layout and the rules of the road.
It provides access to the following key components:
RoadGeometry
: The geometric description of the road surfaces.rules::RoadRulebook
: The set of traffic rules, like speed limits and right-of-way.rules::TrafficLightBook
: A catalog of all traffic lights in the network.IntersectionBook
: A collection of logical intersections and their states. TODO: Complete with other books when available (e.g., `RuleRegistry / PhaseRingBook / etc)
More info can be found at https://maliput.readthedocs.io/en/latest/html/deps/maliput/html/maliput_design.html.
§Example
use maliput::api::RoadNetwork;
use std::collections::HashMap;
// Properties to load an OpenDRIVE file using the "maliput_malidrive" backend.
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())]);
// Create the RoadNetwork by specifying the loader ID and properties.
let road_network = RoadNetwork::new("maliput_malidrive", &road_network_properties).unwrap();
Implementations§
Source§impl RoadNetwork
impl RoadNetwork
Sourcepub fn new(
road_network_loader_id: &str,
properties: &HashMap<&str, &str>,
) -> Result<RoadNetwork, MaliputError>
pub fn new( road_network_loader_id: &str, properties: &HashMap<&str, &str>, ) -> Result<RoadNetwork, MaliputError>
Create a new RoadNetwork
with the given road_network_loader_id
and properties
.
§Arguments
road_network_loader_id
- The id of the road network loader. It identifies the backend to be used (e.g., “maliput_malidrive”).properties
- The properties of the road network.
§Details
It relies on maliput_sys::plugin::ffi::CreateRoadNetwork
to create a new RoadNetwork
.
§Returns
A result containing the RoadNetwork
or a MaliputError
if the creation fails.
Sourcepub fn road_geometry(&self) -> RoadGeometry<'_>
pub fn road_geometry(&self) -> RoadGeometry<'_>
Get the RoadGeometry
of the RoadNetwork
.
Sourcepub fn intersection_book(&mut self) -> IntersectionBook<'_>
pub fn intersection_book(&mut self) -> IntersectionBook<'_>
Get the IntersectionBook
of the RoadNetwork
.
Sourcepub fn traffic_light_book(&self) -> TrafficLightBook<'_>
pub fn traffic_light_book(&self) -> TrafficLightBook<'_>
Get the TrafficLightBook
of the RoadNetwork
.
Sourcepub fn rulebook(&self) -> RoadRulebook<'_>
pub fn rulebook(&self) -> RoadRulebook<'_>
Get the RoadRulebook
of the RoadNetwork
.