maliput_malidrive
RoadHeader Struct Reference

Detailed Description

Holds the values of a XODR description's Road header.

For example, a XODR description with a Road header:

<OpenDRIVE>
<road name="Road 0" length="1.4005927435591335e+2" id="0" junction="-1" rule="RHT">
<link>
<predecessor elementType="road" elementId="80" contactPoint="end"/>
<successor elementType="road" elementId="10" contactPoint="start"/>
</link>
<type s="0.0000000000000000e+0" type="town">
<speed max="40" unit="mph"/>
</type>
<planView>
<geometry s="0.0000000000000000e+0" x="0.0000000000000000e+0" y="0.0000000000000000e+0"
hdg="1.3734007669450161e+0" length="1.4005927435591335e+2">
<line/>
</geometry>
</planView>
<lanes>
<laneOffset s='0.' a='2.2' b='3.3' c='4.4' d='5.5'/>
<laneSection s='0.'>
<left>
<lane id='1' type='driving' level= '0'>
<width sOffset='0.' a='1.' b='2.' c='3.' d='4.'/>
</lane>
</left>
<center>
<lane id='0' type='driving' level= '0'>
</lane>
</center>
<right>
<lane id='-1' type='driving' level= '0'>
<width sOffset='5.' a='6.' b='7.' c='8.' d='9.'/>
</lane>
</right>
</laneSection>
</lanes>
</road>
</OpenDRIVE>

#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 RoadTypeGetRoadType (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< HandTrafficRulerule {std::nullopt}
 Hand traffic rule of the road. More...
 
RoadLink road_link {std::nullopt, std::nullopt}
 Contains the road link. More...
 
std::vector< RoadTyperoad_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"
 

Member Typedef Documentation

◆ Id

Member Enumeration Documentation

◆ HandTrafficRule

enum HandTrafficRule
strong

Holds the hand traffic rules.

Enumerator
kRHT 

Right handed traffic.

kLHT 

Left handed traffic.

Member Function Documentation

◆ GetLaneSectionIndex()

int GetLaneSectionIndex ( double  s) const

Get the lane section index for a particular s-cooridnate.

Parameters
sA s-coordinate of the Road.
Returns
The index of the lane section.
Exceptions
maliput::common::assertion_errorWhen neither LaneSection's range contain the s coordinate.

◆ GetLaneSectionLength()

double GetLaneSectionLength ( int  index) const

Get length of a lane section.

Parameters
indexThe index-th LaneSection to retrieve its length.
Returns
The length of the index-th LaneSection.
Exceptions
maliput::common::assertion_errorWhen index is negative.
maliput::common::assertion_errorWhen index is greater than the numbers of LaneSections in the road.

◆ GetRoadType()

const RoadType * GetRoadType ( double  s) const

Get the RoadType for a particular s-cooridnate.

Parameters
sA s-coordinate of the Road.
Returns
A pointer to the correspondant RoadType. Nullptr if there is no RoadTypes described.
Exceptions
maliput::common::assertion_errorWhen neither RoadType's range contain the s coordinate.

◆ GetRoadTypeLength()

double GetRoadTypeLength ( int  index) const

Get length of a RoadType.

Parameters
indexThe index-th RoadType to retrieve its length.
Returns
The length of the index-th RoadType.
Exceptions
maliput::common::assertion_errorWhen index is negative.
maliput::common::assertion_errorWhen index is greater than the numbers of RoadTypes in the road.

◆ GetRoadTypesInRange()

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].

Parameters
s_startTrack s-coordinate that specifies the start of the range.
s_endTrack s-coordinate that specifies the end of the range.
Returns
A vector of RoadTypes.
Exceptions
maliput::common::assertion_errorWhen s_start is greater than s_end.
maliput::common::assertion_errorWhen s_start is negative.

◆ hand_traffic_rule_to_str()

std::string hand_traffic_rule_to_str ( RoadHeader::HandTrafficRule  rule)
static

Matches string with a HandTrafficRule.

Parameters
ruleIs a HandTrafficRule.
Returns
A string that matches with rule.

◆ operator!=()

bool operator!= ( const RoadHeader other) const

Inequality operator.

◆ operator==()

bool operator== ( const RoadHeader other) const

Equality operator.

◆ s0()

double s0 ( ) const

Get start s value of the Road.

It is delimited by the start point of the first geometry in the planView.

◆ s1()

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.

◆ str_to_hand_traffic_rule()

RoadHeader::HandTrafficRule str_to_hand_traffic_rule ( const std::string &  rule)
static

Matches HandTrafficRule with a string.

Parameters
ruleIs a string.
Returns
A HandtrafficRule that matches with rule.
Exceptions
maliput::common::assertion_errorWhen rule doesn't match with a HandTrafficRule.

Member Data Documentation

◆ id

Id id {"none"}

Unique ID within database.

◆ junction

std::string junction {}

ID of the junction to which the road belongs as a connecting road.(-1 for none.)

◆ kId

constexpr const char* kId = "id"
staticconstexpr

◆ kJunction

constexpr const char* kJunction = "junction"
staticconstexpr

◆ kLength

constexpr const char* kLength = "length"
staticconstexpr

◆ kName

constexpr const char* kName = "name"
staticconstexpr

◆ kRoadHeaderTag

constexpr const char* kRoadHeaderTag = "road"
staticconstexpr

Convenient constants that hold the tag names in the XODR road header description.

◆ kRule

constexpr const char* kRule = "rule"
staticconstexpr

◆ lanes

Lanes lanes {}

Holds the road's lanes.

◆ length

double length {}

Total length of the reference line in the xy-plane.

◆ name

std::optional<std::string> name {std::nullopt}

Name of the road.

◆ reference_geometry

ReferenceGeometry reference_geometry {}

Contains the geometry description of the road.

◆ road_link

RoadLink road_link {std::nullopt, std::nullopt}

Contains the road link.

◆ road_types

std::vector<RoadType> road_types {}

Contains the road types of the road.

◆ rule

std::optional<HandTrafficRule> rule {std::nullopt}

Hand traffic rule of the road.


The documentation for this struct was generated from the following files: