Apollo 11.0
自动驾驶开放平台
apollo::planning::RTKReplayPlanner类 参考

RTKReplayPlanner is a derived class of Planner. 更多...

#include <rtk_replay_planner.h>

类 apollo::planning::RTKReplayPlanner 继承关系图:
apollo::planning::RTKReplayPlanner 的协作图:

Public 成员函数

virtual ~RTKReplayPlanner ()=default
 Destructor
 
std::string Name () override
 
apollo::common::Status Init (const std::shared_ptr< DependencyInjector > &injector, const std::string &config_path="") override
 
void Stop () override
 
apollo::common::Status Plan (const common::TrajectoryPoint &planning_init_point, Frame *frame, ADCTrajectory *ptr_computed_trajectory) override
 Override function Plan in parent class Planner.
 
apollo::common::Status PlanOnReferenceLine (const common::TrajectoryPoint &planning_init_point, Frame *frame, ReferenceLineInfo *reference_line_info) override
 Override function Plan in parent class Planner.
 
void ReadTrajectoryFile (const std::string &filename)
 Read the recorded trajectory file.
 
- Public 成员函数 继承自 apollo::planning::PlannerWithReferenceLine
virtual ~PlannerWithReferenceLine ()=default
 Destructor
 
- Public 成员函数 继承自 apollo::planning::Planner
virtual ~Planner ()=default
 Destructor
 
virtual void Reset (Frame *frame)
 
template<typename T >
bool LoadConfig (const std::string &custom_config_path, T *config)
 

额外继承的成员函数

- Protected 属性 继承自 apollo::planning::Planner
std::shared_ptr< DependencyInjectorinjector_ = nullptr
 

详细描述

RTKReplayPlanner is a derived class of Planner.

It reads a recorded trajectory from a trajectory file and outputs proper segment of the trajectory according to vehicle position.

在文件 rtk_replay_planner.h44 行定义.

构造及析构函数说明

◆ ~RTKReplayPlanner()

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

Destructor

成员函数说明

◆ Init()

Status apollo::planning::RTKReplayPlanner::Init ( const std::shared_ptr< DependencyInjector > &  injector,
const std::string &  config_path = "" 
)
overridevirtual

重载 apollo::planning::Planner .

在文件 rtk_replay_planner.cc35 行定义.

37 {
38 Planner::Init(injector, config_path);
39 ReadTrajectoryFile(FLAGS_rtk_trajectory_filename);
40 return Status::OK();
41}
static Status OK()
generate a success status.
Definition status.h:60
virtual apollo::common::Status Init(const std::shared_ptr< DependencyInjector > &injector, const std::string &config_path="")
Definition planner.h:54
void ReadTrajectoryFile(const std::string &filename)
Read the recorded trajectory file.

◆ Name()

std::string apollo::planning::RTKReplayPlanner::Name ( )
inlineoverridevirtual

实现了 apollo::planning::Planner.

在文件 rtk_replay_planner.h51 行定义.

51{ return "RTK"; }

◆ Plan()

Status apollo::planning::RTKReplayPlanner::Plan ( const common::TrajectoryPoint planning_init_point,
Frame frame,
ADCTrajectory ptr_computed_trajectory 
)
overridevirtual

Override function Plan in parent class Planner.

参数
planning_init_pointThe trajectory point where planning starts.
frameCurrent planning frame.
返回
OK if planning succeeds; error otherwise.

实现了 apollo::planning::Planner.

在文件 rtk_replay_planner.cc43 行定义.

45 {
46 auto status = Status::OK();
47 bool has_plan = false;
48 auto it = std::find_if(
49 frame->mutable_reference_line_info()->begin(),
50 frame->mutable_reference_line_info()->end(),
51 [](const ReferenceLineInfo& ref) { return ref.IsChangeLanePath(); });
52 if (it != frame->mutable_reference_line_info()->end()) {
53 status = PlanOnReferenceLine(planning_start_point, frame, &(*it));
54 has_plan =
55 (it->IsDrivable() && it->IsChangeLanePath() &&
56 it->trajectory().GetSpatialLength() > FLAGS_change_lane_min_length);
57 if (!has_plan) {
58 AERROR << "Fail to plan for lane change.";
59 }
60 }
61
62 if (!has_plan || !FLAGS_prioritize_change_lane) {
63 for (auto& reference_line_info : *frame->mutable_reference_line_info()) {
64 if (reference_line_info.IsChangeLanePath()) {
65 continue;
66 }
67 status = PlanOnReferenceLine(planning_start_point, frame,
68 &reference_line_info);
69 if (status != Status::OK()) {
70 AERROR << "planner failed to make a driving plan for: "
71 << reference_line_info.Lanes().Id();
72 }
73 }
74 }
75 return status;
76}
apollo::common::Status PlanOnReferenceLine(const common::TrajectoryPoint &planning_init_point, Frame *frame, ReferenceLineInfo *reference_line_info) override
Override function Plan in parent class Planner.
#define AERROR
Definition log.h:44

