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

Frame holds all data for one planning cycle. 更多...

#include <frame.h>

apollo::planning::Frame 的协作图:

Public 成员函数

 Frame (uint32_t sequence_num)
 
 Frame (uint32_t sequence_num, const LocalView &local_view, const common::TrajectoryPoint &planning_start_point, const common::VehicleState &vehicle_state, ReferenceLineProvider *reference_line_provider)
 
 Frame (uint32_t sequence_num, const LocalView &local_view, const common::TrajectoryPoint &planning_start_point, const common::VehicleState &vehicle_state)
 
virtual ~Frame ()=default
 
const common::TrajectoryPointPlanningStartPoint () const
 
common::Status Init (const common::VehicleStateProvider *vehicle_state_provider, const std::list< ReferenceLine > &reference_lines, const std::list< hdmap::RouteSegments > &segments, const std::vector< routing::LaneWaypoint > &future_route_waypoints, const EgoInfo *ego_info)
 
common::Status InitForOpenSpace (const common::VehicleStateProvider *vehicle_state_provider, const EgoInfo *ego_info)
 
uint32_t SequenceNum () const
 
std::string DebugString () const
 
const PublishableTrajectoryComputedTrajectory () const
 
void RecordInputDebug (planning_internal::Debug *debug)
 
const std::list< ReferenceLineInfo > & reference_line_info () const
 
std::list< ReferenceLineInfo > * mutable_reference_line_info ()
 
ObstacleFind (const std::string &id)
 
const ReferenceLineInfoFindDriveReferenceLineInfo ()
 
const ReferenceLineInfoFindTargetReferenceLineInfo ()
 
const ReferenceLineInfoFindFailedReferenceLineInfo ()
 
const ReferenceLineInfoDriveReferenceLineInfo () const
 
const std::vector< const Obstacle * > obstacles () const
 
const ObstacleCreateStopObstacle (ReferenceLineInfo *const reference_line_info, const std::string &obstacle_id, const double obstacle_s, double stop_wall_width=4.0)
 : create static virtual object with lane width, mainly used for virtual stop wall
 
const ObstacleCreateStopObstacle (const std::string &obstacle_id, const std::string &lane_id, const double lane_s)
 : create static virtual object with lane width, mainly used for virtual stop wall
 
const ObstacleCreateStaticObstacle (ReferenceLineInfo *const reference_line_info, const std::string &obstacle_id, const double obstacle_start_s, const double obstacle_end_s)
 : create static virtual object with lane width,
 
bool Rerouting (PlanningContext *planning_context)
 
const common::VehicleStatevehicle_state () const
 
void set_current_frame_planned_trajectory (ADCTrajectory current_frame_planned_trajectory)
 
const ADCTrajectorycurrent_frame_planned_trajectory () const
 
void set_current_frame_planned_path (DiscretizedPath current_frame_planned_path)
 
const DiscretizedPathcurrent_frame_planned_path () const
 
const bool is_near_destination () const
 
void UpdateReferenceLinePriority (const std::map< std::string, uint32_t > &id_to_priority)
 Adjust reference line priority according to actual road conditions @id_to_priority lane id and reference line priority mapping relationship
 
const LocalViewlocal_view () const
 
ThreadSafeIndexedObstaclesGetObstacleList ()
 
const OpenSpaceInfoopen_space_info () const
 
OpenSpaceInfomutable_open_space_info ()
 
perception::TrafficLight GetSignal (const std::string &traffic_light_id) const
 
const PadMessage::DrivingActionGetPadMsgDrivingAction () const
 

静态 Public 成员函数

static void AlignPredictionTime (const double planning_start_time, prediction::PredictionObstacles *prediction_obstacles)
 

详细描述

Frame holds all data for one planning cycle.

在文件 frame.h62 行定义.

构造及析构函数说明

◆ Frame() [1/3]

Frame::Frame ( uint32_t  sequence_num)
explicit

在文件 frame.cc58 行定义.

