maliput_malidrive
|
Describes a Lane whose centerline is a offset of a road_curve::RoadCurve at a certain lane offset which is a road_curve::Function.
Lane's width varies with s
.
In maps an XODR Lane within a certain XODR LaneSection.
#include <src/maliput_malidrive/base/lane.h>
Public Member Functions | |
MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN (Lane) | |
Lane (const maliput::api::LaneId &id, int xodr_track, int xodr_lane_id, const maliput::api::HBounds &elevation_bounds, const road_curve::RoadCurve *road_curve, std::unique_ptr< road_curve::Function > lane_width, std::unique_ptr< road_curve::Function > lane_offset, double p0, double p1) | |
Constructs a Lane. More... | |
int | get_track () const |
int | get_lane_id () const |
double | get_track_s_start () const |
double | get_track_s_end () const |
double | TrackSFromLaneS (double lane_s) const |
Converts lane_s coordinate in the LANE Frame to the TRACK Frame s coordinate the ODRM uses. More... | |
double | LaneSFromTrackS (double track_s) const |
Converts track_s coordinate in the TRACK Frame s coordinate the ODRM uses to the s coordinate in the LANE frame. More... | |
Public Member Functions inherited from Lane | |
MALIPUT_NO_COPY_NO_MOVE_NO_ASSIGN (Lane) | |
Lane (const api::LaneId &id) | |
BranchPoint * | mutable_start_branch_point () |
BranchPoint * | mutable_finish_branch_point () |
void | AttachToSegment (common::Passkey< Segment >, const api::Segment *segment, int index) |
void | SetStartBranchPoint (common::Passkey< BranchPoint >, BranchPoint *branch_point) |
void | SetFinishBranchPoint (common::Passkey< BranchPoint >, BranchPoint *branch_point) |
~Lane () override=default | |
Public Member Functions inherited from Lane | |
LaneId | id () const |
const Segment * | segment () const |
int | index () const |
const Lane * | to_left () const |
const Lane * | to_right () const |
double | length () const |
RBounds | lane_bounds (double s) const |
RBounds | segment_bounds (double s) const |
HBounds | elevation_bounds (double s, double r) const |
InertialPosition | ToInertialPosition (const LanePosition &lane_pos) const |
LanePositionResult | ToLanePosition (const InertialPosition &inertial_pos) const |
LanePositionResult | ToSegmentPosition (const InertialPosition &inertial_pos) const |
Rotation | GetOrientation (const LanePosition &lane_pos) const |
LanePosition | EvalMotionDerivatives (const LanePosition &position, const IsoLaneVelocity &velocity) const |
const BranchPoint * | GetBranchPoint (const LaneEnd::Which which_end) const |
const LaneEndSet * | GetConfluentBranches (const LaneEnd::Which which_end) const |
const LaneEndSet * | GetOngoingBranches (const LaneEnd::Which which_end) const |
std::optional< LaneEnd > | GetDefaultBranch (const LaneEnd::Which which_end) const |
bool | Contains (const LanePosition &lane_position) const |
Additional Inherited Members | |
Protected Member Functions inherited from Lane | |
Lane ()=default | |
Lane | ( | const maliput::api::LaneId & | id, |
int | xodr_track, | ||
int | xodr_lane_id, | ||
const maliput::api::HBounds & | elevation_bounds, | ||
const road_curve::RoadCurve * | road_curve, | ||
std::unique_ptr< road_curve::Function > | lane_width, | ||
std::unique_ptr< road_curve::Function > | lane_offset, | ||
double | p0, | ||
double | p1 | ||
) |
Constructs a Lane.
id | Lane's ID. |
xodr_track | The XODR Road ID. It must be non negative. |
xodr_lane_id | The XODR Lane ID within a XODR LaneSection. |
elevation_bounds | Lane's elevation boundaries. They are constant for the entire volume. |
road_curve | A pointer to a road_curve::RoadCurve. It must not be nullptr. Ownership of this object is not managed by this class. |
lane_width | A road_curve::Function describing the width of the lane, i.e. its lane bounds. It must not be nullptr. Its range must be within road_curve->linear_tolerance() distance of road_curve's . |
lane_offset | A road_curve::Function describing the offset of this Lane's centerline. It must not be nullptr. Its range must be within road_curve->linear_tolerance() distance of road_curve's . |
p0 | The value of the \( p \) parameter of road_curve that matches the start of the Lane. |
p1 | The value of the \( p \) parameter of road_curve that matches the finish of the Lane. |
p1
- p0
is less than road_curve->linear_tolerance()
, an instance will not host a RoadCurveOffset to populate p_from_s_
and s_from_p_
. Instead, it will create linear functions to convert back and forth s
and p
parameters. maliput::common::assertion_error | When xodr_track is negative. |
maliput::common::assertion_error | When lane_width , lane_offset or road_curve are nullptr. |
maliput::common::assertion_error | When lane_width's or lane_offset's range are not within road_curve->linear_tolerance() of [ p0 , p1 ] range. |
int get_lane_id | ( | ) | const |
int get_track | ( | ) | const |
double get_track_s_end | ( | ) | const |
s
coordinate of the XODR LaneSection this lane is part of. double get_track_s_start | ( | ) | const |
s
coordinate of the XODR LaneSection this lane is part of. It is a non-negative quantity. double LaneSFromTrackS | ( | double | track_s | ) | const |
Converts track_s
coordinate in the TRACK Frame s
coordinate the ODRM uses to the s
coordinate in the LANE frame.
track_s | The TRACK Frame s coordinate to convert. It must be in [0; get_track_s_end() - get_track_s_start()]. |
s
coordinate which matches track_s
. maliput::common::assertion_error | When track_s is not in range. |
MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN | ( | Lane | ) |
double TrackSFromLaneS | ( | double | lane_s | ) | const |
Converts lane_s
coordinate in the LANE Frame to the TRACK Frame s
coordinate the ODRM uses.
lane_s | The LANE Frame s coordinate to convert. It must be in [0; maliput::api::Lane::length()]. |
s
coordinate which matches lane_s
. maliput::common::assertion_error | When lane_s is not in range. |