◆ PlanOnReferenceLine()

Status apollo::planning::RTKReplayPlanner::PlanOnReferenceLine ( const common::TrajectoryPoint planning_init_point,
Frame frame,
ReferenceLineInfo reference_line_info 
)
overridevirtual

Override function Plan in parent class Planner.

参数
planning_init_pointThe trajectory point where planning starts.
frameCurrent planning frame.
reference_line_infoThe computed reference line.
返回
OK if planning succeeds; error otherwise.

重载 apollo::planning::PlannerWithReferenceLine .

在文件 rtk_replay_planner.cc78 行定义.

80 {
81 if (complete_rtk_trajectory_.empty() || complete_rtk_trajectory_.size() < 2) {
82 const std::string msg =
83 "RTKReplayPlanner doesn't have a recorded trajectory or "
84 "the recorded trajectory doesn't have enough valid trajectory "
85 "points.";
86 AERROR << msg;
87 return Status(ErrorCode::PLANNING_ERROR, msg);
88 }
89
90 std::uint32_t matched_index =
91 QueryPositionMatchedPoint(planning_init_point, complete_rtk_trajectory_);
92
93 std::uint32_t forward_buffer =
94 static_cast<std::uint32_t>(FLAGS_rtk_trajectory_forward);
95 // end_index is excluded.
96 std::uint32_t end_index = std::min<std::uint32_t>(
97 static_cast<std::uint32_t>(complete_rtk_trajectory_.size()),
98 matched_index + forward_buffer);
99
100 // auto* trajectory_points = trajectory_pb->mutable_trajectory_point();
101 std::vector<TrajectoryPoint> trajectory_points(
102 complete_rtk_trajectory_.begin() + matched_index,
103 complete_rtk_trajectory_.begin() + end_index);
104
105 // reset relative time
106 double zero_time = complete_rtk_trajectory_[matched_index].relative_time();
107 for (auto& trajectory_point : trajectory_points) {
108 trajectory_point.set_relative_time(trajectory_point.relative_time() -
109 zero_time);
110 }
111
112 // check if the trajectory has enough points;
113 // if not, append the last points multiple times and
114 // adjust their corresponding time stamps.
115 while (trajectory_points.size() <
116 static_cast<size_t>(FLAGS_rtk_trajectory_forward)) {
117 const auto& last_point = trajectory_points.rbegin();
118 auto new_point = last_point;
119 new_point->set_relative_time(new_point->relative_time() +
120 FLAGS_rtk_trajectory_resolution);
121 trajectory_points.push_back(*new_point);
122 }
123 reference_line_info->SetTrajectory(DiscretizedTrajectory(trajectory_points));
124 return Status::OK();
125}

◆ ReadTrajectoryFile()

void apollo::planning::RTKReplayPlanner::ReadTrajectoryFile ( const std::string &  filename)

Read the recorded trajectory file.

参数
filenameThe name of the trajectory file.

在文件 rtk_replay_planner.cc127 行定义.

127 {
128 if (!complete_rtk_trajectory_.empty()) {
129 complete_rtk_trajectory_.clear();
130 }
131
132 std::ifstream file_in(filename.c_str());
133 if (!file_in.is_open()) {
134 AERROR << "RTKReplayPlanner cannot open trajectory file: " << filename;
135 return;
136 }
137
138 std::string line;
139 // skip the header line.
140 getline(file_in, line);
141
142 while (true) {
143 getline(file_in, line);
144 if (line == "") {
145 break;
146 }
147
148 const std::vector<std::string> tokens =
149 absl::StrSplit(line, absl::ByAnyChar("\t "));
150 if (tokens.size() < 11) {
151 AERROR << "RTKReplayPlanner parse line failed; the data dimension does "
152 "not match.";
153 AERROR << line;
154 continue;
155 }
156
157 TrajectoryPoint point;
158 point.mutable_path_point()->set_x(std::stod(tokens[0]));
159 point.mutable_path_point()->set_y(std::stod(tokens[1]));
160 point.mutable_path_point()->set_z(std::stod(tokens[2]));
161
162 point.set_v(std::stod(tokens[3]));
163 point.set_a(std::stod(tokens[4]));
164
165 point.mutable_path_point()->set_kappa(std::stod(tokens[5]));
166 point.mutable_path_point()->set_dkappa(std::stod(tokens[6]));
167
168 point.set_relative_time(std::stod(tokens[7]));
169
170 point.mutable_path_point()->set_theta(std::stod(tokens[8]));
171
172 point.mutable_path_point()->set_s(std::stod(tokens[10]));
173 complete_rtk_trajectory_.push_back(std::move(point));
174 }
175
176 file_in.close();
177}

◆ Stop()

void apollo::planning::RTKReplayPlanner::Stop ( )
inlineoverridevirtual

实现了 apollo::planning::Planner.

在文件 rtk_replay_planner.h57 行定义.

57{}

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