59 : sequence_num_(sequence_num),
60 monitor_logger_buffer_(common::monitor::MonitorMessageItem::PLANNING) {}

◆ Frame() [2/3]

Frame::Frame ( uint32_t  sequence_num,
const LocalView local_view,
const common::TrajectoryPoint planning_start_point,
const common::VehicleState vehicle_state,
ReferenceLineProvider reference_line_provider 
)

在文件 frame.cc62 行定义.

66 : sequence_num_(sequence_num),
67 local_view_(local_view),
68 planning_start_point_(planning_start_point),
69 vehicle_state_(vehicle_state),
70 reference_line_provider_(reference_line_provider),
71 monitor_logger_buffer_(common::monitor::MonitorMessageItem::PLANNING) {}
const common::VehicleState & vehicle_state() const
Definition frame.cc:83
LocalView contains all necessary data as planning input

◆ Frame() [3/3]

Frame::Frame ( uint32_t  sequence_num,
const LocalView local_view,
const common::TrajectoryPoint planning_start_point,
const common::VehicleState vehicle_state 
)

在文件 frame.cc73 行定义.

76 : Frame(sequence_num, local_view, planning_start_point, vehicle_state,
77 nullptr) {}

◆ ~Frame()

virtual apollo::planning::Frame::~Frame ( )
virtualdefault

成员函数说明

◆ AlignPredictionTime()

void Frame::AlignPredictionTime ( const double  planning_start_time,
prediction::PredictionObstacles prediction_obstacles 
)
static

在文件 frame.cc458 行定义.

459 {
460 if (!prediction_obstacles || !prediction_obstacles->has_header() ||
461 !prediction_obstacles->header().has_timestamp_sec()) {
462 return;
463 }
464 double prediction_header_time =
465 prediction_obstacles->header().timestamp_sec();
466 for (auto &obstacle : *prediction_obstacles->mutable_prediction_obstacle()) {
467 for (auto &trajectory : *obstacle.mutable_trajectory()) {
468 for (auto &point : *trajectory.mutable_trajectory_point()) {
469 point.set_relative_time(prediction_header_time + point.relative_time() -
470 planning_start_time);
471 }
472 if (!trajectory.trajectory_point().empty() &&
473 trajectory.trajectory_point().begin()->relative_time() < 0) {
474 auto it = trajectory.trajectory_point().begin();
475 while (it != trajectory.trajectory_point().end() &&
476 it->relative_time() < 0) {
477 ++it;
478 }
479 trajectory.mutable_trajectory_point()->erase(
480 trajectory.trajectory_point().begin(), it);
481 }
482 }
483 }
484}

◆ ComputedTrajectory()

const PublishableTrajectory & apollo::planning::Frame::ComputedTrajectory ( ) const

◆ CreateStaticObstacle()

const Obstacle * Frame::CreateStaticObstacle ( ReferenceLineInfo *const  reference_line_info,
const std::string &  obstacle_id,
const double  obstacle_start_s,
const double  obstacle_end_s 
)

: create static virtual object with lane width,

在文件 frame.cc274 行定义.

277 {
278 if (reference_line_info == nullptr) {
279 AERROR << "reference_line_info nullptr";
280 return nullptr;
281 }
282
283 const auto &reference_line = reference_line_info->reference_line();
284
285 // start_xy
286 common::SLPoint sl_point;
287 sl_point.set_s(obstacle_start_s);
288 sl_point.set_l(0.0);
289 common::math::Vec2d obstacle_start_xy;
290 if (!reference_line.SLToXY(sl_point, &obstacle_start_xy)) {
291 AERROR << "Failed to get start_xy from sl: " << sl_point.DebugString();
292 return nullptr;
293 }
294
295 // end_xy
296 sl_point.set_s(obstacle_end_s);
297 sl_point.set_l(0.0);
298 common::math::Vec2d obstacle_end_xy;
299 if (!reference_line.SLToXY(sl_point, &obstacle_end_xy)) {
300 AERROR << "Failed to get end_xy from sl: " << sl_point.DebugString();
301 return nullptr;
302 }
303
304 double left_lane_width = 0.0;
305 double right_lane_width = 0.0;
306 if (!reference_line.GetLaneWidth(obstacle_start_s, &left_lane_width,
307 &right_lane_width)) {
308 AERROR << "Failed to get lane width at s[" << obstacle_start_s << "]";
309 return nullptr;
310 }
311
312 common::math::Box2d obstacle_box{
313 common::math::LineSegment2d(obstacle_start_xy, obstacle_end_xy),
314 left_lane_width + right_lane_width};
315
316 return CreateStaticVirtualObstacle(obstacle_id, obstacle_box);
317}
const std::list< ReferenceLineInfo > & reference_line_info() const
Definition frame.cc:123
#define AERROR
Definition log.h:44

