Apollo  6.0
Open source self driving car software
Classes | Public Member Functions | List of all members
apollo::planning::ReferenceLine Class Reference

#include <reference_line.h>

Collaboration diagram for apollo::planning::ReferenceLine:
Collaboration graph

Public Member Functions

 ReferenceLine ()=default
 
 ReferenceLine (const ReferenceLine &reference_line)=default
 
template<typename Iterator >
 ReferenceLine (const Iterator begin, const Iterator end)
 
 ReferenceLine (const std::vector< ReferencePoint > &reference_points)
 
 ReferenceLine (const hdmap::Path &hdmap_path)
 
bool Stitch (const ReferenceLine &other)
 
bool Segment (const common::math::Vec2d &point, const double distance_backward, const double distance_forward)
 
bool Segment (const double s, const double distance_backward, const double distance_forward)
 
const hdmap::Pathmap_path () const
 
const std::vector< ReferencePoint > & reference_points () const
 
ReferencePoint GetReferencePoint (const double s) const
 
common::FrenetFramePoint GetFrenetPoint (const common::PathPoint &path_point) const
 
std::pair< std::array< double, 3 >, std::array< double, 3 > > ToFrenetFrame (const common::TrajectoryPoint &traj_point) const
 
std::vector< ReferencePointGetReferencePoints (double start_s, double end_s) const
 
size_t GetNearestReferenceIndex (const double s) const
 
ReferencePoint GetNearestReferencePoint (const common::math::Vec2d &xy) const
 
std::vector< hdmap::LaneSegmentGetLaneSegments (const double start_s, const double end_s) const
 
ReferencePoint GetNearestReferencePoint (const double s) const
 
ReferencePoint GetReferencePoint (const double x, const double y) const
 
bool GetApproximateSLBoundary (const common::math::Box2d &box, const double start_s, const double end_s, SLBoundary *const sl_boundary) const
 
bool GetSLBoundary (const common::math::Box2d &box, SLBoundary *const sl_boundary) const
 
bool GetSLBoundary (const hdmap::Polygon &polygon, SLBoundary *const sl_boundary) const
 
bool SLToXY (const common::SLPoint &sl_point, common::math::Vec2d *const xy_point) const
 
bool XYToSL (const common::math::Vec2d &xy_point, common::SLPoint *const sl_point) const
 
template<class XYPoint >
bool XYToSL (const XYPoint &xy, common::SLPoint *const sl_point) const
 
bool GetLaneWidth (const double s, double *const lane_left_width, double *const lane_right_width) const
 
bool GetOffsetToMap (const double s, double *l_offset) const
 
bool GetRoadWidth (const double s, double *const road_left_width, double *const road_right_width) const
 
hdmap::Road::Type GetRoadType (const double s) const
 
void GetLaneFromS (const double s, std::vector< hdmap::LaneInfoConstPtr > *lanes) const
 
double GetDrivingWidth (const SLBoundary &sl_boundary) const
 
bool IsOnLane (const common::SLPoint &sl_point) const
 : check if a box/point is on lane along reference line More...
 
bool IsOnLane (const common::math::Vec2d &vec2d_point) const
 
template<class XYPoint >
bool IsOnLane (const XYPoint &xy) const
 
bool IsOnLane (const SLBoundary &sl_boundary) const
 
bool IsOnRoad (const common::SLPoint &sl_point) const
 : check if a box/point is on road (not on sideways/medians) along reference line More...
 
bool IsOnRoad (const common::math::Vec2d &vec2d_point) const
 
bool IsOnRoad (const SLBoundary &sl_boundary) const
 
bool IsBlockRoad (const common::math::Box2d &box2d, double gap) const
 Check if a box is blocking the road surface. The criteria is to check whether the remaining space on the road surface is larger than the provided gap space. More...
 
bool HasOverlap (const common::math::Box2d &box) const
 check if any part of the box has overlap with the road. More...
 
double Length () const
 
std::string DebugString () const
 
double GetSpeedLimitFromS (const double s) const
 
void AddSpeedLimit (double start_s, double end_s, double speed_limit)
 
uint32_t GetPriority () const
 
void SetPriority (uint32_t priority)
 
const hdmap::PathGetMapPath () const
 

Constructor & Destructor Documentation

