maliput_malidrive
Lane Class Reference

Detailed Description

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>

Inheritance diagram for Lane:
[legend]

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)
 
BranchPointmutable_start_branch_point ()
 
BranchPointmutable_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 Segmentsegment () const
 
int index () const
 
const Laneto_left () const
 
const Laneto_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 BranchPointGetBranchPoint (const LaneEnd::Which which_end) const
 
const LaneEndSetGetConfluentBranches (const LaneEnd::Which which_end) const
 
const LaneEndSetGetOngoingBranches (const LaneEnd::Which which_end) const
 
std::optional< LaneEndGetDefaultBranch (const LaneEnd::Which which_end) const
 
bool Contains (const LanePosition &lane_position) const
 

Additional Inherited Members

- Protected Member Functions inherited from Lane
 Lane ()=default
 

Constructor & Destructor Documentation

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

Parameters
idLane's ID.
xodr_trackThe XODR Road ID. It must be non negative.
xodr_lane_idThe XODR Lane ID within a XODR LaneSection.
elevation_boundsLane's elevation boundaries. They are constant for the entire volume.
road_curveA pointer to a road_curve::RoadCurve. It must not be nullptr. Ownership of this object is not managed by this class.
lane_widthA 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_offsetA 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.
p0The value of the \( p \) parameter of road_curve that matches the start of the Lane.
p1The value of the \( p \) parameter of road_curve that matches the finish of the Lane.
Note
When the ground curve's arc length in range 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.
Exceptions
maliput::common::assertion_errorWhen xodr_track is negative.
maliput::common::assertion_errorWhen lane_width, lane_offset or road_curve are nullptr.
maliput::common::assertion_errorWhen lane_width's or lane_offset's range are not within road_curve->linear_tolerance() of [ p0, p1 ] range.

Member Function Documentation

◆ get_lane_id()

int get_lane_id ( ) const
Returns
The OpenDRIVE Lane Id Road Id.

◆ get_track()

int get_track ( ) const
Returns
The OpenDRIVE Road Id, which is also referred to as Track Id. It is a non-negative number.

◆ get_track_s_end()

double get_track_s_end ( ) const
Returns
The TRACK Frame end s coordinate of the XODR LaneSection this lane is part of.

◆ get_track_s_start()

double get_track_s_start ( ) const
Returns
The TRACK Frame start s coordinate of the XODR LaneSection this lane is part of. It is a non-negative quantity.

◆ LaneSFromTrackS()

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.

Parameters
track_sThe TRACK Frame s coordinate to convert. It must be in [0; get_track_s_end() - get_track_s_start()].
Returns
The LANE Frame s coordinate which matches track_s.
Exceptions
maliput::common::assertion_errorWhen track_s is not in range.

◆ MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN()

MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN ( Lane  )

◆ TrackSFromLaneS()

double TrackSFromLaneS ( double  lane_s) const

Converts lane_s coordinate in the LANE Frame to the TRACK Frame s coordinate the ODRM uses.

Parameters
lane_sThe LANE Frame s coordinate to convert. It must be in [0; maliput::api::Lane::length()].
Returns
The TRACK Frame s coordinate which matches lane_s.
Exceptions
maliput::common::assertion_errorWhen lane_s is not in range.

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