Apollo 10.0
自动驾驶开放平台
apollo::planning::ReferenceLineInfo类 参考

ReferenceLineInfo holds all data for one reference line. 更多...

#include <reference_line_info.h>

apollo::planning::ReferenceLineInfo 的协作图:

Public 类型

enum class  LaneType { LeftForward , LeftReverse , RightForward , RightReverse }
 
enum  OverlapType {
  CLEAR_AREA = 1 , CROSSWALK = 2 , OBSTACLE = 3 , PNC_JUNCTION = 4 ,
  SIGNAL = 5 , STOP_SIGN = 6 , YIELD_SIGN = 7 , JUNCTION = 8 ,
  AREA = 9
}
 

Public 成员函数

 ReferenceLineInfo ()=default
 
 ReferenceLineInfo (const common::VehicleState &vehicle_state, const common::TrajectoryPoint &adc_planning_point, const ReferenceLine &reference_line, const hdmap::RouteSegments &segments)
 
bool Init (const std::vector< const Obstacle * > &obstacles, double target_speed)
 
bool AddObstacles (const std::vector< const Obstacle * > &obstacles)
 
ObstacleAddObstacle (const Obstacle *obstacle)
 
const common::VehicleStatevehicle_state () const
 
PathDecisionpath_decision ()
 
const PathDecisionpath_decision () const
 
const ReferenceLinereference_line () const
 
ReferenceLinemutable_reference_line ()
 
double SDistanceToDestination () const
 
double SDistanceToRefEnd () const
 
bool ReachedDestination () const
 
void SetTrajectory (const DiscretizedTrajectory &trajectory)
 
const DiscretizedTrajectorytrajectory () const
 
double Cost () const
 
void AddCost (double cost)
 
void SetCost (double cost)
 
double PriorityCost () const
 
void SetPriorityCost (double cost)
 
void SetLatticeStopPoint (const StopPoint &stop_point)
 
void SetLatticeCruiseSpeed (double speed)
 
const PlanningTargetplanning_target () const
 
void SetCruiseSpeed (double speed)
 
void LimitCruiseSpeed (double speed)
 Limit the cruise speed based on the "base_cruise_speed_".
 
double GetBaseCruiseSpeed () const
 
double GetCruiseSpeed () const
 
hdmap::LaneInfoConstPtr LocateLaneInfo (const double s) const
 
bool GetNeighborLaneInfo (const ReferenceLineInfo::LaneType lane_type, const double s, hdmap::Id *ptr_lane_id, double *ptr_lane_width) const
 
bool IsStartFrom (const ReferenceLineInfo &previous_reference_line_info) const
 check if current reference line is started from another reference line info line.
 
planning_internal::Debugmutable_debug ()
 
const planning_internal::Debugdebug () const
 
LatencyStatsmutable_latency_stats ()
 
const LatencyStatslatency_stats () const
 
const PathDatapath_data () const
 
const PathDatafallback_path_data () const
 
const SpeedDataspeed_data () const
 
PathDatamutable_path_data ()
 
PathDatamutable_fallback_path_data ()
 
SpeedDatamutable_speed_data ()
 
const RSSInforss_info () const
 
RSSInfomutable_rss_info ()
 
bool CombinePathAndSpeedProfile (const double relative_time, const double start_s, DiscretizedTrajectory *discretized_trajectory)
 
bool AdjustTrajectoryWhichStartsFromCurrentPos (const common::TrajectoryPoint &planning_start_point, const std::vector< common::TrajectoryPoint > &trajectory, DiscretizedTrajectory *adjusted_trajectory)
 
const SLBoundaryAdcSlBoundary () const
 
std::string PathSpeedDebugString () const
 
void PrintReferenceSegmentDebugString ()
 
bool IsChangeLanePath () const
 Check if the current reference line is a change lane reference line, i.e., ADC's current position is not on this reference line.
 
bool IsNeighborLanePath () const
 Check if the current reference line is the neighbor of the vehicle current position
 
void SetDrivable (bool drivable)
 Set if the vehicle can drive following this reference line A planner need to set this value to true if the reference line is OK
 
bool IsDrivable () const
 
void ExportEngageAdvice (common::EngageAdvice *engage_advice, PlanningContext *planning_context) const
 
const hdmap::RouteSegmentsLanes () const
 
std::list< hdmap::IdTargetLaneId () const
 
void ExportDecision (DecisionResult *decision_result, PlanningContext *planning_context) const
 
void SetJunctionRightOfWay (const double junction_s, const bool is_protected) const
 
ADCTrajectory::RightOfWayStatus GetRightOfWayStatus () const
 
hdmap::Lane::LaneTurn GetPathTurnType (const double s) const
 
bool GetIntersectionRightofWayStatus (const hdmap::PathOverlap &pnc_junction_overlap) const
 
double OffsetToOtherReferenceLine () const
 
void SetOffsetToOtherReferenceLine (const double offset)
 
const std::vector< PathBoundary > & GetCandidatePathBoundaries () const
 
void SetCandidatePathBoundaries (std::vector< PathBoundary > &&candidate_path_boundaries)
 
const std::vector< PathData > & GetCandidatePathData () const
 
std::vector< PathData > * MutableCandidatePathData ()
 
void SetCandidatePathData (std::vector< PathData > &&candidate_path_data)
 
ObstacleGetBlockingObstacle () const
 
void SetBlockingObstacle (const std::string &blocking_obstacle_id)
 
bool is_path_lane_borrow () const
 
void set_is_path_lane_borrow (const bool is_path_lane_borrow)
 
void set_is_on_reference_line ()
 
uint32_t GetPriority () const
 
void SetPriority (uint32_t priority)
 
void set_trajectory_type (const ADCTrajectory::TrajectoryType trajectory_type)
 
ADCTrajectory::TrajectoryType trajectory_type () const
 
StGraphDatamutable_st_graph_data ()
 
const StGraphDatast_graph_data ()
 
const std::vector< std::pair< OverlapType, hdmap::PathOverlap > > & FirstEncounteredOverlaps () const
 
int GetPnCJunction (const double s, hdmap::PathOverlap *pnc_junction_overlap) const
 
int GetJunction (const double s, hdmap::PathOverlap *junction_overlap) const
 
int GetArea (const double s, hdmap::PathOverlap *area_overlap) const
 
std::vector< common::SLPointGetAllStopDecisionSLPoint () const
 
void SetTurnSignal (const common::VehicleSignal::TurnSignal &turn_signal)
 
void SetEmergencyLight ()
 
void set_path_reusable (const bool path_reusable)
 
bool path_reusable () const
 
hdmap::PathOverlapGetOverlapOnReferenceLine (const std::string &overlap_id, const OverlapType &overlap_type) const
 
void set_key (std::size_t key)
 
std::size_t key () const
 
void set_index (std::size_t index)
 
std::size_t index () const
 
void set_id (std::string id)
 
std::string id () const
 
void GetRangeOverlaps (std::vector< hdmap::PathOverlap > *path_overlaps, double start_s, double end_s)
 
const std::vector< double > & reference_line_towing_l () const
 
std::vector< double > * mutable_reference_line_towing_l ()
 
const PathBoundaryreference_line_towing_path_boundary () const
 
PathBoundarymutable_reference_line_towing_path_boundary ()
 

详细描述

ReferenceLineInfo holds all data for one reference line.

在文件 reference_line_info.h55 行定义.

成员枚举类型说明

◆ LaneType

◆ OverlapType

构造及析构函数说明

◆ ReferenceLineInfo() [1/2]

apollo::planning::ReferenceLineInfo::ReferenceLineInfo ( )
default

◆ ReferenceLineInfo() [2/2]

apollo::planning::ReferenceLineInfo::ReferenceLineInfo ( const common::VehicleState vehicle_state,
const common::TrajectoryPoint adc_planning_point,
const ReferenceLine reference_line,
const hdmap::RouteSegments segments 
)

在文件 reference_line_info.cc53 行定义.