◆ ReferenceLine() [1/5]

apollo::planning::ReferenceLine::ReferenceLine ( )
default

◆ ReferenceLine() [2/5]

apollo::planning::ReferenceLine::ReferenceLine ( const ReferenceLine reference_line)
explicitdefault

◆ ReferenceLine() [3/5]

template<typename Iterator >
apollo::planning::ReferenceLine::ReferenceLine ( const Iterator  begin,
const Iterator  end 
)
inline

◆ ReferenceLine() [4/5]

apollo::planning::ReferenceLine::ReferenceLine ( const std::vector< ReferencePoint > &  reference_points)
explicit

◆ ReferenceLine() [5/5]

apollo::planning::ReferenceLine::ReferenceLine ( const hdmap::Path hdmap_path)
explicit

Member Function Documentation

◆ AddSpeedLimit()

void apollo::planning::ReferenceLine::AddSpeedLimit ( double  start_s,
double  end_s,
double  speed_limit 
)

◆ DebugString()

std::string apollo::planning::ReferenceLine::DebugString ( ) const

◆ GetApproximateSLBoundary()

bool apollo::planning::ReferenceLine::GetApproximateSLBoundary ( const common::math::Box2d box,
const double  start_s,
const double  end_s,
SLBoundary *const  sl_boundary 
) const

◆ GetDrivingWidth()

double apollo::planning::ReferenceLine::GetDrivingWidth ( const SLBoundary &  sl_boundary) const

◆ GetFrenetPoint()

common::FrenetFramePoint apollo::planning::ReferenceLine::GetFrenetPoint ( const common::PathPoint &  path_point) const

◆ GetLaneFromS()

void apollo::planning::ReferenceLine::GetLaneFromS ( const double  s,
std::vector< hdmap::LaneInfoConstPtr > *  lanes 
) const

◆ GetLaneSegments()

std::vector<hdmap::LaneSegment> apollo::planning::ReferenceLine::GetLaneSegments ( const double  start_s,
const double  end_s 
) const

◆ GetLaneWidth()

bool apollo::planning::ReferenceLine::GetLaneWidth ( const double  s,
double *const  lane_left_width,
double *const  lane_right_width 
) const

◆ GetMapPath()

const hdmap::Path& apollo::planning::ReferenceLine::GetMapPath ( ) const
inline

◆ GetNearestReferenceIndex()

size_t apollo::planning::ReferenceLine::GetNearestReferenceIndex ( const double  s) const

◆ GetNearestReferencePoint() [1/2]

ReferencePoint apollo::planning::ReferenceLine::GetNearestReferencePoint ( const common::math::Vec2d xy) const

◆ GetNearestReferencePoint() [2/2]

ReferencePoint apollo::planning::ReferenceLine::GetNearestReferencePoint ( const double  s) const

◆ GetOffsetToMap()

bool apollo::planning::ReferenceLine::GetOffsetToMap ( const double  s,
double *  l_offset 
) const

◆ GetPriority()

uint32_t apollo::planning::ReferenceLine::GetPriority ( ) const
inline

◆ GetReferencePoint() [1/2]

ReferencePoint apollo::planning::ReferenceLine::GetReferencePoint ( const double  s) const

◆ GetReferencePoint() [2/2]

ReferencePoint apollo::planning::ReferenceLine::GetReferencePoint ( const double  x,
const double  y 
) const

◆ GetReferencePoints()

std::vector<ReferencePoint> apollo::planning::ReferenceLine::GetReferencePoints ( double  start_s,
double  end_s 
) const

◆ GetRoadType()

hdmap::Road::Type apollo::planning::ReferenceLine::GetRoadType ( const double  s) const

◆ GetRoadWidth()

bool apollo::planning::ReferenceLine::GetRoadWidth ( const double  s,
double *const  road_left_width,
double *const  road_right_width 
) const

◆ GetSLBoundary() [1/2]

bool apollo::planning::ReferenceLine::GetSLBoundary ( const common::math::Box2d box,
SLBoundary *const  sl_boundary 
) const

◆ GetSLBoundary() [2/2]

bool apollo::planning::ReferenceLine::GetSLBoundary ( const hdmap::Polygon &  polygon,
SLBoundary *const  sl_boundary 
) const

