Getting Started

This page will help you out getting started with the library.

Warning

Please go to the Installation page before you start.

As explained in the Maliput Overview page, maliput package is an API which implementation is provided by a backend. At the moment there are four different implementations: maliput_dragway, maliput_multilane, maliput_malidrive and maliput_osm.

The maliput_malidrive implementation is the one that provides more feature support, so it is the recommended choice.

The Basics

Loading a RoadNetwork

The maliput::api::RoadNetwork is the main entity from a hierarchical point of view point. It aggregates everything pertaining to Maliput. Once a road network is loaded, you can access its elements:

There are two ways of loading a RoadNetwork:

Let’s focus on the first way of loading a road network.

Load a maliput_malidrive RoadNetwork

  1. Configure your project to correctly link to maliput’s libraries, whether your are using CMake or Bazel:

1find_package(maliput)
2find_package(maliput_malidrive)
3# ...
4# ...
5target_link_libraries(<your_target>
6  maliput::api
7  maliput_malidrive::loader
8)
  1. Relies on the maliput_malidrive’s loader for loading the maliput::api::RoadNetwork:

1std::map<std::string, std::string> road_network_configuration;
2road_network_configuration.emplace("opendrive_file", "<path_to_xodr_file>");
3auto road_network = malidrive::loader::Load<malidrive::builder::RoadNetworkBuilder>(road_network_configuration);

There are several parameters that can be passed to the maliput_malidrive loader. In this case, opendrive_file parameters is suggested as the maliput_malidrive relies on the OpenDRIVE standard for describing road networks. You can check all the maliput_malidrive’s parameters at Road Network Configuration Builder keys

maliput_malidrive package provides several XODR files as resources and they available at /opt/ros/<ROS_DISTRO>/share/maliput_malidrive/resources/odr, for this case we could replace then <path_to_xodr_file> by /opt/ros/<ROS_DISTRO>/share/maliput_malidrive/resources/odr/TShapeRoad.xodr

Note

maliput_malidrive package adds an environment variable called MALIPUT_MALIDRIVE_RESOURCE_ROOT that points to resources’s root folder.

Loading a RoadNetwork via Maliput Plugin Architecture

  1. If you are using CMake, link to maliput library:

1find_package(maliput)
2# ...
3target_link_libraries(<your_target>
4  maliput::api
5  maliput::plugin
6)

We link against maliput::api and maliput::plugin for using the plugin interface. Note that we aren’t linking against any maliput backend(maliput_malidrive in this case). The plugin architecture is in charge of loading the backend at runtime.

  1. Use maliput::plugin’s convenient method for loading a maliput::api::RoadNetwork instance.

1// ...
2#include <maliput/api/road_network.h>
3#include <maliput/plugin/create_road_network.h>
4
5const std::string road_network_loader_id = "maliput_malidrive";
6std::map<std::string, std::string> road_network_configuration;
7road_network_configuration.emplace("opendrive_file", "<path_to_xodr_file>");
8// Use maliput plugin interface for loading a road network
9std::unique_ptr<maliput::api::RoadNetwork> road_network = maliput::plugin::CreateRoadNetwork(road_network_loader_id, road_network_configuration);

The maliput’s implementation, maliput_malidrive in this case, is loaded in runtime. Therefore, no need to link to maliput_malidrive library.

See Maliput Plugin Architecture for further information.

Querying the RoadGeometry

1const maliput::api::RoadGeometry* road_geometry = road_network->road_geometry();
2const maliput::api::Lane* lane = road_geometry->ById.GetLane(maliput::api::LaneId{"1_0_1"});
1const maliput::api::RoadGeometry* road_geometry = road_network->road_geometry();
2const maliput::api::RoadPositionResult road_position_result = road_geometry->ToRoadPosition(maliput::api::InertialPosition{10.0, 0.0, 0.0});;
3const maliput::api::Lane* lane = road_poisition_result.road_position.lane;
1const maliput::api::RoadGeometry* road_geometry = road_network->road_geometry();
2maliput::api::InertialPosition inertial_position = lane->ToInertialPosition(maliput::api::LanePosition{0.0, 0.0, 0.0});

For a complete maliput api reference please visit: maliput::api

Maliput Python Interface

maliput_py package provides bindings to the maliput library. See Maliput Python Interface for general information about the maliput python interface

Load a maliput_malidrive RoadNetwork

It is required to have maliput and at least one backend installed, e.g. maliput_malidrive , to use the python interface. It is possible to install them via ROS 2 Repositories or PyPI.