57 : vehicle_state_(vehicle_state),
58 adc_planning_point_(adc_planning_point),
59 reference_line_(reference_line),
60 lanes_(segments) {
61 if (lanes_.size() == 0) {
62 return;
63 }
64 std::ostringstream segs_id;
65 segs_id.setf(std::ios::fixed);
66 segs_id.precision(2);
67 segs_id.str("");
68 for (const auto& seg : lanes_) {
69 segs_id << "_" << seg.lane->id().id();
70 }
71
72 segs_id << "_" << lanes_.front().start_s << "_" << lanes_.back().end_s;
73 key_ = cyber::common::Hash(segs_id.str());
74 id_ = segs_id.str();
75}
const common::VehicleState & vehicle_state() const
const ReferenceLine & reference_line() const
std::size_t Hash(const std::string &key)
Definition util.h:27

成员函数说明

◆ AdcSlBoundary()

const SLBoundary & apollo::planning::ReferenceLineInfo::AdcSlBoundary ( ) const

在文件 reference_line_info.cc366 行定义.

366 {
367 return adc_sl_boundary_;
368}

◆ AddCost()

void apollo::planning::ReferenceLineInfo::AddCost ( double  cost)
inline

在文件 reference_line_info.h87 行定义.

87{ cost_ += cost; }

◆ AddObstacle()

Obstacle * apollo::planning::ReferenceLineInfo::AddObstacle ( const Obstacle obstacle)

在文件 reference_line_info.cc394 行定义.

394 {
395 if (!obstacle) {
396 AERROR << "The provided obstacle is empty";
397 return nullptr;
398 }
399 auto* mutable_obstacle = path_decision_.AddObstacle(*obstacle);
400 if (!mutable_obstacle) {
401 AERROR << "failed to add obstacle " << obstacle->Id();
402 return nullptr;
403 }
404
405 SLBoundary perception_sl;
406 if (!reference_line_.GetSLBoundary(obstacle->PerceptionPolygon(),
407 &perception_sl)) {
408 AERROR << "Failed to get sl boundary for obstacle: " << obstacle->Id();
409 return mutable_obstacle;
410 }
411 mutable_obstacle->SetPerceptionSlBoundary(perception_sl);
412 mutable_obstacle->CheckLaneBlocking(reference_line_);
413 if (mutable_obstacle->IsLaneBlocking()) {
414 ADEBUG << "obstacle [" << obstacle->Id() << "] is lane blocking.";
415 } else {
416 ADEBUG << "obstacle [" << obstacle->Id() << "] is NOT lane blocking.";
417 }
418
419 if (IsIrrelevantObstacle(*mutable_obstacle)) {
420 ObjectDecisionType ignore;
421 ignore.mutable_ignore();
422 path_decision_.AddLateralDecision("reference_line_filter", obstacle->Id(),
423 ignore);
424 path_decision_.AddLongitudinalDecision("reference_line_filter",
425 obstacle->Id(), ignore);
426 AINFO << "NO build reference line st boundary. id:" << obstacle->Id();
427 } else {
428 AINFO << "build reference line st boundary. id:" << obstacle->Id();
429 mutable_obstacle->BuildReferenceLineStBoundary(reference_line_,
430 adc_sl_boundary_.start_s());
431
432 ADEBUG << "reference line st boundary: t["
433 << mutable_obstacle->reference_line_st_boundary().min_t() << ", "
434 << mutable_obstacle->reference_line_st_boundary().max_t() << "] s["
435 << mutable_obstacle->reference_line_st_boundary().min_s() << ", "
436 << mutable_obstacle->reference_line_st_boundary().max_s() << "]";
437 }
438 return mutable_obstacle;
439}
const std::string & Id() const
Definition obstacle.h:75
bool AddLateralDecision(const std::string &tag, const std::string &object_id, const ObjectDecisionType &decision)
bool AddLongitudinalDecision(const std::string &tag, const std::string &object_id, const ObjectDecisionType &decision)
Obstacle * AddObstacle(const Obstacle &obstacle)
bool GetSLBoundary(const common::math::Box2d &box, SLBoundary *const sl_boundary, double warm_start_s=-1.0) const
Get the SL Boundary of the box.
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42

◆ AddObstacles()

bool apollo::planning::ReferenceLineInfo::AddObstacles ( const std::vector< const Obstacle * > &  obstacles)

在文件 reference_line_info.cc441 行定义.

442 {
443 if (FLAGS_use_multi_thread_to_add_obstacles) {
444 std::vector<std::future<Obstacle*>> results;
445 for (const auto* obstacle : obstacles) {
446 results.push_back(
447 cyber::Async(&ReferenceLineInfo::AddObstacle, this, obstacle));
448 }
449 for (auto& result : results) {
450 if (!result.get()) {
451 AERROR << "Fail to add obstacles.";
452 return false;
453 }
454 }
455 } else {
456 for (const auto* obstacle : obstacles) {
457 if (!AddObstacle(obstacle)) {
458 AERROR << "Failed to add obstacle " << obstacle->Id();
459 return false;
460 }
461 }
462 }
463
464 return true;
465}
Obstacle * AddObstacle(const Obstacle *obstacle)

◆ AdjustTrajectoryWhichStartsFromCurrentPos()

bool apollo::planning::ReferenceLineInfo::AdjustTrajectoryWhichStartsFromCurrentPos ( const common::TrajectoryPoint planning_start_point,
const std::vector< common::TrajectoryPoint > &  trajectory,
DiscretizedTrajectory adjusted_trajectory 
)

在文件 reference_line_info.cc593 行定义.

596 {
597 ACHECK(adjusted_trajectory != nullptr);
598 // find insert index by check heading
599 static constexpr double kMaxAngleDiff = M_PI_2;
600 const double start_point_heading = planning_start_point.path_point().theta();
601 const double start_point_x = planning_start_point.path_point().x();
602 const double start_point_y = planning_start_point.path_point().y();
603 const double start_point_relative_time = planning_start_point.relative_time();
604
605 int insert_idx = -1;
606 for (size_t i = 0; i < trajectory.size(); ++i) {
607 // skip trajectory_points early than planning_start_point
608 if (trajectory[i].relative_time() <= start_point_relative_time) {
609 continue;
610 }
611
612 const double cur_point_x = trajectory[i].path_point().x();
613 const double cur_point_y = trajectory[i].path_point().y();
614 const double tracking_heading =
615 std::atan2(cur_point_y - start_point_y, cur_point_x - start_point_x);
616 if (std::fabs(common::math::AngleDiff(start_point_heading,
617 tracking_heading)) < kMaxAngleDiff) {
618 insert_idx = i;
619 break;
620 }
621 }
622 if (insert_idx == -1) {
623 AERROR << "All points are behind of planning init point";
624 return false;
625 }
626
627 DiscretizedTrajectory cut_trajectory(trajectory);
628 cut_trajectory.erase(cut_trajectory.begin(),
629 cut_trajectory.begin() + insert_idx);
630 cut_trajectory.insert(cut_trajectory.begin(), planning_start_point);
631
632 // In class TrajectoryStitcher, the stitched point which is also the planning
633 // init point is supposed have one planning_cycle_time ahead respect to
634 // current timestamp as its relative time. So the relative timelines
635 // of planning init point and the trajectory which start from current
636 // position(relative time = 0) are the same. Therefore any conflicts on the
637 // relative time including the one below should return false and inspected its
638 // cause.
639 if (cut_trajectory.size() > 1 && cut_trajectory.front().relative_time() >=
640 cut_trajectory[1].relative_time()) {
641 AERROR << "planning init point relative_time["
642 << cut_trajectory.front().relative_time()
643 << "] larger than its next point's relative_time["
644 << cut_trajectory[1].relative_time() << "]";
645 return false;
646 }
647
648 // In class TrajectoryStitcher, the planing_init_point is set to have s as 0,
649 // so adjustment is needed to be done on the other points
650 double accumulated_s = 0.0;
651 for (size_t i = 1; i < cut_trajectory.size(); ++i) {
652 const auto& pre_path_point = cut_trajectory[i - 1].path_point();
653 auto* cur_path_point = cut_trajectory[i].mutable_path_point();
654 accumulated_s += std::sqrt((cur_path_point->x() - pre_path_point.x()) *
655 (cur_path_point->x() - pre_path_point.x()) +
656 (cur_path_point->y() - pre_path_point.y()) *
657 (cur_path_point->y() - pre_path_point.y()));
658 cur_path_point->set_s(accumulated_s);
659 }
660
661 // reevaluate relative_time to make delta t the same
662 adjusted_trajectory->clear();
663 // use varied resolution to reduce data load but also provide enough data
664 // point for control module
665 const double kDenseTimeResoltuion = FLAGS_trajectory_time_min_interval;
666 const double kSparseTimeResolution = FLAGS_trajectory_time_max_interval;
667 const double kDenseTimeSec = FLAGS_trajectory_time_high_density_period;
668 for (double cur_rel_time = cut_trajectory.front().relative_time();
669 cur_rel_time <= cut_trajectory.back().relative_time();
670 cur_rel_time += (cur_rel_time < kDenseTimeSec ? kDenseTimeResoltuion
671 : kSparseTimeResolution)) {
672 adjusted_trajectory->AppendTrajectoryPoint(
673 cut_trajectory.Evaluate(cur_rel_time));
674 }
675 return true;
676}
const DiscretizedTrajectory & trajectory() const
#define ACHECK(cond)
Definition log.h:80
double AngleDiff(const double from, const double to)
Calculate the difference between angle from and to
Definition math_utils.cc:61

