maliput_malidrive
|
Holds the values of a XODR Lane.
For example, a XML node describing a XODR's lane:
#include <src/maliput_malidrive/xodr/lane.h>
Classes | |
struct | Speed |
Speed description. More... | |
Public Types | |
enum | Type { kNone, kDriving, kStop, kShoulder, kBiking, kSidewalk, kBorder, kRestricted, kParking, kCurb, kBidirectional, kMedian, kSpecial1, kSpecial2, kSpecial3, kRoadWorks, kTram, kRail, kEntry, kExit, kOffRamp, kOnRamp, kConnectingRamp, kBus, kTaxi, kHOV, kMwyEntry, kMwyExit } |
Holds types of lanes. More... | |
using | Id = maliput::api::TypeSpecificIdentifier< struct Lane > |
Id alias. More... | |
Public Member Functions | |
bool | operator== (const Lane &other) const |
Equality operator. More... | |
bool | operator!= (const Lane &other) const |
Inequality operator. More... | |
Static Public Member Functions | |
static std::string | type_to_str (Type type) |
Matches string with a Type. More... | |
static Type | str_to_type (const std::string &type) |
Matches Type with a string. More... | |
Public Attributes | |
Id | id {"none"} |
ID of the lane. More... | |
Type | type {} |
Type of the lane. More... | |
std::optional< bool > | level {std::nullopt} |
Indicates whether apply or not superelevation and crossfall to this lane: More... | |
LaneLink | lane_link {std::nullopt, std::nullopt} |
Contains the lane link. More... | |
std::vector< LaneWidth > | width_description {} |
Widths of the lane. More... | |
std::vector< Speed > | speed {} |
Speed records of the lane. More... | |
std::optional< std::string > | user_data {std::nullopt} |
Contains ancillary data in XML format. It holds the entire userData node. More... | |
Static Public Attributes | |
static constexpr const char * | kLaneTag = "lane" |
Convenient constants that hold the tag names in XODR lane description. More... | |
static constexpr const char * | kId = "id" |
static constexpr const char * | kType = "type" |
static constexpr const char * | kLevel = "level" |
static constexpr const char * | kUserData = "userData" |
using Id = maliput::api::TypeSpecificIdentifier<struct Lane> |
Id alias.
|
strong |
Holds types of lanes.
bool operator!= | ( | const Lane & | other | ) | const |
Inequality operator.
bool operator== | ( | const Lane & | other | ) | const |
Equality operator.
|
static |
Matches Type with a string.
type | Is a string. |
type
. maliput::common::assertion_error | When type doesn't match with a Type. |
|
static |
Matches string with a Type.
type | Is a Type. |
type
. Id id {"none"} |
ID of the lane.
|
staticconstexpr |
|
staticconstexpr |
Convenient constants that hold the tag names in XODR lane description.
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
LaneLink lane_link {std::nullopt, std::nullopt} |
Contains the lane link.
std::optional<bool> level {std::nullopt} |
Indicates whether apply or not superelevation and crossfall to this lane:
Type type {} |
Type of the lane.
std::optional<std::string> user_data {std::nullopt} |
Contains ancillary data in XML format. It holds the entire userData node.
std::vector<LaneWidth> width_description {} |
Widths of the lane.