Note

Please refer to Installation for installing the packages via binaries.

1import maliput.api
2import maliput.plugin
3
4import os
5
6configuration = {"opendrive_file" : os.getenv("MALIPUT_MALIDRIVE_RESOURCE_ROOT") + "/resources/odr/TShapeRoad.xodr"}
7road_network = maliput.plugin.create_road_network("maliput_malidrive", configuration)
8print(road_network.road_geometry().id())

Maliput Visualizer

maliput_viz package provides a visualizer for maliput RoadNetworks. Via its GUI it is possible to select which maliput backend to use and what are the parameters to be passed to the loader of the particular backend.

Several aspects of the road network can be visualized:
  • Lane info: Information about the selected lane.

  • Rules: Information about rules applying to the selected lane.

  • Traffic Lights: Traffic lights are shown in the visualizer.

  • Phases: When PhaseRings are loaded in the visualizer, the current phase can be selected.

To run the visualizer simply execute:

maliput_viz

Note

It is possible to load the visualizer with a specific backend and configuration. Execute maliput_viz –help for further information about the available options.

The backend discovery is achieved via the plugin architecture. (See Maliput Plugin Architecture for further information). In a way that the users can create their own backend and load it via the visualizer GUI.

Advanced

Traffic Lights

maliput models traffic lights via maliput::api::rules::TrafficLight. It contains one or more groups of light bulbs with varying colors and shapes. Note that traffic lights are physical manifestations of underlying right-of-way rules.

  • maliput::api::rules::TrafficLight: A TrafficLight models the signaling device that are typically located at road intersections. It is composed by one or more groups of light bulbs called BulbGroup. For each TrafficLight an unique id and a pose in the Inertial-frame is defined.

  • maliput::api::rules::BulbGroup: A BulbGroup models a group of light bulbs within a traffic light. Pose is relative to the traffic light that holds it.

  • maliput::api::rules::Bulb: A Bulb models a light bulb within a BulbGroup. The pose is relative to the BulbGroup it belongs. Each Bulb has a collection of possible states (e.g: On, Off, Blinking).

maliput::api::rules::TrafficLightBook is an interface that allows getting the traffic lights according their ids.

Loading a TrafficLightBook

maliput provides a base implementation of the maliput::api::rules::TrafficLightBook, which can be used for adding maliput::api::rules::TrafficLight s to the book. However, the most convenient way of populating this book is to load it via YAML file by using the maliput::LoadTrafficLightBookFromFile method.