◆ CombinePathAndSpeedProfile()

bool apollo::planning::ReferenceLineInfo::CombinePathAndSpeedProfile ( const double  relative_time,
const double  start_s,
DiscretizedTrajectory discretized_trajectory 
)

在文件 reference_line_info.cc531 行定义.

533 {
534 ACHECK(ptr_discretized_trajectory != nullptr);
535 // use varied resolution to reduce data load but also provide enough data
536 // point for control module
537 const double kDenseTimeResoltuion = FLAGS_trajectory_time_min_interval;
538 const double kSparseTimeResolution = FLAGS_trajectory_time_max_interval;
539 const double kDenseTimeSec = FLAGS_trajectory_time_high_density_period;
540
541 if (path_data_.discretized_path().empty()) {
542 AERROR << "path data is empty";
543 return false;
544 }
545
546 if (speed_data_.empty()) {
547 AERROR << "speed profile is empty";
548 return false;
549 }
550
551 for (double cur_rel_time = 0.0; cur_rel_time < speed_data_.TotalTime();
552 cur_rel_time += (cur_rel_time < kDenseTimeSec ? kDenseTimeResoltuion
553 : kSparseTimeResolution)) {
554 common::SpeedPoint speed_point;
555 if (!speed_data_.EvaluateByTime(cur_rel_time, &speed_point)) {
556 AERROR << "Fail to get speed point with relative time " << cur_rel_time;
557 return false;
558 }
559
560 if (speed_point.s() > path_data_.discretized_path().Length()) {
561 break;
562 }
563 common::PathPoint path_point =
564 path_data_.GetPathPointWithPathS(speed_point.s());
565 path_point.set_s(path_point.s() + start_s);
566
567 common::TrajectoryPoint trajectory_point;
568 trajectory_point.mutable_path_point()->CopyFrom(path_point);
569 trajectory_point.set_v(speed_point.v());
570 trajectory_point.set_a(speed_point.a());
571 trajectory_point.set_relative_time(speed_point.t() + relative_time);
572 ptr_discretized_trajectory->AppendTrajectoryPoint(trajectory_point);
573 }
574 if (path_data_.is_reverse_path()) {
575 std::for_each(ptr_discretized_trajectory->begin(),
576 ptr_discretized_trajectory->end(),
577 [](common::TrajectoryPoint& trajectory_point) {
578 trajectory_point.set_v(-trajectory_point.v());
579 trajectory_point.set_a(-trajectory_point.a());
580 trajectory_point.mutable_path_point()->set_s(
581 -trajectory_point.path_point().s());
582 });
583 AINFO << "reversed path";
584 ptr_discretized_trajectory->SetIsReversed(true);
585 }
586 return true;
587}
bool is_reverse_path() const
Definition path_data.h:113
common::PathPoint GetPathPointWithPathS(const double s) const
Definition path_data.cc:112
const DiscretizedPath & discretized_path() const
Definition path_data.cc:90
bool EvaluateByTime(const double time, common::SpeedPoint *const speed_point) const
Definition speed_data.cc:60

◆ Cost()

double apollo::planning::ReferenceLineInfo::Cost ( ) const
inline

在文件 reference_line_info.h86 行定义.

86{ return cost_; }

◆ debug()

const planning_internal::Debug & apollo::planning::ReferenceLineInfo::debug ( ) const
inline

在文件 reference_line_info.h127 行定义.

127{ return debug_; }

◆ ExportDecision()

void apollo::planning::ReferenceLineInfo::ExportDecision ( DecisionResult *  decision_result,
PlanningContext planning_context 
) const

在文件 reference_line_info.cc873 行定义.

874 {
875 MakeDecision(decision_result, planning_context);
876 ExportVehicleSignal(decision_result->mutable_vehicle_signal());
877 auto* main_decision = decision_result->mutable_main_decision();
878 if (main_decision->has_stop()) {
879 main_decision->mutable_stop()->set_change_lane_type(
880 Lanes().PreviousAction());
881 } else if (main_decision->has_cruise()) {
882 main_decision->mutable_cruise()->set_change_lane_type(
883 Lanes().PreviousAction());
884 }
885}
const hdmap::RouteSegments & Lanes() const

◆ ExportEngageAdvice()

void apollo::planning::ReferenceLineInfo::ExportEngageAdvice ( common::EngageAdvice engage_advice,
PlanningContext planning_context 
) const

在文件 reference_line_info.cc1008 行定义.

1009 {
1010 static EngageAdvice prev_advice;
1011 static constexpr double kMaxAngleDiff = M_PI / 6.0;
1012
1013 bool engage = false;
1014 if (!IsDrivable()) {
1015 prev_advice.set_reason("Reference line not drivable");
1016 } else if (!is_on_reference_line_) {
1017 const auto& scenario_type =
1018 planning_context->planning_status().scenario().scenario_type();
1019 if (scenario_type == "PARK_AND_GO" || IsChangeLanePath()) {
1020 // note: when is_on_reference_line_ is FALSE
1021 // (1) always engage while in PARK_AND_GO scenario
1022 // (2) engage when "ChangeLanePath" is picked as Drivable ref line
1023 // where most likely ADC not OnLane yet
1024 engage = true;
1025 } else {
1026 prev_advice.set_reason("Not on reference line");
1027 }
1028 } else {
1029 // check heading
1030 auto ref_point =
1031 reference_line_.GetReferencePoint(adc_sl_boundary_.end_s());
1032 if (common::math::AngleDiff(vehicle_state_.heading(), ref_point.heading()) <
1033 kMaxAngleDiff) {
1034 engage = true;
1035 } else {
1036 prev_advice.set_reason("Vehicle heading is not aligned");
1037 }
1038 }
1039
1040 if (engage) {
1041 if (vehicle_state_.driving_mode() !=
1042 Chassis::DrivingMode::Chassis_DrivingMode_COMPLETE_AUTO_DRIVE) {
1043 // READY_TO_ENGAGE when in non-AUTO mode
1044 prev_advice.set_advice(EngageAdvice::READY_TO_ENGAGE);
1045 } else {
1046 // KEEP_ENGAGED when in AUTO mode
1047 prev_advice.set_advice(EngageAdvice::KEEP_ENGAGED);
1048 }
1049 prev_advice.clear_reason();
1050 } else {
1051 if (prev_advice.advice() != EngageAdvice::DISALLOW_ENGAGE) {
1052 prev_advice.set_advice(EngageAdvice::PREPARE_DISENGAGE);
1053 }
1054 }
1055 engage_advice->CopyFrom(prev_advice);
1056}
bool IsChangeLanePath() const
Check if the current reference line is a change lane reference line, i.e., ADC's current position is ...
ReferencePoint GetReferencePoint(const double s) const
optional apollo::canbus::Chassis::DrivingMode driving_mode

