maliput_malidrive
|
Holds the values of a XODR description's Road header.
For example, a XODR description with a Road header:
#include <src/maliput_malidrive/xodr/road_header.h>
Public Types | |
enum | HandTrafficRule { kRHT = 0, kLHT } |
Holds the hand traffic rules. More... | |
using | Id = maliput::api::TypeSpecificIdentifier< struct RoadHeader > |
Id alias. More... | |
Public Member Functions | |
double | GetLaneSectionLength (int index) const |
Get length of a lane section. More... | |
int | GetLaneSectionIndex (double s) const |
Get the lane section index for a particular s-cooridnate. More... | |
double | GetRoadTypeLength (int index) const |
Get length of a RoadType. More... | |
const RoadType * | GetRoadType (double s) const |
Get the RoadType for a particular s-cooridnate. More... | |
std::vector< const RoadType * > | GetRoadTypesInRange (double s_start, double s_end) const |
Get the RoadTypes that are present within the range: [s_start , s_end ]. More... | |
double | s0 () const |
Get start s value of the Road. More... | |
double | s1 () const |
Get start s value of the Road. More... | |
bool | operator== (const RoadHeader &other) const |
Equality operator. More... | |
bool | operator!= (const RoadHeader &other) const |
Inequality operator. More... | |
Static Public Member Functions | |
static std::string | hand_traffic_rule_to_str (HandTrafficRule rule) |
Matches string with a HandTrafficRule. More... | |
static HandTrafficRule | str_to_hand_traffic_rule (const std::string &rule) |
Matches HandTrafficRule with a string. More... | |
Public Attributes | |
std::optional< std::string > | name {std::nullopt} |
Name of the road. More... | |
double | length {} |
Total length of the reference line in the xy-plane. More... | |
Id | id {"none"} |
Unique ID within database. More... | |
std::string | junction {} |
ID of the junction to which the road belongs as a connecting road.(-1 for none.) More... | |
std::optional< HandTrafficRule > | rule {std::nullopt} |
Hand traffic rule of the road. More... | |
RoadLink | road_link {std::nullopt, std::nullopt} |
Contains the road link. More... | |
std::vector< RoadType > | road_types {} |
Contains the road types of the road. More... | |
ReferenceGeometry | reference_geometry {} |
Contains the geometry description of the road. More... | |
Lanes | lanes {} |
Holds the road's lanes. More... | |
Static Public Attributes | |
static constexpr const char * | kRoadHeaderTag = "road" |
Convenient constants that hold the tag names in the XODR road header description. More... | |
static constexpr const char * | kName = "name" |
static constexpr const char * | kLength = "length" |
static constexpr const char * | kId = "id" |
static constexpr const char * | kJunction = "junction" |
static constexpr const char * | kRule = "rule" |
using Id = maliput::api::TypeSpecificIdentifier<struct RoadHeader> |
Id alias.
|
strong |
int GetLaneSectionIndex | ( | double | s | ) | const |
Get the lane section index for a particular s-cooridnate.
s | A s-coordinate of the Road. |
maliput::common::assertion_error | When neither LaneSection's range contain the s coordinate. |
double GetLaneSectionLength | ( | int | index | ) | const |
Get length of a lane section.
index | The index -th LaneSection to retrieve its length. |
index
-th LaneSection. maliput::common::assertion_error | When index is negative. |
maliput::common::assertion_error | When index is greater than the numbers of LaneSections in the road. |
const RoadType * GetRoadType | ( | double | s | ) | const |
Get the RoadType for a particular s-cooridnate.
s | A s-coordinate of the Road. |
maliput::common::assertion_error | When neither RoadType's range contain the s coordinate. |
double GetRoadTypeLength | ( | int | index | ) | const |
Get length of a RoadType.
index | The index -th RoadType to retrieve its length. |
index
-th RoadType. maliput::common::assertion_error | When index is negative. |
maliput::common::assertion_error | When index is greater than the numbers of RoadTypes in the road. |
std::vector< const RoadType * > GetRoadTypesInRange | ( | double | s_start, |
double | s_end | ||
) | const |
Get the RoadTypes that are present within the range: [s_start
, s_end
].
s_start | Track s-coordinate that specifies the start of the range. |
s_end | Track s-coordinate that specifies the end of the range. |
maliput::common::assertion_error | When s_start is greater than s_end . |
maliput::common::assertion_error | When s_start is negative. |
|
static |
Matches string with a HandTrafficRule.
rule | Is a HandTrafficRule. |
rule
. bool operator!= | ( | const RoadHeader & | other | ) | const |
Inequality operator.
bool operator== | ( | const RoadHeader & | other | ) | const |
Equality operator.
double s0 | ( | ) | const |
Get start s value of the Road.
It is delimited by the start point of the first geometry in the planView.
double s1 | ( | ) | const |
Get start s value of the Road.
It is computed as the sum of the last geometry's start point and its length.
|
static |
Matches HandTrafficRule with a string.
rule | Is a string. |
rule
. maliput::common::assertion_error | When rule doesn't match with a HandTrafficRule. |
Id id {"none"} |
Unique ID within database.
std::string junction {} |
ID of the junction to which the road belongs as a connecting road.(-1 for none.)
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
Convenient constants that hold the tag names in the XODR road header description.
|
staticconstexpr |
Lanes lanes {} |
Holds the road's lanes.
double length {} |
Total length of the reference line in the xy-plane.
std::optional<std::string> name {std::nullopt} |
Name of the road.
ReferenceGeometry reference_geometry {} |
Contains the geometry description of the road.
RoadLink road_link {std::nullopt, std::nullopt} |
Contains the road link.
std::vector<RoadType> road_types {} |
Contains the road types of the road.
std::optional<HandTrafficRule> rule {std::nullopt} |
Hand traffic rule of the road.