◆ CreateStopObstacle() [1/2]

const Obstacle * Frame::CreateStopObstacle ( const std::string &  obstacle_id,
const std::string &  lane_id,
const double  lane_s 
)

: create static virtual object with lane width, mainly used for virtual stop wall

在文件 frame.cc237 行定义.

239 {
240 if (!hdmap_) {
241 AERROR << "Invalid HD Map.";
242 return nullptr;
243 }
244 hdmap::LaneInfoConstPtr lane = nullptr;
245 if (nullptr == reference_line_provider_) {
246 lane = hdmap_->GetLaneById(hdmap::MakeMapId(lane_id));
247 } else {
248 lane = reference_line_provider_->GetLaneById(hdmap::MakeMapId(lane_id));
249 }
250
251 if (!lane) {
252 AERROR << "Failed to find lane[" << lane_id << "]";
253 return nullptr;
254 }
255
256 double dest_lane_s = std::max(0.0, lane_s);
257 auto dest_point = lane->GetSmoothPoint(dest_lane_s);
258
259 double lane_left_width = 0.0;
260 double lane_right_width = 0.0;
261 lane->GetWidth(dest_lane_s, &lane_left_width, &lane_right_width);
262
263 Box2d stop_wall_box{{dest_point.x(), dest_point.y()},
264 lane->Heading(dest_lane_s),
265 FLAGS_virtual_stop_wall_length,
266 lane_left_width + lane_right_width};
267
268 return CreateStaticVirtualObstacle(obstacle_id, stop_wall_box);
269}
LaneInfoConstPtr GetLaneById(const Id &id) const
Definition hdmap.cc:34
hdmap::LaneInfoConstPtr GetLaneById(const hdmap::Id &id) const
apollo::hdmap::Id MakeMapId(const std::string &id)
create a Map ID given a string.
Definition hdmap_util.h:85
std::shared_ptr< const LaneInfo > LaneInfoConstPtr

◆ CreateStopObstacle() [2/2]

const Obstacle * Frame::CreateStopObstacle ( ReferenceLineInfo *const  reference_line_info,
const std::string &  obstacle_id,
const double  obstacle_s,
double  stop_wall_width = 4.0 
)

: create static virtual object with lane width, mainly used for virtual stop wall

在文件 frame.cc214 行定义.

217 {
218 if (reference_line_info == nullptr) {
219 AERROR << "reference_line_info nullptr";
220 return nullptr;
221 }
222
223 const auto &reference_line = reference_line_info->reference_line();
224 const double box_center_s = obstacle_s + FLAGS_virtual_stop_wall_length / 2.0;
225 auto box_center = reference_line.GetReferencePoint(box_center_s);
226 double heading = reference_line.GetReferencePoint(obstacle_s).heading();
227 Box2d stop_wall_box{box_center, heading, FLAGS_virtual_stop_wall_length,
228 stop_wall_width};
229
230 return CreateStaticVirtualObstacle(obstacle_id, stop_wall_box);
231}

◆ current_frame_planned_path()

const DiscretizedPath & apollo::planning::Frame::current_frame_planned_path ( ) const
inline

在文件 frame.h150 行定义.