◆ fallback_path_data()

const PathData & apollo::planning::ReferenceLineInfo::fallback_path_data ( ) const

在文件 reference_line_info.cc513 行定义.

513 {
514 return fallback_path_data_;
515}

◆ FirstEncounteredOverlaps()

const std::vector< std::pair< OverlapType, hdmap::PathOverlap > > & apollo::planning::ReferenceLineInfo::FirstEncounteredOverlaps ( ) const
inline

在文件 reference_line_info.h251 行定义.

251 {
252 return first_encounter_overlaps_;
253 }

◆ GetAllStopDecisionSLPoint()

std::vector< common::SLPoint > apollo::planning::ReferenceLineInfo::GetAllStopDecisionSLPoint ( ) const

在文件 reference_line_info.cc1164 行定义.

1165 {
1166 std::vector<common::SLPoint> result;
1167 for (const auto* obstacle : path_decision_.obstacles().Items()) {
1168 const auto& object_decision = obstacle->LongitudinalDecision();
1169 if (!object_decision.has_stop()) {
1170 continue;
1171 }
1172 apollo::common::PointENU stop_point = object_decision.stop().stop_point();
1173 common::SLPoint stop_line_sl;
1174 reference_line_.XYToSL(stop_point, &stop_line_sl);
1175 if (stop_line_sl.s() <= 0 || stop_line_sl.s() >= reference_line_.Length()) {
1176 continue;
1177 }
1178 result.push_back(stop_line_sl);
1179 }
1180
1181 // sort by s
1182 if (!result.empty()) {
1183 std::sort(result.begin(), result.end(),
1184 [](const common::SLPoint& a, const common::SLPoint& b) {
1185 return a.s() < b.s();
1186 });
1187 }
1188
1189 return result;
1190}
bool XYToSL(const common::math::Vec2d &xy_point, common::SLPoint *const sl_point, double warm_start_s=-1.0) const
Transvert Cartesian coordinates to Frenet.

◆ GetArea()

int apollo::planning::ReferenceLineInfo::GetArea ( const double  s,
hdmap::PathOverlap area_overlap 
) const

在文件 reference_line_info.cc1143 行定义.

1144 {
1145 CHECK_NOTNULL(area_overlap);
1146 const std::vector<hdmap::PathOverlap>& area_overlaps =
1147 reference_line_.map_path().area_overlaps();
1148
1149 static constexpr double kError = 1.0; // meter
1150 for (const auto& overlap : area_overlaps) {
1151 if (s >= overlap.start_s - kError && s <= overlap.end_s + kError) {
1152 *area_overlap = overlap;
1153 return 1;
1154 }
1155 }
1156 return 0;
1157}
const std::vector< PathOverlap > & area_overlaps() const
Definition path.h:331
const hdmap::Path & map_path() const

◆ GetBaseCruiseSpeed()

double apollo::planning::ReferenceLineInfo::GetBaseCruiseSpeed ( ) const

在文件 reference_line_info.cc165 行定义.

165 {
166 return base_cruise_speed_ > 0.0 ? base_cruise_speed_
167 : FLAGS_default_cruise_speed;
168}

◆ GetBlockingObstacle()

Obstacle * apollo::planning::ReferenceLineInfo::GetBlockingObstacle ( ) const
inline

在文件 reference_line_info.h210 行定义.

210{ return blocking_obstacle_; }

◆ GetCandidatePathBoundaries()

const std::vector< PathBoundary > & apollo::planning::ReferenceLineInfo::GetCandidatePathBoundaries ( ) const

在文件 reference_line_info.cc148 行定义.

149 {
150 return candidate_path_boundaries_;
151}

◆ GetCandidatePathData()

const std::vector< PathData > & apollo::planning::ReferenceLineInfo::GetCandidatePathData ( ) const

在文件 reference_line_info.cc139 行定义.

139 {
140 return candidate_path_data_;
141}

◆ GetCruiseSpeed()

double apollo::planning::ReferenceLineInfo::GetCruiseSpeed ( ) const

在文件 reference_line_info.cc170 行定义.

170 {
171 return cruise_speed_ > 0.0 ? cruise_speed_ : FLAGS_default_cruise_speed;
172}

◆ GetIntersectionRightofWayStatus()

bool apollo::planning::ReferenceLineInfo::GetIntersectionRightofWayStatus ( const hdmap::PathOverlap pnc_junction_overlap) const

在文件 reference_line_info.cc1101 行定义.

1102 {
1103 if (GetPathTurnType(pnc_junction_overlap.start_s) != hdmap::Lane::NO_TURN) {
1104 return false;
1105 }
1106
1107 // TODO(all): iterate exits of intersection to check/compare speed-limit
1108 return true;
1109}
hdmap::Lane::LaneTurn GetPathTurnType(const double s) const

◆ GetJunction()

int apollo::planning::ReferenceLineInfo::GetJunction ( const double  s,
hdmap::PathOverlap junction_overlap 
) const

在文件 reference_line_info.cc1127 行定义.

1128 {
1129 CHECK_NOTNULL(junction_overlap);
1130 const std::vector<hdmap::PathOverlap>& junction_overlaps =
1131 reference_line_.map_path().junction_overlaps();
1132
1133 static constexpr double kError = 1.0; // meter
1134 for (const auto& overlap : junction_overlaps) {
1135 if (s >= overlap.start_s - kError && s <= overlap.end_s + kError) {
1136 *junction_overlap = overlap;
1137 return 1;
1138 }
1139 }
1140 return 0;
1141}
const std::vector< PathOverlap > & junction_overlaps() const
Definition path.h:313

◆ GetNeighborLaneInfo()

bool apollo::planning::ReferenceLineInfo::GetNeighborLaneInfo ( const ReferenceLineInfo::LaneType  lane_type,
const double  s,
hdmap::Id ptr_lane_id,
double *  ptr_lane_width 
) const

在文件 reference_line_info.cc186 行定义.

188 {
189 auto ptr_lane_info = LocateLaneInfo(s);
190 if (ptr_lane_info == nullptr) {
191 return false;
192 }
193
194 switch (lane_type) {
196 if (ptr_lane_info->lane().left_neighbor_forward_lane_id().empty()) {
197 return false;
198 }
199 *ptr_lane_id = ptr_lane_info->lane().left_neighbor_forward_lane_id(0);
200 break;
201 }
203 if (ptr_lane_info->lane().left_neighbor_reverse_lane_id().empty()) {
204 return false;
205 }
206 *ptr_lane_id = ptr_lane_info->lane().left_neighbor_reverse_lane_id(0);
207 break;
208 }
210 if (ptr_lane_info->lane().right_neighbor_forward_lane_id().empty()) {
211 return false;
212 }
213 *ptr_lane_id = ptr_lane_info->lane().right_neighbor_forward_lane_id(0);
214 break;
215 }
217 if (ptr_lane_info->lane().right_neighbor_reverse_lane_id().empty()) {
218 return false;
219 }
220 *ptr_lane_id = ptr_lane_info->lane().right_neighbor_reverse_lane_id(0);
221 break;
222 }
223 default:
224 ACHECK(false);
225 }
226 auto ptr_neighbor_lane =
228 if (ptr_neighbor_lane == nullptr) {
229 return false;
230 }
231
232 auto ref_point = reference_line_.GetReferencePoint(s);
233
234 double neighbor_s = 0.0;
235 double neighbor_l = 0.0;
236 if (!ptr_neighbor_lane->GetProjection({ref_point.x(), ref_point.y()},
237 &neighbor_s, &neighbor_l)) {
238 return false;
239 }
240
241 *ptr_lane_width = ptr_neighbor_lane->GetWidth(neighbor_s);
242 return true;
243}
static const HDMap * BaseMapPtr()
LaneInfoConstPtr GetLaneById(const Id &id) const
Definition hdmap.cc:34
hdmap::LaneInfoConstPtr LocateLaneInfo(const double s) const

