delphyne
|
Functions | |
const maliput::api::Lane * | FindLane (const maliput::api::LaneId &lane_id, const maliput::api::RoadGeometry &road_geometry) |
Find the lane inside the specified road geometry by id. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateRoadNetwork (const std::string &road_network_plugin_name, const std::map< std::string, std::string > &loader_parameters) |
Creates a maliput::api::RoadNetwork based on an available maliput::plugin::RoadNetworkLoader plugin implementation. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateDragway (const std::string &name, int num_lanes, double length, double lane_width, double shoulder_width, double maximum_height, double linear_tolerance=std::numeric_limits< double >::epsilon(), double angular_tolerance=std::numeric_limits< double >::epsilon()) |
Creates a dragway. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateMultilaneFromFile (const std::string &file_path) |
Creates a multilane from yaml source. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateMultilaneFromDescription (const std::string &yaml_description) |
Creates a multilane from yaml description. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateMalidriveFromXodr (const std::string &name, const std::string &file_path, double linear_tolerance=1e-3, double angular_tolerance=1e-3) |
Creates a malidrive from xodr source. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateMalidriveRoadNetworkFromXodr (const std::string &name, const std::string &file_path, const std::string &rule_registry_file_path=std::string(), const std::string &road_rulebook_file_path=std::string(), const std::string &traffic_light_book_path=std::string(), const std::string &phase_ring_path=std::string(), const std::string &intersection_book_path=std::string(), double linear_tolerance=1e-3, double angular_tolerance=1e-3) |
Creates a malidrive from xodr source. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateOnRamp () |
Creates a multilane on-ramp. More... | |
std::unique_ptr< maliput::api::RoadNetwork > | CreateMaliputOSMRoadNetwork (const std::string &name, const std::string &file_path, const std::string &origin=std::string(), const std::string &rule_registry_file_path=std::string(), const std::string &road_rulebook_file_path=std::string(), const std::string &traffic_light_book_path=std::string(), const std::string &phase_ring_path=std::string(), const std::string &intersection_book_path=std::string(), double linear_tolerance=1e-3, double angular_tolerance=1e-3) |
Creates a maliput_osm based RoadNetwork from osm source. More... | |
std::unique_ptr< maliput::api::RoadNetwork > CreateDragway | ( | const std::string & | name, |
int | num_lanes, | ||
double | length, | ||
double | lane_width, | ||
double | shoulder_width, | ||
double | maximum_height, | ||
double | linear_tolerance = std::numeric_limits<double>::epsilon() , |
||
double | angular_tolerance = std::numeric_limits<double>::epsilon() |
||
) |
Creates a dragway.
[in] | name | The name of the dragway. Will be used as the ID of the underlying RoadGeometry. |
[in] | num_lanes | The number of lanes (m). |
[in] | length | The length of the dragway (m). |
[in] | lane_width | The width of each lane (m). |
[in] | shoulder_width | The width of the shoulders on each side of the road (m). |
[in] | maximum_height | The maximum height above the road surface modelled by the RoadGeometry (m). |
[in] | linear_tolerance | The tolerance guaranteed for linear measurements (m). |
[in] | angular_tolerance | The tolerance guaranteed for angular measurements (m). |
std::unique_ptr< maliput::api::RoadNetwork > CreateMalidriveFromXodr | ( | const std::string & | name, |
const std::string & | file_path, | ||
double | linear_tolerance = 1e-3 , |
||
double | angular_tolerance = 1e-3 |
||
) |
Creates a malidrive from xodr source.
[in] | name | A name for the road geometry to be created. |
[in] | file_path | A string pointing to the file to be loaded. |
[in] | linear_tolerance | The linear RoadGeometry tolerance. Default value is 1e-3m. |
[in] | angular_tolerance | The angular RoadGeometry tolerance. Default value is 1e-3rad. |
std::unique_ptr< maliput::api::RoadNetwork > CreateMalidriveRoadNetworkFromXodr | ( | const std::string & | name, |
const std::string & | file_path, | ||
const std::string & | rule_registry_file_path = std::string() , |
||
const std::string & | road_rulebook_file_path = std::string() , |
||
const std::string & | traffic_light_book_path = std::string() , |
||
const std::string & | phase_ring_path = std::string() , |
||
const std::string & | intersection_book_path = std::string() , |
||
double | linear_tolerance = 1e-3 , |
||
double | angular_tolerance = 1e-3 |
||
) |
Creates a malidrive from xodr source.
[in] | name | A name for the road geometry to be created. |
[in] | file_path | A string pointing to the XODR file to be loaded. |
[in] | rule_registry_file_path | A string pointing to the RuleRegistry file to be loaded. |
[in] | road_rulebook_file_path | A string pointing to the Rulebook file to be loaded. |
[in] | traffic_light_book_path | A string pointing to the TrafficLightBook file to be loaded. |
[in] | phase_ring_path | A string pointing to the PhaseRingBook file to be loaded. |
[in] | intersection_book_path | A string pointing to the IntersectionBook file to be loaded. |
[in] | linear_tolerance | The linear RoadGeometry tolerance. Default value is 1e-3m. |
[in] | angular_tolerance | The angular RoadGeometry tolerance. Default value is 1e-3rad. |
std::unique_ptr< maliput::api::RoadNetwork > CreateMaliputOSMRoadNetwork | ( | const std::string & | name, |
const std::string & | file_path, | ||
const std::string & | origin = std::string() , |
||
const std::string & | rule_registry_file_path = std::string() , |
||
const std::string & | road_rulebook_file_path = std::string() , |
||
const std::string & | traffic_light_book_path = std::string() , |
||
const std::string & | phase_ring_path = std::string() , |
||
const std::string & | intersection_book_path = std::string() , |
||
double | linear_tolerance = 1e-3 , |
||
double | angular_tolerance = 1e-3 |
||
) |
Creates a maliput_osm based RoadNetwork from osm source.
[in] | name | A name for the road geometry to be created. |
[in] | file_path | A string pointing to the OSM file to be loaded. |
[in] | origin | A 2D-vector representing the origin(lat-long) of the OSM map. |
[in] | rule_registry_file_path | A string pointing to the RuleRegistry file to be loaded. |
[in] | road_rulebook_file_path | A string pointing to the Rulebook file to be loaded. |
[in] | traffic_light_book_path | A string pointing to the TrafficLightBook file to be loaded. |
[in] | phase_ring_path | A string pointing to the PhaseRingBook file to be loaded. |
[in] | intersection_book_path | A string pointing to the IntersectionBook file to be loaded. |
[in] | linear_tolerance | The linear RoadGeometry tolerance. Default value is 1e-3m. |
[in] | angular_tolerance | The angular RoadGeometry tolerance. Default value is 1e-3rad. |
std::unique_ptr< maliput::api::RoadNetwork > CreateMultilaneFromDescription | ( | const std::string & | yaml_description | ) |
Creates a multilane from yaml description.
[in] | yaml_description | A serialized yaml description to be loaded. |
std::unique_ptr< maliput::api::RoadNetwork > CreateMultilaneFromFile | ( | const std::string & | file_path | ) |
Creates a multilane from yaml source.
[in] | file_path | A string pointing to the file to be loaded. |
std::unique_ptr< maliput::api::RoadNetwork > CreateOnRamp | ( | ) |
Creates a multilane on-ramp.
std::unique_ptr<maliput::api::RoadNetwork> delphyne::roads::CreateRoadNetwork | ( | const std::string & | road_network_plugin_name, |
const std::map< std::string, std::string > & | loader_parameters | ||
) |
Creates a maliput::api::RoadNetwork based on an available maliput::plugin::RoadNetworkLoader plugin implementation.
[in] | road_network_plugin_name | maliput::plugin::RoadnetworkLoader plugin name to be used. |
[in] | loader_parameters | Parameters to be passed to the maliput::api::RoadNetwork builder. |
maliput::common::assertion_error | When road_network_plugin_name isn't found. |
const maliput::api::Lane * FindLane | ( | const maliput::api::LaneId & | lane_id, |
const maliput::api::RoadGeometry & | road_geometry | ||
) |
Find the lane inside the specified road geometry by id.
[in] | lane_id | a maliput-style identifier based on drake::automotive::api::TypeSpecificIdentifier<class Lane> "TypeSpecificIdentifier" |
[in] | road_geometry | Search over this road geometry. |