As example, we will use the maliput_malidrive backend, which fully supports maliput’s API.

 1// ...
 2#include <maliput/api/road_network.h>
 3#include <maliput/plugin/create_road_network.h>
 4
 5const std::string road_network_loader_id = "maliput_malidrive";
 6const std::string resources_path = std::string(std::getenv("MALIPUT_MALIDRIVE_RESOURCE_ROOT")) + "/resources/odr";
 7std::map<std::string, std::string> road_network_configuration;
 8road_network_configuration.emplace("opendrive_file", resources_path + "/LoopRoadPedestrianCrosswalk.xodr");
 9road_network_configuration.emplace("traffic_light_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
10auto road_network = maliput::plugin::CreateRoadNetwork(road_network_loader_id, road_network_configuration);

While the LoopRoadPedestrianCrosswalk.xodr file contains the road network description using the OpenDRIVE format specification, the LoopRoadPedestrianCrosswalk.yaml describes other aspects of the road network using the YAML format specification. For the moment, we focus on the TrafficLights section using the YAML format specification.

After loading the road network we can get the TrafficLightBook from the RoadNetwork, and obtain any required information:

1// ...
2#include <maliput/api/lane_data.h>
3#include <maliput/api/rules/traffic_lights.h>
4#include <maliput/api/rules/traffic_light_book.h>
5
6// ...
7const maliput::api::rules::TrafficLightBook* book = road_network->traffic_light_book();
8const maliput::api::rules::TrafficLight::Id traffic_light_id{"WestFacingSouth"};
9const maliput::api::InertialPosition inertial_position = book->GetTrafficLight(traffic_light_id)->position_road_network();

Rules

maliput provides an API for rule support. The rules are used to model all kind of traffic rules that could be applied to a road network.

The base interface for rules is maliput::api::rules::Rule. Each rule has:

  • id: a unique identifier for the rule

  • type id: a unique identifier for the type of the rule

  • zone: a zone that the rule is applied to.

For each rule can be defined as many as states as needed. Each state is defined by:

  • severity: a severity for the state.

  • related rules: a group of rules that are related to the state.

  • related unique ids: a group of unique ids related to the state, typically used for the TrafficLights that are affected by the state.

  • value: a value for the state.

Depending on the nature of the values of the rule’s states, two kinds of rules are defined:

Rule Registry

maliput provides a registry of rules for registering a type of rule and the states they possible have.

maliput::api::rules::RuleRegistry provides a registry of the various rule types, and enables semantic validation when building rule instances.

Loading a Rule Registry

maliput provides a way to load the rule registry via a YAML file by using the maliput::LoadRuleRegistryFromFile method.

As example, we will use the maliput_malidrive backend.

 1// ...
 2#include <maliput/api/lane_data.h>
 3#include <maliput/api/road_network.h>
 4#include <maliput/api/rules/traffic_lights.h>
 5#include <maliput/api/rules/traffic_light_book.h>
 6#include <maliput/plugin/create_road_network.h>
 7
 8const std::string road_network_loader_id = "maliput_malidrive";
 9const std::string resources_path = std::string(std::getenv("MALIPUT_MALIDRIVE_RESOURCE_ROOT")) + "/resources/odr";
10std::map<std::string, std::string> road_network_configuration;
11road_network_configuration.emplace("opendrive_file", resources_path + "/LoopRoadPedestrianCrosswalk.xodr");
12road_network_configuration.emplace("traffic_light_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
13road_network_configuration.emplace("rule_registry", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
14auto road_network = maliput::plugin::CreateRoadNetwork(road_network_loader_id, road_network_configuration);

In this example, LoopRoadPedestrianCrosswalk.yaml contains a RuleRegistry section where the rules types are defined. These rules are going to be used later on by the RoadRulebook to validate the rule types.

After loading the road network, the RuleRegistry is accessible from the RoadNetwork.

1// ...
2const maliput::api::rules::RuleRegistry* rule_registry = road_network->rule_registry();
3// Obtains all the DiscreteValueRules from the registry.
4auto discrete_types = rule_registry->DiscreteValueRuleTypes();
5// Obtains all the RangeValueRules from the registry.
6auto range_types = rule_registry->RangeValueRuleTypes();

RoadRulebook

The maliput::api::rules::RoadRulebook is an interface for querying the rules in given road network. This book is expected to gathered all the available rules. It provides an API for obtaining all the rules; obtaining the rules by id; or even obtaining the rules that apply to zone in particular.

maliput provides a base implementation for loading the RoadRulebook with the rules. However, the most convenient way of populating this book is to load it via YAML file by using the maliput::LoadRoadRuleBookFromFile method.

As example, we will use the maliput_malidrive backend.

 1// ...
 2#include <maliput/api/lane_data.h>
 3#include <maliput/api/road_network.h>
 4#include <maliput/api/rules/traffic_lights.h>
 5#include <maliput/api/rules/traffic_light_book.h>
 6#include <maliput/api/rules/road_rulebook.h>
 7#include <maliput/plugin/create_road_network.h>
 8
 9const std::string road_network_loader_id = "maliput_malidrive";
10const std::string resources_path = std::string(std::getenv("MALIPUT_MALIDRIVE_RESOURCE_ROOT")) + "/resources/odr";
11std::map<std::string, std::string> road_network_configuration;
12road_network_configuration.emplace("opendrive_file", resources_path + "/LoopRoadPedestrianCrosswalk.xodr");
13road_network_configuration.emplace("traffic_light_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
14road_network_configuration.emplace("rule_registry", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
15road_network_configuration.emplace("road_rule_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
16auto road_network = maliput::plugin::CreateRoadNetwork(road_network_loader_id, road_network_configuration);

In this example, LoopRoadPedestrianCrosswalk.yaml contains a RoadRulebook section where the rules types are defined.

After loading the road network, the RoadRulebook is accessible from the RoadNetwork.

1// ...
2const maliput::api::rules::RoadRulebook* rulebook = road_network->rulebook();
3// Obtains all the rules from the book.
4auto rules = rulebook->Rules().size();
5int number_of_discrete_rules = rules.discrete_value_rules.size();
6// Obtains a discrete value rule by id.
7maliput::api::rules::Rule::Id rule_id{"Right-Of-Way Rule Type/WestToEastSouth"};
8auto discrete_rule = rulebook->GetDiscreteValueRule(rule_id);

Rule State Providers

As it was mentioned, maliput’s rule API lets the user to add rules that may contain as many states as needed. The current state of a rule may depend on certain condition. For instance, a rule state may vary on a time basis, as right-of-way rules in a intersection according to the traffic lights.

maliput defines two interfaces for getting the current state of a rule depending of the nature of the rules:

DiscreteValueRuleStateProvider

1// ...
2const maliput::api::rules::DiscreteValueRuleStateProvider* state_provider = road_network->discrete_value_rule_state_provider();
3maliput::api::rules::Rule::Id rule_id{"Right-Of-Way Rule Type/WestToEastSouth"};
4auto state_result = state_provider->GetState(rule_id);
5auto discrete_value = state_result->state;
6std::cout << discrete_value.value << std::endl;

RangeValueRuleStateProvider

1// ...
2const maliput::api::rules::RangeValueRuleStateProvider* state_provider = road_network->range_value_rule_state_provider();
3maliput::api::rules::Rule::Id rule_id{"Speed-Limit Rule Type/1_1_-1_1"};
4auto state_result = state_provider->GetState(rule_id);
5auto range_value = state_result->state;
6std::cout << range_value.min << std::endl;
7std::cout << range_value.max << std::endl;

Phases

Maliput models the sequencing of rule states and traffic lights’ bulbs as a ring of maliput::api::rules::Phase`_s. Each `Phase holds a dictionary of rule IDs to rule states (DiscreteValues) and related bulb IDs (UniqueBulbIds) to the bulb state (BulbState).

The maliput::api::rules::PhaseRing acts as a container of all the related Phases in a sequence. A designer might query them by the maliput::api::rules::Phase::Id or the next Phases, but no strict order should be expected. Instead, maliput::api::rules::PhaseProvider offers an interface to obtain the current and next Phase::Id`s for a `PhaseRing. Custom time based or event driven behaviors could be implemented for this interface. Similarly to the rules, there are convenient “manual” implementations to exercise the interfaces in integration examples.

PhaseRingBook

The PhaseRingBook is expected to contain all the PhaseRing`s in the road network. It provides an interface for obtaining the PhaseRings in the road network and some convenient queries to retrieve the PhaseRing that governs a specific `Rule::Id

maliput provides a base implementation for loading the maliput::api::rules::PhaseRingBook with the rules. However, the most convenient way of populating this book is to load it via YAML file by using the maliput::LoadPhaseRingBookFromFile method.

As example, we will use the maliput_malidrive backend.

 1// ...
 2#include <maliput/api/lane_data.h>
 3#include <maliput/api/road_network.h>
 4#include <maliput/api/rules/phase_ring_book.h>
 5#include <maliput/api/rules/traffic_lights.h>
 6#include <maliput/api/rules/traffic_light_book.h>
 7#include <maliput/api/rules/road_rulebook.h>
 8#include <maliput/plugin/create_road_network.h>
 9
10const std::string road_network_loader_id = "maliput_malidrive";
11const std::string resources_path = std::string(std::getenv("MALIPUT_MALIDRIVE_RESOURCE_ROOT")) + "/resources/odr";
12std::map<std::string, std::string> road_network_configuration;
13road_network_configuration.emplace("opendrive_file", resources_path + "/LoopRoadPedestrianCrosswalk.xodr");
14road_network_configuration.emplace("traffic_light_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
15road_network_configuration.emplace("rule_registry", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
16road_network_configuration.emplace("road_rule_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
17road_network_configuration.emplace("phase_ring_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
18auto road_network = maliput::plugin::CreateRoadNetwork(road_network_loader_id, road_network_configuration);

In this example, LoopRoadPedestrianCrosswalk.yaml contains a PhaseRings section where all the phase rings are defined.

After loading the road network, the PhaseRingBook is accessible from the RoadNetwork.

 1// ...
 2const maliput::api::rules::PhaseRingBook* phase_ring_book = road_network->phase_ring_book();
 3// Obtains all the phase rings from the book.
 4auto phase_rings = phase_ring_book->GetPhaseRings();
 5const int number_of_phase_rings = phase_rings.size();
 6// Obtains a phase ring containing the specified rule.
 7const maliput::api::rules::Rule::Id rule_id{"Right-Of-Way Rule Type/WestToEastSouth"};
 8auto phase_ring = phase_ring_book->FindPhaseRing(rule_id);
 9// Obtains a phase of that phase ring.
10const maliput::api::rules::Phase::Id phase_id{"AllGoPhase"};
11auto phase = phase_ring->GetPhase(phase_id);
12// Obtains all the discrete value rule states from the phase.
13auto discrete_value_rule_states = phase->discrete_value_rule_states();
14// Obtains all the bulb states from the phase.
15auto bulb_states = phase->bulb_states();

PhaseProvider

In a dynamic environment, phases in a phase ring are expected to change over a certain condition, such as traffic light changing its state in a time basis. maliput introduces a maliput::api::rules::PhaseProvider interface to allow the user to obtain the current phase.

1// ...
2const maliput::api::rules::PhaseProvider* phase_provider = road_network->phase_provider();
3maliput::api::rules::PhaseRing::Id phase_ring_id{"PedestrianCrosswalkIntersectionSouth"};
4auto current_phase = phase_provider->GetPhase(phase_ring_id);
5std::cout << current_phase.state << std::endl;

maliput_integration package provides an example where a dynamic environment is simulated using the PhaseProvider interface. For trying out the example please visit maliput_dynamic_environment tutorial example. The source code is located at maliput_dynamic_environment.cc

Intersection

An abstract convenience class that aggregates information pertaining to an intersection. Its primary purpose is to serve as a single source of this information and to remove the need for users to query numerous disparate data structures and state providers.

See maliput::api::Intersection’s API for more details.

IntersectionBook

The maliput::api::IntersectionBook is an interface for querying for the intersection in a given road network. This book is expected to gather all the available maliput::api::Intersection s. The API allows you to find intersections by maliput::api::Intersection, maliput::api::rules::TrafficLight or maliput::api::rules::DiscretValueRule ID and even by inertial position.

maliput provides a base implementation for loading the maliput::api::Intersection s. However, the most convenient way of populating this book is to load it via YAML file by using the maliput::LoadIntersectionBookFromFile method.

As example, we will use the maliput_malidrive backend.

 1// ...
 2#include <maliput/api/intersection_book.h>
 3#include <maliput/api/lane_data.h>
 4#include <maliput/api/road_network.h>
 5#include <maliput/api/rules/phase_ring_book.h>
 6#include <maliput/api/rules/traffic_lights.h>
 7#include <maliput/api/rules/traffic_light_book.h>
 8#include <maliput/api/rules/road_rulebook.h>
 9#include <maliput/plugin/create_road_network.h>
10
11const std::string road_network_loader_id = "maliput_malidrive";
12const std::string resources_path = std::string(std::getenv("MALIPUT_MALIDRIVE_RESOURCE_ROOT")) + "/resources/odr";
13std::map<std::string, std::string> road_network_configuration;
14road_network_configuration.emplace("opendrive_file", resources_path + "/LoopRoadPedestrianCrosswalk.xodr");
15road_network_configuration.emplace("traffic_light_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
16road_network_configuration.emplace("rule_registry", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
17road_network_configuration.emplace("road_rule_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
18road_network_configuration.emplace("phase_ring_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
19road_network_configuration.emplace("intersection_book", resources_path + "/LoopRoadPedestrianCrosswalk.yaml");
20auto road_network = maliput::plugin::CreateRoadNetwork(road_network_loader_id, road_network_configuration);

In this example, LoopRoadPedestrianCrosswalk.yaml contains a Intersections section where all the intersections are defined.

After loading the road network, the IntersectionBook is accessible from the RoadNetwork.

 1// ...
 2const maliput::api::IntersectionBook* intersection_book = road_network->intersection_book();
 3// Obtains all intersections from the book.
 4auto intersections = intersection_book->GetIntersections();
 5const auto number_of_intersections = intersections.size();
 6
 7// Obtains a intersection containing the specified traffic light.
 8const maliput::api::rules::TrafficLight::Id traffic_light_id{"WestFacingSouth"};
 9maliput::api::Intersection* traffic_light_intersection = intersection_book->FindIntersection(traffic_light_id);
10
11// Obtain a intersection containing the specified discrete value rule.
12const maliput::api::rules::DiscreteValueRule::Id discrete_value_rule_id{"Right-Of-Way Rule Type/WestToEastSouth"};
13maliput::api::Intersection* discrete_rule_intersection = intersection_book->FindIntersection(discrete_value_rule_id);
14
15// Obtains the rule states of the intersection.
16auto discrete_value_rule_states = discrete_rule_intersection->DiscreteValueRuleStates();
17// Obtains the bulb states of the intersection.
18auto bulb_states = discrete_rule_intersection->bulb_states();

Further readings

Maliput Design contains addition information about the API in case you are interested in the details.