◆ GetOverlapOnReferenceLine()

hdmap::PathOverlap * apollo::planning::ReferenceLineInfo::GetOverlapOnReferenceLine ( const std::string &  overlap_id,
const OverlapType overlap_type 
) const

在文件 reference_line_info.cc1192 行定义.

1193 {
1194 if (overlap_type == ReferenceLineInfo::SIGNAL) {
1195 // traffic_light_overlap
1196 const auto& traffic_light_overlaps =
1197 reference_line_.map_path().signal_overlaps();
1198 for (const auto& traffic_light_overlap : traffic_light_overlaps) {
1199 if (traffic_light_overlap.object_id == overlap_id) {
1200 return const_cast<hdmap::PathOverlap*>(&traffic_light_overlap);
1201 }
1202 }
1203 } else if (overlap_type == ReferenceLineInfo::STOP_SIGN) {
1204 // stop_sign_overlap
1205 const auto& stop_sign_overlaps =
1206 reference_line_.map_path().stop_sign_overlaps();
1207 for (const auto& stop_sign_overlap : stop_sign_overlaps) {
1208 if (stop_sign_overlap.object_id == overlap_id) {
1209 return const_cast<hdmap::PathOverlap*>(&stop_sign_overlap);
1210 }
1211 }
1212 } else if (overlap_type == ReferenceLineInfo::PNC_JUNCTION) {
1213 // pnc_junction_overlap
1214 const auto& pnc_junction_overlaps =
1215 reference_line_.map_path().pnc_junction_overlaps();
1216 for (const auto& pnc_junction_overlap : pnc_junction_overlaps) {
1217 if (pnc_junction_overlap.object_id == overlap_id) {
1218 return const_cast<hdmap::PathOverlap*>(&pnc_junction_overlap);
1219 }
1220 }
1221 } else if (overlap_type == ReferenceLineInfo::YIELD_SIGN) {
1222 // yield_sign_overlap
1223 const auto& yield_sign_overlaps =
1224 reference_line_.map_path().yield_sign_overlaps();
1225 for (const auto& yield_sign_overlap : yield_sign_overlaps) {
1226 if (yield_sign_overlap.object_id == overlap_id) {
1227 return const_cast<hdmap::PathOverlap*>(&yield_sign_overlap);
1228 }
1229 }
1230 } else if (overlap_type == ReferenceLineInfo::JUNCTION) {
1231 // junction_overlap
1232 const auto& junction_overlaps =
1233 reference_line_.map_path().junction_overlaps();
1234 for (const auto& junction_overlap : junction_overlaps) {
1235 if (junction_overlap.object_id == overlap_id) {
1236 return const_cast<hdmap::PathOverlap*>(&junction_overlap);
1237 }
1238 }
1239 } else if (overlap_type == ReferenceLineInfo::AREA) {
1240 // area_overlap
1241 const auto& area_overlaps = reference_line_.map_path().area_overlaps();
1242 for (const auto& area_overlap : area_overlaps) {
1243 if (area_overlap.object_id == overlap_id) {
1244 return const_cast<hdmap::PathOverlap*>(&area_overlap);
1245 }
1246 }
1247 }
1248
1249 return nullptr;
1250}
const std::vector< PathOverlap > & signal_overlaps() const
Definition path.h:301
const std::vector< PathOverlap > & yield_sign_overlaps() const
Definition path.h:304
const std::vector< PathOverlap > & pnc_junction_overlaps() const
Definition path.h:316
const std::vector< PathOverlap > & stop_sign_overlaps() const
Definition path.h:307

◆ GetPathTurnType()

hdmap::Lane::LaneTurn apollo::planning::ReferenceLineInfo::GetPathTurnType ( const double  s) const

在文件 reference_line_info.cc1079 行定义.

1079 {
1080 const double forward_buffer = 20.0;
1081 double route_s = 0.0;
1082 for (const auto& seg : Lanes()) {
1083 if (route_s > s + forward_buffer) {
1084 break;
1085 }
1086 route_s += seg.end_s - seg.start_s;
1087 if (route_s < s) {
1088 continue;
1089 }
1090 const auto& turn_type = seg.lane->lane().turn();
1091 if (turn_type == hdmap::Lane::LEFT_TURN ||
1092 turn_type == hdmap::Lane::RIGHT_TURN ||
1093 turn_type == hdmap::Lane::U_TURN) {
1094 return turn_type;
1095 }
1096 }
1097
1098 return hdmap::Lane::NO_TURN;
1099}

◆ GetPnCJunction()

int apollo::planning::ReferenceLineInfo::GetPnCJunction ( const double  s,
hdmap::PathOverlap pnc_junction_overlap 
) const

在文件 reference_line_info.cc1111 行定义.

1112 {
1113 CHECK_NOTNULL(pnc_junction_overlap);
1114 const std::vector<hdmap::PathOverlap>& pnc_junction_overlaps =
1115 reference_line_.map_path().pnc_junction_overlaps();
1116
1117 static constexpr double kError = 1.0; // meter
1118 for (const auto& overlap : pnc_junction_overlaps) {
1119 if (s >= overlap.start_s - kError && s <= overlap.end_s + kError) {
1120 *pnc_junction_overlap = overlap;
1121 return 1;
1122 }
1123 }
1124 return 0;
1125}

◆ GetPriority()

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

在文件 reference_line_info.h220 行定义.

220{ return reference_line_.GetPriority(); }

◆ GetRangeOverlaps()

void apollo::planning::ReferenceLineInfo::GetRangeOverlaps ( std::vector< hdmap::PathOverlap > *  path_overlaps,
double  start_s,
double  end_s 
)

在文件 reference_line_info.cc1255 行定义.

1257 {
1258 CHECK_NOTNULL(path_overlaps);
1259 const std::vector<hdmap::PathOverlap>& junction_overlaps =
1260 reference_line_.map_path().junction_overlaps();
1261
1262 static constexpr double kError = 0.1; // meter
1263 AINFO << "GetRangeOverlaps start_s: " << start_s << ", end_s: " << end_s;
1264 for (const auto& overlap : junction_overlaps) {
1265 if (start_s >= overlap.end_s - kError) {
1266 continue;
1267 } else if (end_s < overlap.start_s - kError) {
1268 break;
1269 } else {
1270 AINFO << "overlap emplace_back " << overlap.start_s << ", "
1271 << overlap.end_s << " ]";
1272 path_overlaps->emplace_back(overlap);
1273 }
1274 }
1275}

◆ GetRightOfWayStatus()

ADCTrajectory::RightOfWayStatus apollo::planning::ReferenceLineInfo::GetRightOfWayStatus ( ) const

在文件 reference_line_info.cc342 行定义.

342 {
343 for (const auto& overlap : reference_line_.map_path().junction_overlaps()) {
344 if (overlap.end_s < adc_sl_boundary_.start_s()) {
345 junction_right_of_way_map_.erase(overlap.object_id);
346 } else if (WithinOverlap(overlap, adc_sl_boundary_.end_s())) {
347 auto is_protected = junction_right_of_way_map_[overlap.object_id];
348 if (is_protected) {
350 }
351 }
352 }
354}
bool WithinOverlap(const hdmap::PathOverlap &overlap, double s)

◆ id()

std::string apollo::planning::ReferenceLineInfo::id ( ) const
inline

在文件 reference_line_info.h279 行定义.

279{ return id_; }

◆ index()

std::size_t apollo::planning::ReferenceLineInfo::index ( ) const
inline

在文件 reference_line_info.h276 行定义.

276{ return index_; }

◆ Init()

bool apollo::planning::ReferenceLineInfo::Init ( const std::vector< const Obstacle * > &  obstacles,
double  target_speed 
)

在文件 reference_line_info.cc77 行定义.