150 {
151 return current_frame_planned_path_;
152 }

◆ current_frame_planned_trajectory()

const ADCTrajectory & apollo::planning::Frame::current_frame_planned_trajectory ( ) const
inline

在文件 frame.h141 行定义.

141 {
142 return current_frame_planned_trajectory_;
143 }

◆ DebugString()

std::string Frame::DebugString ( ) const

在文件 frame.cc425 行定义.

425 {
426 return absl::StrCat("Frame: ", sequence_num_);
427}

◆ DriveReferenceLineInfo()

const ReferenceLineInfo * Frame::DriveReferenceLineInfo ( ) const

在文件 frame.cc573 行定义.

573 {
574 return drive_reference_line_info_;
575}

◆ Find()

Obstacle * Frame::Find ( const std::string &  id)

在文件 frame.cc486 行定义.

486{ return obstacles_.Find(id); }

◆ FindDriveReferenceLineInfo()

const ReferenceLineInfo * Frame::FindDriveReferenceLineInfo ( )

在文件 frame.cc538 行定义.

538 {
539 double min_cost = std::numeric_limits<double>::infinity();
540 drive_reference_line_info_ = nullptr;
541 for (const auto &reference_line_info : reference_line_info_) {
542 if (reference_line_info.IsDrivable() &&
543 reference_line_info.Cost() < min_cost) {
544 drive_reference_line_info_ = &reference_line_info;
545 min_cost = reference_line_info.Cost();
546 }
547 }
548 return drive_reference_line_info_;
549}

◆ FindFailedReferenceLineInfo()

const ReferenceLineInfo * Frame::FindFailedReferenceLineInfo ( )

在文件 frame.cc562 行定义.

562 {
563 for (const auto &reference_line_info : reference_line_info_) {
564 // Find the unsuccessful lane-change path
565 if (!reference_line_info.IsDrivable() &&
566 reference_line_info.IsChangeLanePath()) {
567 return &reference_line_info;
568 }
569 }
570 return nullptr;
571}

◆ FindTargetReferenceLineInfo()

const ReferenceLineInfo * Frame::FindTargetReferenceLineInfo ( )

在文件 frame.cc551 行定义.

551 {
552 const ReferenceLineInfo *target_reference_line_info = nullptr;
553 for (const auto &reference_line_info : reference_line_info_) {
554 if (reference_line_info.IsChangeLanePath()) {
555 return &reference_line_info;
556 }
557 target_reference_line_info = &reference_line_info;
558 }
559 return target_reference_line_info;
560}

◆ GetObstacleList()

ThreadSafeIndexedObstacles * apollo::planning::Frame::GetObstacleList ( )
inline

在文件 frame.h165 行定义.

165{ return &obstacles_; }

◆ GetPadMsgDrivingAction()

const PadMessage::DrivingAction & apollo::planning::Frame::GetPadMsgDrivingAction ( ) const
inline

在文件 frame.h173 行定义.

173 {
174 return pad_msg_driving_action_;
175 }

◆ GetSignal()

perception::TrafficLight Frame::GetSignal ( const std::string &  traffic_light_id) const

在文件 frame.cc511 行定义.

512 {
513 const auto *result =
514 apollo::common::util::FindPtrOrNull(traffic_lights_, traffic_light_id);
515 if (result == nullptr) {
516 perception::TrafficLight traffic_light;
517 traffic_light.set_id(traffic_light_id);
518 traffic_light.set_color(perception::TrafficLight::UNKNOWN);
519 traffic_light.set_confidence(0.0);
520 traffic_light.set_tracking_time(0.0);
521 return traffic_light;
522 }
523 return *result;
524}

◆ Init()

Status Frame::Init ( const common::VehicleStateProvider vehicle_state_provider,
const std::list< ReferenceLine > &  reference_lines,
const std::list< hdmap::RouteSegments > &  segments,
const std::vector< routing::LaneWaypoint > &  future_route_waypoints,
const EgoInfo ego_info 
)