◆ GetSpeedLimitFromS()

double apollo::planning::ReferenceLine::GetSpeedLimitFromS ( const double  s) const

◆ HasOverlap()

bool apollo::planning::ReferenceLine::HasOverlap ( const common::math::Box2d box) const

check if any part of the box has overlap with the road.

◆ IsBlockRoad()

bool apollo::planning::ReferenceLine::IsBlockRoad ( const common::math::Box2d box2d,
double  gap 
) const

Check if a box is blocking the road surface. The criteria is to check whether the remaining space on the road surface is larger than the provided gap space.

Parameters
boxedthe provided box
gapcheck the gap of the space
Returns
true if the box blocks the road.

◆ IsOnLane() [1/4]

bool apollo::planning::ReferenceLine::IsOnLane ( const common::SLPoint &  sl_point) const

: check if a box/point is on lane along reference line

◆ IsOnLane() [2/4]

bool apollo::planning::ReferenceLine::IsOnLane ( const common::math::Vec2d vec2d_point) const

◆ IsOnLane() [3/4]

template<class XYPoint >
bool apollo::planning::ReferenceLine::IsOnLane ( const XYPoint &  xy) const
inline

◆ IsOnLane() [4/4]

bool apollo::planning::ReferenceLine::IsOnLane ( const SLBoundary &  sl_boundary) const

◆ IsOnRoad() [1/3]

bool apollo::planning::ReferenceLine::IsOnRoad ( const common::SLPoint &  sl_point) const

: check if a box/point is on road (not on sideways/medians) along reference line

◆ IsOnRoad() [2/3]

bool apollo::planning::ReferenceLine::IsOnRoad ( const common::math::Vec2d vec2d_point) const

◆ IsOnRoad() [3/3]

bool apollo::planning::ReferenceLine::IsOnRoad ( const SLBoundary &  sl_boundary) const

◆ Length()

double apollo::planning::ReferenceLine::Length ( ) const
inline

◆ map_path()

const hdmap::Path& apollo::planning::ReferenceLine::map_path ( ) const

◆ reference_points()

const std::vector<ReferencePoint>& apollo::planning::ReferenceLine::reference_points ( ) const

◆ Segment() [1/2]

bool apollo::planning::ReferenceLine::Segment ( const common::math::Vec2d point,
const double  distance_backward,
const double  distance_forward 
)

◆ Segment() [2/2]

bool apollo::planning::ReferenceLine::Segment ( const double  s,
const double  distance_backward,
const double  distance_forward 
)

◆ SetPriority()

void apollo::planning::ReferenceLine::SetPriority ( uint32_t  priority)
inline

◆ SLToXY()

bool apollo::planning::ReferenceLine::SLToXY ( const common::SLPoint &  sl_point,
common::math::Vec2d *const  xy_point 
) const

◆ Stitch()

bool apollo::planning::ReferenceLine::Stitch ( const ReferenceLine other)

Stitch current reference line with the other reference line The stitching strategy is to use current reference points as much as possible. The following two examples show two successful stitch cases.

Example 1 this: |-----—A--—x--—B---—| other: |--—C---—x-----—D----—| Result: |---—A--—x--—B---—x-----—D----—| In the above example, A-B is current reference line, and C-D is the other reference line. If part B and part C matches, we update current reference line to A-B-D.

Example 2 this: |--—A---—x-----—B----—| other: |-----—C--—x--—D---—| Result: |-----—C--—x--—A---—x-----—B----—| In the above example, A-B is current reference line, and C-D is the other reference line. If part A and part D matches, we update current reference line to C-A-B.

Returns
false if these two reference line cannot be stitched

◆ ToFrenetFrame()

std::pair<std::array<double, 3>, std::array<double, 3> > apollo::planning::ReferenceLine::ToFrenetFrame ( const common::TrajectoryPoint &  traj_point) const

◆ XYToSL() [1/2]

bool apollo::planning::ReferenceLine::XYToSL ( const common::math::Vec2d xy_point,
common::SLPoint *const  sl_point 
) const

◆ XYToSL() [2/2]

template<class XYPoint >
bool apollo::planning::ReferenceLine::XYToSL ( const XYPoint &  xy,
common::SLPoint *const  sl_point 
) const
inline

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