78 {
79 const auto& param = VehicleConfigHelper::GetConfig().vehicle_param();
80 // stitching point
81 const auto& path_point = adc_planning_point_.path_point();
82 Vec2d position(path_point.x(), path_point.y());
83 Vec2d vec_to_center(
84 (param.front_edge_to_center() - param.back_edge_to_center()) / 2.0,
85 (param.left_edge_to_center() - param.right_edge_to_center()) / 2.0);
86 Vec2d center(position + vec_to_center.rotate(path_point.theta()));
87 Box2d box(center, path_point.theta(), param.length(), param.width());
88 // realtime vehicle position
89 Vec2d vehicle_position(vehicle_state_.x(), vehicle_state_.y());
90 Vec2d vehicle_center(vehicle_position +
91 vec_to_center.rotate(vehicle_state_.heading()));
92 Box2d vehicle_box(vehicle_center, vehicle_state_.heading(), param.length(),
93 param.width());
94
95 if (!reference_line_.GetSLBoundary(box, &adc_sl_boundary_)) {
96 AERROR << "Failed to get ADC boundary from box: " << box.DebugString();
97 return false;
98 }
99
100 InitFirstOverlaps();
101
102 if (adc_sl_boundary_.end_s() < 0 ||
103 adc_sl_boundary_.start_s() > reference_line_.Length()) {
104 AWARN << "Vehicle SL " << adc_sl_boundary_.ShortDebugString()
105 << " is not on reference line:[0, " << reference_line_.Length()
106 << "]";
107 }
108 static constexpr double kOutOfReferenceLineL = 14.0; // in meters
109 if (adc_sl_boundary_.start_l() > kOutOfReferenceLineL ||
110 adc_sl_boundary_.end_l() < -kOutOfReferenceLineL) {
111 AERROR << "Ego vehicle is too far away from reference line."
112 << "adc_sl_boundary_.start_l:" << adc_sl_boundary_.start_l()
113 << "adc_sl_boundary_.end_l:" << adc_sl_boundary_.end_l();
114 return false;
115 }
116 is_on_reference_line_ = reference_line_.IsOnLane(adc_sl_boundary_);
117 if (!AddObstacles(obstacles)) {
118 AERROR << "Failed to add obstacles to reference line";
119 return false;
120 }
121
122 const auto& map_path = reference_line_.map_path();
123 for (const auto& speed_bump : map_path.speed_bump_overlaps()) {
124 // -1 and + 1.0 are added to make sure it can be sampled.
125 reference_line_.AddSpeedLimit(speed_bump.start_s - 1.0,
126 speed_bump.end_s + 1.0,
127 FLAGS_speed_bump_speed_limit);
128 }
129
130 SetCruiseSpeed(target_speed);
131 // set lattice planning target speed limit;
132 SetLatticeCruiseSpeed(target_speed);
133
134 vehicle_signal_.Clear();
135
136 return true;
137}
static const VehicleConfig & GetConfig()
Get the current vehicle configuration.
bool AddObstacles(const std::vector< const Obstacle * > &obstacles)
bool IsOnLane(const common::SLPoint &sl_point) const
: check if a box/point is on lane along reference line
void AddSpeedLimit(double start_s, double end_s, double speed_limit)
#define AWARN
Definition log.h:43
optional VehicleParam vehicle_param

◆ is_path_lane_borrow()

bool apollo::planning::ReferenceLineInfo::is_path_lane_borrow ( ) const
inline

在文件 reference_line_info.h213 行定义.

213{ return is_path_lane_borrow_; }

◆ IsChangeLanePath()

bool apollo::planning::ReferenceLineInfo::IsChangeLanePath ( ) const

Check if the current reference line is a change lane reference line, i.e., ADC's current position is not on this reference line.

在文件 reference_line_info.cc682 行定义.

682 {
683 return !Lanes().IsOnSegment();
684}

◆ IsDrivable()

bool apollo::planning::ReferenceLineInfo::IsDrivable ( ) const

在文件 reference_line_info.cc680 行定义.

680{ return is_drivable_; }

◆ IsNeighborLanePath()

bool apollo::planning::ReferenceLineInfo::IsNeighborLanePath ( ) const

Check if the current reference line is the neighbor of the vehicle current position

在文件 reference_line_info.cc686 行定义.

686 {
687 return Lanes().IsNeighborSegment();
688}

◆ IsStartFrom()

bool apollo::planning::ReferenceLineInfo::IsStartFrom ( const ReferenceLineInfo previous_reference_line_info) const

check if current reference line is started from another reference line info line.

The method is to check if the start point of current reference line is on previous reference line info.

返回
returns true if current reference line starts on previous reference line, otherwise false.

在文件 reference_line_info.cc498 行定义.

499 {
500 if (reference_line_.reference_points().empty()) {
501 return false;
502 }
503 auto start_point = reference_line_.reference_points().front();
504 const auto& prev_reference_line =
505 previous_reference_line_info.reference_line();
506 common::SLPoint sl_point;
507 prev_reference_line.XYToSL(start_point, &sl_point);
508 return previous_reference_line_info.reference_line_.IsOnLane(sl_point);
509}
const std::vector< ReferencePoint > & reference_points() const

◆ key()

std::size_t apollo::planning::ReferenceLineInfo::key ( ) const
inline

在文件 reference_line_info.h273 行定义.

273{ return key_; }

◆ Lanes()

const hdmap::RouteSegments & apollo::planning::ReferenceLineInfo::Lanes ( ) const

在文件 reference_line_info.cc356 行定义.

356{ return lanes_; }

◆ latency_stats()

const LatencyStats & apollo::planning::ReferenceLineInfo::latency_stats ( ) const
inline

在文件 reference_line_info.h129 行定义.

129{ return latency_stats_; }

◆ LimitCruiseSpeed()

void apollo::planning::ReferenceLineInfo::LimitCruiseSpeed ( double  speed)

Limit the cruise speed based on the "base_cruise_speed_".

If the new setting speed > "base_cruise_speed_", it will be ignored.

参数
speedThe new speed.

在文件 reference_line_info.cc158 行定义.

158 {
159 if (base_cruise_speed_ <= speed) {
160 return;
161 }
162 cruise_speed_ = speed;
163}

◆ LocateLaneInfo()

hdmap::LaneInfoConstPtr apollo::planning::ReferenceLineInfo::LocateLaneInfo ( const double  s) const

在文件 reference_line_info.cc174 行定义.

175 {
176 std::vector<hdmap::LaneInfoConstPtr> lanes;
177 reference_line_.GetLaneFromS(s, &lanes);
178 if (lanes.empty()) {
179 AWARN << "cannot get any lane using s";
180 return nullptr;
181 }
182
183 return lanes.front();
184}
void GetLaneFromS(const double s, std::vector< hdmap::LaneInfoConstPtr > *lanes) const

◆ mutable_debug()

planning_internal::Debug * apollo::planning::ReferenceLineInfo::mutable_debug ( )
inline

在文件 reference_line_info.h126 行定义.

126{ return &debug_; }

◆ mutable_fallback_path_data()

PathData * apollo::planning::ReferenceLineInfo::mutable_fallback_path_data ( )

在文件 reference_line_info.cc521 行定义.

521 {
522 return &fallback_path_data_;
523}

◆ mutable_latency_stats()

LatencyStats * apollo::planning::ReferenceLineInfo::mutable_latency_stats ( )
inline

在文件 reference_line_info.h128 行定义.

128{ return &latency_stats_; }

◆ mutable_path_data()

PathData * apollo::planning::ReferenceLineInfo::mutable_path_data ( )

在文件 reference_line_info.cc519 行定义.

519{ return &path_data_; }

◆ mutable_reference_line()

ReferenceLine * apollo::planning::ReferenceLineInfo::mutable_reference_line ( )

在文件 reference_line_info.cc380 行定义.

380 {
381 return &reference_line_;
382}

◆ mutable_reference_line_towing_l()

std::vector< double > * apollo::planning::ReferenceLineInfo::mutable_reference_line_towing_l ( )

在文件 reference_line_info.cc1281 行定义.