在文件 frame.cc334 行定义.

339 {
340 // TODO(QiL): refactor this to avoid redundant nullptr checks in scenarios.
341 auto status = InitFrameData(vehicle_state_provider, ego_info);
342 if (!status.ok()) {
343 AERROR << "failed to init frame:" << status.ToString();
344 return status;
345 }
346 if (!CreateReferenceLineInfo(reference_lines, segments)) {
347 const std::string msg = "Failed to init reference line info.";
348 AERROR << msg;
349 return Status(ErrorCode::PLANNING_ERROR, msg);
350 }
351 future_route_waypoints_ = future_route_waypoints;
352 for (auto &reference_line_info : reference_line_info_) {
353 reference_line_info.PrintReferenceSegmentDebugString();
354 }
355 return Status::OK();
356}
static Status OK()
generate a success status.
Definition status.h:60

◆ InitForOpenSpace()

Status Frame::InitForOpenSpace ( const common::VehicleStateProvider vehicle_state_provider,
const EgoInfo ego_info 
)

在文件 frame.cc358 行定义.

360 {
361 return InitFrameData(vehicle_state_provider, ego_info);
362}

◆ is_near_destination()

const bool apollo::planning::Frame::is_near_destination ( ) const
inline

在文件 frame.h154 行定义.

154{ return is_near_destination_; }

◆ local_view()

const LocalView & apollo::planning::Frame::local_view ( ) const
inline

在文件 frame.h163 行定义.

163{ return local_view_; }

◆ mutable_open_space_info()

OpenSpaceInfo * apollo::planning::Frame::mutable_open_space_info ( )
inline

在文件 frame.h169 行定义.

169{ return &open_space_info_; }

◆ mutable_reference_line_info()

std::list< ReferenceLineInfo > * Frame::mutable_reference_line_info ( )

在文件 frame.cc127 行定义.

127 {
128 return &reference_line_info_;
129}

◆ obstacles()

const std::vector< const Obstacle * > Frame::obstacles ( ) const

在文件 frame.cc577 行定义.

577 {
578 return obstacles_.Items();
579}
std::vector< const T * > Items() const

◆ open_space_info()

const OpenSpaceInfo & apollo::planning::Frame::open_space_info ( ) const
inline

在文件 frame.h167 行定义.

167{ return open_space_info_; }

◆ PlanningStartPoint()

const common::TrajectoryPoint & Frame::PlanningStartPoint ( ) const

在文件 frame.cc79 行定义.

79 {
80 return planning_start_point_;
81}

◆ RecordInputDebug()

void Frame::RecordInputDebug ( planning_internal::Debug debug)

在文件 frame.cc429 行定义.

429 {
430 if (!debug) {
431 ADEBUG << "Skip record input into debug";
432 return;
433 }
434 auto *planning_debug_data = debug->mutable_planning_data();
435 auto *adc_position = planning_debug_data->mutable_adc_position();
436 adc_position->CopyFrom(*local_view_.localization_estimate);
437
438 auto debug_chassis = planning_debug_data->mutable_chassis();
439 debug_chassis->CopyFrom(*local_view_.chassis);
440
441 if (!FLAGS_use_navigation_mode) {
442 auto debug_routing = planning_debug_data->mutable_routing();
443 debug_routing->CopyFrom(
444 local_view_.planning_command->lane_follow_command());
445 }
446
447 planning_debug_data->mutable_prediction_header()->CopyFrom(
448 local_view_.prediction_obstacles->header());
449 /*
450 auto relative_map = AdapterManager::GetRelativeMap();
451 if (!relative_map->Empty()) {
452 planning_debug_data->mutable_relative_map()->mutable_header()->CopyFrom(
453 relative_map->GetLatestObserved().header());
454 }
455 */
456}
#define ADEBUG
Definition log.h:41
std::shared_ptr< localization::LocalizationEstimate > localization_estimate
Definition local_view.h:43
std::shared_ptr< PlanningCommand > planning_command
Definition local_view.h:48
std::shared_ptr< prediction::PredictionObstacles > prediction_obstacles
Definition local_view.h:41
std::shared_ptr< canbus::Chassis > chassis
Definition local_view.h:42