1281 {
1282 return &reference_line_towing_l_;
1283}

◆ mutable_reference_line_towing_path_boundary()

PathBoundary * apollo::planning::ReferenceLineInfo::mutable_reference_line_towing_path_boundary ( )

在文件 reference_line_info.cc1290 行定义.

1290 {
1291 return &reference_line_towing_path_boundary_;
1292}

◆ mutable_rss_info()

RSSInfo * apollo::planning::ReferenceLineInfo::mutable_rss_info ( )

在文件 reference_line_info.cc529 行定义.

529{ return &rss_info_; }

◆ mutable_speed_data()

SpeedData * apollo::planning::ReferenceLineInfo::mutable_speed_data ( )

在文件 reference_line_info.cc525 行定义.

525{ return &speed_data_; }

◆ mutable_st_graph_data()

StGraphData * apollo::planning::ReferenceLineInfo::mutable_st_graph_data ( )
inline

在文件 reference_line_info.h233 行定义.

233{ return &st_graph_data_; }

◆ MutableCandidatePathData()

std::vector< PathData > * apollo::planning::ReferenceLineInfo::MutableCandidatePathData ( )

在文件 reference_line_info.cc1251 行定义.

1251 {
1252 return &candidate_path_data_;
1253}

◆ OffsetToOtherReferenceLine()

double apollo::planning::ReferenceLineInfo::OffsetToOtherReferenceLine ( ) const
inline

在文件 reference_line_info.h194 行定义.

194 {
195 return offset_to_other_reference_line_;
196 }

◆ path_data()

const PathData & apollo::planning::ReferenceLineInfo::path_data ( ) const

在文件 reference_line_info.cc511 行定义.

511{ return path_data_; }

◆ path_decision() [1/2]

PathDecision * apollo::planning::ReferenceLineInfo::path_decision ( )

在文件 reference_line_info.cc370 行定义.

370{ return &path_decision_; }

◆ path_decision() [2/2]

const PathDecision & apollo::planning::ReferenceLineInfo::path_decision ( ) const

在文件 reference_line_info.cc372 行定义.

372 {
373 return path_decision_;
374}

◆ path_reusable()

bool apollo::planning::ReferenceLineInfo::path_reusable ( ) const
inline

在文件 reference_line_info.h268 行定义.

268{ return path_reusable_; }

◆ PathSpeedDebugString()

std::string apollo::planning::ReferenceLineInfo::PathSpeedDebugString ( ) const

在文件 reference_line_info.cc690 行定义.

690 {
691 return absl::StrCat("path_data:", path_data_.DebugString(),
692 "speed_data:", speed_data_.DebugString());
693}
std::string DebugString() const
Definition path_data.cc:161
virtual std::string DebugString() const

◆ planning_target()

const PlanningTarget & apollo::planning::ReferenceLineInfo::planning_target ( ) const
inline

在文件 reference_line_info.h94 行定义.

94{ return planning_target_; }

◆ PrintReferenceSegmentDebugString()

void apollo::planning::ReferenceLineInfo::PrintReferenceSegmentDebugString ( )

在文件 reference_line_info.cc1294 行定义.

1294 {
1295 PrintCurves print_curve;
1296 const auto& lane_segments = reference_line_.GetMapPath().lane_segments();
1297 for (size_t i = 0; i < lane_segments.size(); ++i) {
1298 for (const auto& seg :
1299 lane_segments.at(i).lane->lane().left_boundary().curve().segment()) {
1300 for (const auto& pt : seg.line_segment().point()) {
1301 print_curve.AddPoint(std::to_string(index_) + "_left_pt_print", pt.x(),
1302 pt.y());
1303 }
1304 }
1305 for (const auto& seg :
1306 lane_segments.at(i).lane->lane().right_boundary().curve().segment()) {
1307 for (const auto& pt : seg.line_segment().point()) {
1308 print_curve.AddPoint(std::to_string(index_) + "_right_pt_print", pt.x(),
1309 pt.y());
1310 }
1311 }
1312 for (const auto& pt : lane_segments.at(i).lane->points()) {
1313 print_curve.AddPoint(std::to_string(index_) + "_center_pt_print", pt.x(),
1314 pt.y());
1315 }
1316 }
1317 print_curve.PrintToLog();
1318}
const std::vector< LaneSegment > & lane_segments() const
Definition path.h:280
const hdmap::Path & GetMapPath() const

◆ PriorityCost()

double apollo::planning::ReferenceLineInfo::PriorityCost ( ) const
inline

在文件 reference_line_info.h89 行定义.

89{ return priority_cost_; }

◆ ReachedDestination()

bool apollo::planning::ReferenceLineInfo::ReachedDestination ( ) const

在文件 reference_line_info.cc815 行定义.

815 {
816 const double distance_destination = SDistanceToDestination();
817 const double distance_ref_end = SDistanceToRefEnd();
818 AINFO << "distance_destination:" << distance_destination
819 << "distance_ref_end: " << distance_ref_end;
820 return distance_destination <= FLAGS_passed_destination_threshold ||
821 distance_ref_end <= FLAGS_passed_referenceline_end_threshold;
822}

◆ reference_line()

const ReferenceLine & apollo::planning::ReferenceLineInfo::reference_line ( ) const

在文件 reference_line_info.cc376 行定义.

376 {
377 return reference_line_;
378}

◆ reference_line_towing_l()

const std::vector< double > & apollo::planning::ReferenceLineInfo::reference_line_towing_l ( ) const

在文件 reference_line_info.cc1277 行定义.

1277 {
1278 return reference_line_towing_l_;
1279}

◆ reference_line_towing_path_boundary()

const PathBoundary & apollo::planning::ReferenceLineInfo::reference_line_towing_path_boundary ( ) const

在文件 reference_line_info.cc1285 行定义.

1286 {
1287 return reference_line_towing_path_boundary_;
1288}

◆ rss_info()

const RSSInfo & apollo::planning::ReferenceLineInfo::rss_info ( ) const

在文件 reference_line_info.cc527 行定义.

527{ return rss_info_; }

◆ SDistanceToDestination()

double apollo::planning::ReferenceLineInfo::SDistanceToDestination ( ) const

在文件 reference_line_info.cc824 行定义.

824 {
825 double res = std::numeric_limits<double>::max();
826 const auto* dest_ptr = path_decision_.Find(FLAGS_destination_obstacle_id);
827 if (!dest_ptr) {
828 return res;
829 }
830 if (!dest_ptr->LongitudinalDecision().has_stop()) {
831 return res;
832 }
833 if (!reference_line_.IsOnLane(dest_ptr->PerceptionBoundingBox().center())) {
834 return res;
835 }
836 const double stop_s = dest_ptr->PerceptionSLBoundary().start_s() +
837 dest_ptr->LongitudinalDecision().stop().distance_s();
838 AINFO << "stop_s: " << stop_s << "end_s: " << adc_sl_boundary_.end_s();
839 return stop_s - adc_sl_boundary_.end_s();
840}
const SLBoundary & PerceptionSLBoundary() const
Definition obstacle.cc:694
const Obstacle * Find(const std::string &object_id) const

◆ SDistanceToRefEnd()

double apollo::planning::ReferenceLineInfo::SDistanceToRefEnd ( ) const

在文件 reference_line_info.cc842 行定义.

842 {
843 double res = std::numeric_limits<double>::max();
844
845 std::string ref_end_id;
846 for (const auto* obstacle : path_decision_.obstacles().Items()) {
847 std::string id = obstacle->Id();
848 if (id.find("REF_END") != std::string::npos) {
849 ref_end_id = id;
850 AINFO << "Found reference line end id: " << ref_end_id;
851 } else {
852 continue;
853 }
854 }
855 if (!ref_end_id.empty()) {
856 AINFO << "REF_END: " << ref_end_id;
857 const auto* ref_end_ptr = path_decision_.Find(ref_end_id);
858 AINFO << "ref_end_ptr:" << ref_end_ptr->DebugString();
859 if (!ref_end_ptr && !ref_end_ptr->LongitudinalDecision().has_stop() &&
860 !reference_line_.IsOnLane(
861 ref_end_ptr->PerceptionBoundingBox().center())) {
862 const double stop_s =
863 ref_end_ptr->PerceptionSLBoundary().start_s() +
864 ref_end_ptr->LongitudinalDecision().stop().distance_s();
865 AINFO << "REF_END: stop_s: " << stop_s
866 << "end_s: " << adc_sl_boundary_.end_s();
867 res = stop_s - adc_sl_boundary_.end_s();
868 }
869 }
870 return res;
871}
std::string DebugString() const
Definition obstacle.cc:675