◆ reference_line_info()

const std::list< ReferenceLineInfo > & Frame::reference_line_info ( ) const

在文件 frame.cc123 行定义.

123 {
124 return reference_line_info_;
125}

◆ Rerouting()

bool Frame::Rerouting ( PlanningContext planning_context)

在文件 frame.cc87 行定义.

87 {
88 if (FLAGS_use_navigation_mode) {
89 AERROR << "Rerouting not supported in navigation mode";
90 return false;
91 }
92 if (local_view_.planning_command == nullptr) {
93 AERROR << "No previous routing available";
94 return false;
95 }
96 if (!hdmap_) {
97 AERROR << "Invalid HD Map.";
98 return false;
99 }
100 auto *rerouting =
101 planning_context->mutable_planning_status()->mutable_rerouting();
102 rerouting->set_need_rerouting(true);
103 auto *lane_follow_command = rerouting->mutable_lane_follow_command();
104 if (future_route_waypoints_.size() < 1) {
105 AERROR << "Failed to find future waypoints";
106 return false;
107 }
108 for (size_t i = 0; i < future_route_waypoints_.size() - 1; i++) {
109 auto waypoint = lane_follow_command->add_way_point();
110 waypoint->set_x(future_route_waypoints_[i].pose().x());
111 waypoint->set_y(future_route_waypoints_[i].pose().y());
112 waypoint->set_heading(future_route_waypoints_[i].heading());
113 }
114 auto *end_pose = lane_follow_command->mutable_end_pose();
115 end_pose->set_x(future_route_waypoints_.back().pose().x());
116 end_pose->set_y(future_route_waypoints_.back().pose().y());
117 end_pose->set_heading(future_route_waypoints_.back().heading());
118
119 monitor_logger_buffer_.INFO("Planning send Rerouting request");
120 return true;
121}

◆ SequenceNum()

uint32_t Frame::SequenceNum ( ) const

在文件 frame.cc423 行定义.

423{ return sequence_num_; }

◆ set_current_frame_planned_path()

void apollo::planning::Frame::set_current_frame_planned_path ( DiscretizedPath  current_frame_planned_path)
inline

在文件 frame.h145 行定义.

146 {
147 current_frame_planned_path_ = std::move(current_frame_planned_path);
148 }
const DiscretizedPath & current_frame_planned_path() const
Definition frame.h:150

◆ set_current_frame_planned_trajectory()

void apollo::planning::Frame::set_current_frame_planned_trajectory ( ADCTrajectory  current_frame_planned_trajectory)
inline

在文件 frame.h135 行定义.

136 {
137 current_frame_planned_trajectory_ =
139 }
const ADCTrajectory & current_frame_planned_trajectory() const
Definition frame.h:141

◆ UpdateReferenceLinePriority()

void Frame::UpdateReferenceLinePriority ( const std::map< std::string, uint32_t > &  id_to_priority)

Adjust reference line priority according to actual road conditions @id_to_priority lane id and reference line priority mapping relationship

在文件 frame.cc131 行定义.

132 {
133 for (const auto &pair : id_to_priority) {
134 const auto id = pair.first;
135 const auto priority = pair.second;
136 auto ref_line_info_itr =
137 std::find_if(reference_line_info_.begin(), reference_line_info_.end(),
138 [&id](const ReferenceLineInfo &ref_line_info) {
139 return ref_line_info.Lanes().Id() == id;
140 });
141 if (ref_line_info_itr != reference_line_info_.end()) {
142 ref_line_info_itr->SetPriority(priority);
143 }
144 }
145}

◆ vehicle_state()

const common::VehicleState & Frame::vehicle_state ( ) const

在文件 frame.cc83 行定义.

83 {
84 return vehicle_state_;
85}

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