◆ set_id()

void apollo::planning::ReferenceLineInfo::set_id ( std::string  id)
inline

在文件 reference_line_info.h278 行定义.

278{ id_ = id; }

◆ set_index()

void apollo::planning::ReferenceLineInfo::set_index ( std::size_t  index)
inline

在文件 reference_line_info.h275 行定义.

275{ index_ = index; }

◆ set_is_on_reference_line()

void apollo::planning::ReferenceLineInfo::set_is_on_reference_line ( )
inline

在文件 reference_line_info.h218 行定义.

218{ is_on_reference_line_ = true; }

◆ set_is_path_lane_borrow()

void apollo::planning::ReferenceLineInfo::set_is_path_lane_borrow ( const bool  is_path_lane_borrow)
inline

在文件 reference_line_info.h214 行定义.

214 {
215 is_path_lane_borrow_ = is_path_lane_borrow;
216 }

◆ set_key()

void apollo::planning::ReferenceLineInfo::set_key ( std::size_t  key)
inline

在文件 reference_line_info.h272 行定义.

272{ key_ = key; }

◆ set_path_reusable()

void apollo::planning::ReferenceLineInfo::set_path_reusable ( const bool  path_reusable)
inline

在文件 reference_line_info.h264 行定义.

264 {
265 path_reusable_ = path_reusable;
266 }

◆ set_trajectory_type()

void apollo::planning::ReferenceLineInfo::set_trajectory_type ( const ADCTrajectory::TrajectoryType  trajectory_type)
inline

在文件 reference_line_info.h224 行定义.

225 {
226 trajectory_type_ = trajectory_type;
227 }
ADCTrajectory::TrajectoryType trajectory_type() const

◆ SetBlockingObstacle()

void apollo::planning::ReferenceLineInfo::SetBlockingObstacle ( const std::string &  blocking_obstacle_id)

在文件 reference_line_info.cc1159 行定义.

1160 {
1161 blocking_obstacle_ = path_decision_.Find(blocking_obstacle_id);
1162}

◆ SetCandidatePathBoundaries()

void apollo::planning::ReferenceLineInfo::SetCandidatePathBoundaries ( std::vector< PathBoundary > &&  candidate_path_boundaries)

在文件 reference_line_info.cc153 行定义.

154 {
155 candidate_path_boundaries_ = std::move(path_boundaries);
156}

◆ SetCandidatePathData()

void apollo::planning::ReferenceLineInfo::SetCandidatePathData ( std::vector< PathData > &&  candidate_path_data)

在文件 reference_line_info.cc143 行定义.

144 {
145 candidate_path_data_ = std::move(candidate_path_data);
146}

◆ SetCost()

void apollo::planning::ReferenceLineInfo::SetCost ( double  cost)
inline

在文件 reference_line_info.h88 行定义.

88{ cost_ = cost; }

◆ SetCruiseSpeed()

void apollo::planning::ReferenceLineInfo::SetCruiseSpeed ( double  speed)
inline

在文件 reference_line_info.h96 行定义.

96 {
97 cruise_speed_ = speed;
98 base_cruise_speed_ = speed;
99 }

◆ SetDrivable()

void apollo::planning::ReferenceLineInfo::SetDrivable ( bool  drivable)

Set if the vehicle can drive following this reference line A planner need to set this value to true if the reference line is OK

在文件 reference_line_info.cc678 行定义.

678{ is_drivable_ = drivable; }

◆ SetEmergencyLight()

void apollo::planning::ReferenceLineInfo::SetEmergencyLight ( )

在文件 reference_line_info.cc804 行定义.

804 {
805 vehicle_signal_.set_emergency_light(true);
806}

◆ SetJunctionRightOfWay()

void apollo::planning::ReferenceLineInfo::SetJunctionRightOfWay ( const double  junction_s,
const bool  is_protected 
) const

在文件 reference_line_info.cc333 行定义.

334 {
335 for (const auto& overlap : reference_line_.map_path().junction_overlaps()) {
336 if (WithinOverlap(overlap, junction_s)) {
337 junction_right_of_way_map_[overlap.object_id] = is_protected;
338 }
339 }
340}

◆ SetLatticeCruiseSpeed()

void apollo::planning::ReferenceLineInfo::SetLatticeCruiseSpeed ( double  speed)

在文件 reference_line_info.cc494 行定义.

494 {
495 planning_target_.set_cruise_speed(speed);
496}

◆ SetLatticeStopPoint()

void apollo::planning::ReferenceLineInfo::SetLatticeStopPoint ( const StopPoint stop_point)

在文件 reference_line_info.cc490 行定义.

490 {
491 planning_target_.mutable_stop_point()->CopyFrom(stop_point);
492}

◆ SetOffsetToOtherReferenceLine()

void apollo::planning::ReferenceLineInfo::SetOffsetToOtherReferenceLine ( const double  offset)
inline

在文件 reference_line_info.h197 行定义.

197 {
198 offset_to_other_reference_line_ = offset;
199 }

◆ SetPriority()

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

在文件 reference_line_info.h222 行定义.

222{ reference_line_.SetPriority(priority); }
void SetPriority(uint32_t priority)

◆ SetPriorityCost()

void apollo::planning::ReferenceLineInfo::SetPriorityCost ( double  cost)
inline

在文件 reference_line_info.h90 行定义.

90{ priority_cost_ = cost; }

◆ SetTrajectory()

void apollo::planning::ReferenceLineInfo::SetTrajectory ( const DiscretizedTrajectory trajectory)

在文件 reference_line_info.cc384 行定义.

384 {
385 discretized_trajectory_ = trajectory;
386}

◆ SetTurnSignal()

void apollo::planning::ReferenceLineInfo::SetTurnSignal ( const common::VehicleSignal::TurnSignal turn_signal)

在文件 reference_line_info.cc799 行定义.

800 {
801 vehicle_signal_.set_turn_signal(turn_signal);
802}

◆ speed_data()

const SpeedData & apollo::planning::ReferenceLineInfo::speed_data ( ) const

在文件 reference_line_info.cc517 行定义.

517{ return speed_data_; }

◆ st_graph_data()

const StGraphData & apollo::planning::ReferenceLineInfo::st_graph_data ( )
inline

在文件 reference_line_info.h235 行定义.

235{ return st_graph_data_; }

◆ TargetLaneId()

std::list< hdmap::Id > apollo::planning::ReferenceLineInfo::TargetLaneId ( ) const

在文件 reference_line_info.cc358 行定义.

358 {
359 std::list<hdmap::Id> lane_ids;
360 for (const auto& lane_seg : lanes_) {
361 lane_ids.push_back(lane_seg.lane->id());
362 }
363 return lane_ids;
364}

◆ trajectory()

const DiscretizedTrajectory & apollo::planning::ReferenceLineInfo::trajectory ( ) const

在文件 reference_line_info.cc486 行定义.

486 {
487 return discretized_trajectory_;
488}

◆ trajectory_type()

ADCTrajectory::TrajectoryType apollo::planning::ReferenceLineInfo::trajectory_type ( ) const
inline

在文件 reference_line_info.h229 行定义.

229 {
230 return trajectory_type_;
231 }

◆ vehicle_state()

const common::VehicleState & apollo::planning::ReferenceLineInfo::vehicle_state ( ) const
inline

在文件 reference_line_info.h70 行定义.

70{ return vehicle_state_; }

该类的文档由以下文件生成: