Apollo 10.0
自动驾驶开放平台
sim_perfect_control.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
18
19#include "cyber/common/file.h"
20#include "cyber/time/clock.h"
27
28namespace apollo {
29namespace dreamview {
30
39using apollo::common::util::FillHeader;
46using Json = nlohmann::json;
47
48namespace {
49
50void TransformToVRF(const Point3D &point_mrf, const Quaternion &orientation,
51 Point3D *point_vrf) {
52 Eigen::Vector3d v_mrf(point_mrf.x(), point_mrf.y(), point_mrf.z());
53 auto v_vrf = InverseQuaternionRotate(orientation, v_mrf);
54 point_vrf->set_x(v_vrf.x());
55 point_vrf->set_y(v_vrf.y());
56 point_vrf->set_z(v_vrf.z());
57}
58
59bool IsSameHeader(const Header &lhs, const Header &rhs) {
60 return lhs.sequence_num() == rhs.sequence_num() &&
61 lhs.timestamp_sec() == rhs.timestamp_sec();
62}
63
64} // namespace
65
68 map_service_(map_service),
69 node_(cyber::CreateNode("sim_perfect_control")),
70 current_trajectory_(std::make_shared<ADCTrajectory>()) {
71 InitTimerAndIO();
72}
73
74void SimPerfectControl::InitTimerAndIO() {
75 localization_reader_ =
76 node_->CreateReader<LocalizationEstimate>(FLAGS_localization_topic);
77 planning_reader_ = node_->CreateReader<ADCTrajectory>(
78 FLAGS_planning_trajectory_topic,
79 [this](const std::shared_ptr<ADCTrajectory> &trajectory) {
80 this->OnPlanning(trajectory);
81 });
82 planning_command_reader_ = node_->CreateReader<PlanningCommand>(
83 FLAGS_planning_command,
84 [this](const std::shared_ptr<PlanningCommand> &planning_command) {
85 this->OnPlanningCommand(planning_command);
86 });
87 navigation_reader_ = node_->CreateReader<NavigationInfo>(
88 FLAGS_navigation_topic,
89 [this](const std::shared_ptr<NavigationInfo> &navigation_info) {
90 this->OnReceiveNavigationInfo(navigation_info);
91 });
92 prediction_reader_ = node_->CreateReader<PredictionObstacles>(
93 FLAGS_prediction_topic,
94 [this](const std::shared_ptr<PredictionObstacles> &obstacles) {
95 this->OnPredictionObstacles(obstacles);
96 });
97
98 localization_writer_ =
99 node_->CreateWriter<LocalizationEstimate>(FLAGS_localization_topic);
100 chassis_writer_ = node_->CreateWriter<Chassis>(FLAGS_chassis_topic);
101 prediction_writer_ =
102 node_->CreateWriter<PredictionObstacles>(FLAGS_prediction_topic);
103
104 // Start timer to publish localization and chassis messages.
105 sim_control_timer_.reset(new cyber::Timer(
106 kSimControlIntervalMs, [this]() { this->RunOnce(); }, false));
107 sim_prediction_timer_.reset(new cyber::Timer(
108 kSimPredictionIntervalMs, [this]() { this->PublishDummyPrediction(); },
109 false));
110}
111
112void SimPerfectControl::Init(bool set_start_point,
113 nlohmann::json start_point_attr,
114 bool use_start_point_position) {
115 if (set_start_point && !FLAGS_use_navigation_mode) {
116 InitStartPoint(start_point_attr["start_velocity"],
117 start_point_attr["start_acceleration"]);
118 }
119}
120
121void SimPerfectControl::InitStartPoint(double x, double y,
122 double start_velocity,
123 double start_acceleration) {
124 TrajectoryPoint point;
125 // Use the scenario start point as start point,
126 start_point_from_localization_ = false;
127 point.mutable_path_point()->set_x(x);
128 point.mutable_path_point()->set_y(y);
129 // z use default 0
130 point.mutable_path_point()->set_z(0);
131 double theta = 0.0;
132 double s = 0.0;
133 map_service_->GetPoseWithRegardToLane(x, y, &theta, &s);
134 point.mutable_path_point()->set_theta(theta);
135 point.set_v(start_velocity);
136 point.set_a(start_acceleration);
137 SetStartPoint(point);
138}
139
140void SimPerfectControl::ReSetPoinstion(double x, double y, double heading) {
141 std::lock_guard<std::mutex> lock(mutex_);
142 TrajectoryPoint point;
143 point.mutable_path_point()->set_x(x);
144 point.mutable_path_point()->set_y(y);
145 // z use default 0
146 point.mutable_path_point()->set_z(0);
147 point.mutable_path_point()->set_theta(heading);
148 SetStartPoint(point);
149 InternalReset();
150}
151
152void SimPerfectControl::InitStartPoint(double start_velocity,
153 double start_acceleration) {
154 TrajectoryPoint point;
155 // Use the latest localization position as start point,
156 // fall back to a dummy point from map
157 localization_reader_->Observe();
158 start_point_from_localization_ = false;
159 if (!localization_reader_->Empty()) {
160 const auto &localization = localization_reader_->GetLatestObserved();
161 const auto &pose = localization->pose();
162 if (map_service_->PointIsValid(pose.position().x(), pose.position().y())) {
163 point.mutable_path_point()->set_x(pose.position().x());
164 point.mutable_path_point()->set_y(pose.position().y());
165 point.mutable_path_point()->set_z(pose.position().z());
166 point.mutable_path_point()->set_theta(pose.heading());
167 point.set_v(
168 std::hypot(pose.linear_velocity().x(), pose.linear_velocity().y()));
169 // Calculates the dot product of acceleration and velocity. The sign
170 // of this projection indicates whether this is acceleration or
171 // deceleration.
172 double projection =
173 pose.linear_acceleration().x() * pose.linear_velocity().x() +
174 pose.linear_acceleration().y() * pose.linear_velocity().y();
175
176 // Calculates the magnitude of the acceleration. Negate the value if
177 // it is indeed a deceleration.
178 double magnitude = std::hypot(pose.linear_acceleration().x(),
179 pose.linear_acceleration().y());
180 point.set_a(std::signbit(projection) ? -magnitude : magnitude);
181 start_point_from_localization_ = true;
182 }
183 }
184 if (!start_point_from_localization_) {
185 apollo::common::PointENU start_point;
186 if (!map_service_->GetStartPoint(&start_point)) {
187 AWARN << "Failed to get a dummy start point from map!";
188 return;
189 }
190 point.mutable_path_point()->set_x(start_point.x());
191 point.mutable_path_point()->set_y(start_point.y());
192 point.mutable_path_point()->set_z(start_point.z());
193 double theta = 0.0;
194 double s = 0.0;
195 map_service_->GetPoseWithRegardToLane(start_point.x(), start_point.y(),
196 &theta, &s);
197 point.mutable_path_point()->set_theta(theta);
198 point.set_v(start_velocity);
199 point.set_a(start_acceleration);
200 }
201 SetStartPoint(point);
202}
203
204void SimPerfectControl::SetStartPoint(const TrajectoryPoint &start_point) {
205 next_point_ = start_point;
206 prev_point_index_ = next_point_index_ = 0;
207 received_planning_ = false;
208}
209
211 std::lock_guard<std::mutex> lock(mutex_);
212 InternalReset();
213}
214
216 if (enabled_) {
217 {
218 std::lock_guard<std::mutex> lock(timer_mutex_);
219 sim_control_timer_->Stop();
220 sim_prediction_timer_->Stop();
221 }
222 enabled_ = false;
223 }
224}
225
226void SimPerfectControl::InternalReset() {
227 current_routing_header_.Clear();
228 send_dummy_prediction_ = true;
229 ClearPlanning();
230}
231
232void SimPerfectControl::ClearPlanning() {
233 current_trajectory_->Clear();
234 received_planning_ = false;
235}
236
237void SimPerfectControl::OnReceiveNavigationInfo(
238 const std::shared_ptr<NavigationInfo> &navigation_info) {
239 std::lock_guard<std::mutex> lock(mutex_);
240 if (!enabled_) {
241 return;
242 }
243 if (navigation_info->navigation_path_size() > 0) {
244 const auto &path = navigation_info->navigation_path(0).path();
245 if (path.path_point_size() > 0) {
246 adc_position_ = path.path_point(0);
247 }
248 }
249}
250
251void SimPerfectControl::OnPlanningCommand(
252 const std::shared_ptr<PlanningCommand> &planning_command) {
253 std::lock_guard<std::mutex> lock(mutex_);
254 if (!enabled_) {
255 return;
256 }
257 // Avoid not sending prediction messages to planning after playing packets
258 // with obstacles
259 send_dummy_prediction_ = true;
260 current_routing_header_ = planning_command->header();
261 AINFO << "planning_command: " << planning_command->DebugString();
262
263 // if (planning_command->lane_follow_command()
264 // .routing_request()
265 // .is_start_pose_set()) {
266 // auto lane_follow_command = planning_command->mutable_lane_follow_command();
267 // const auto &start_pose =
268 // lane_follow_command->routing_request().waypoint(0).pose();
269 // ClearPlanning();
270 // TrajectoryPoint point;
271 // point.mutable_path_point()->set_x(start_pose.x());
272 // point.mutable_path_point()->set_y(start_pose.y());
273 // point.set_a(next_point_.has_a() ? next_point_.a() : 0.0);
274 // point.set_v(next_point_.has_v() ? next_point_.v() : 0.0);
275 // double theta = 0.0;
276 // double s = 0.0;
277
278 // // Find the lane nearest to the start pose and get its heading as theta.
279 // map_service_->GetPoseWithRegardToLane(start_pose.x(), start_pose.y(),
280 // &theta, &s);
281
282 // point.mutable_path_point()->set_theta(theta);
283 // SetStartPoint(point);
284 // }
285 return;
286}
287
288void SimPerfectControl::OnPredictionObstacles(
289 const std::shared_ptr<PredictionObstacles> &obstacles) {
290 std::lock_guard<std::mutex> lock(mutex_);
291
292 if (!enabled_) {
293 return;
294 }
295
296 send_dummy_prediction_ = obstacles->header().module_name() == "SimPrediction";
297}
298
300 std::lock_guard<std::mutex> lock(mutex_);
301
302 if (!enabled_) {
303 // When there is no localization yet, Init(true) will use a
304 // dummy point from the current map as an arbitrary start.
305 // When localization is already available, we do not need to
306 // reset/override the start point.
307 localization_reader_->Observe();
308 Json start_point_attr({});
309 start_point_attr["start_velocity"] =
310 next_point_.has_v() ? next_point_.v() : 0.0;
311 start_point_attr["start_acceleration"] =
312 next_point_.has_a() ? next_point_.a() : 0.0;
313 Init(true, start_point_attr);
314 InternalReset();
315 {
316 std::lock_guard<std::mutex> lock(timer_mutex_);
317 sim_control_timer_->Start();
318 sim_prediction_timer_->Start();
319 }
320 enabled_ = true;
321 }
322}
323
324void SimPerfectControl::Start(double x, double y, double v, double a) {
325 std::lock_guard<std::mutex> lock(mutex_);
326 if (!enabled_) {
327 // Do not use localization info. use scenario start point to init start
328 // point.
329 InitStartPoint(x, y, v, a);
330 InternalReset();
331 sim_control_timer_->Start();
332 sim_prediction_timer_->Start();
333 enabled_ = true;
334 }
335}
336
337void SimPerfectControl::OnPlanning(
338 const std::shared_ptr<ADCTrajectory> &trajectory) {
339 std::lock_guard<std::mutex> lock(mutex_);
340
341 if (!enabled_) {
342 return;
343 }
344
345 // Reset current trajectory and the indices upon receiving a new trajectory.
346 // The routing SimPerfectControl owns must match with the one Planning has.
347 if (IsSameHeader(trajectory->routing_header(), current_routing_header_)) {
348 current_trajectory_ = trajectory;
349 prev_point_index_ = 0;
350 next_point_index_ = 0;
351 received_planning_ = true;
352 } else {
353 ClearPlanning();
354 }
355}
356
357void SimPerfectControl::Freeze() {
358 next_point_.set_v(0.0);
359 next_point_.set_a(0.0);
360 prev_point_ = next_point_;
361}
362
364 std::lock_guard<std::mutex> lock(mutex_);
365
366 TrajectoryPoint trajectory_point;
367 Chassis::GearPosition gear_position;
368 if (!PerfectControlModel(&trajectory_point, &gear_position)) {
369 AERROR << "Failed to calculate next point with perfect control model";
370 return;
371 }
372
373 PublishChassis(trajectory_point.v(), gear_position);
374 PublishLocalization(trajectory_point);
375}
376
377bool SimPerfectControl::PerfectControlModel(
378 TrajectoryPoint *point, Chassis::GearPosition *gear_position) {
379 // Result of the interpolation.
380 auto current_time = Clock::NowInSeconds();
381 const auto &trajectory = current_trajectory_->trajectory_point();
382 *gear_position = current_trajectory_->gear();
383
384 if (!received_planning_) {
385 prev_point_ = next_point_;
386 } else {
387 if (current_trajectory_->estop().is_estop()) {
388 // Freeze the car when there's an estop or the current trajectory has
389 // been exhausted.
390 Freeze();
391 } else if (next_point_index_ >= trajectory.size()) {
392 prev_point_ = next_point_;
393 } else {
394 // Determine the status of the car based on received planning message.
395 while (next_point_index_ < trajectory.size() &&
396 current_time > trajectory.Get(next_point_index_).relative_time() +
397 current_trajectory_->header().timestamp_sec()) {
398 ++next_point_index_;
399 }
400
401 if (next_point_index_ >= trajectory.size()) {
402 next_point_index_ = trajectory.size() - 1;
403 }
404
405 if (next_point_index_ == 0) {
406 AERROR << "First trajectory point is a future point!";
407 return false;
408 }
409
410 prev_point_index_ = next_point_index_ - 1;
411
412 next_point_ = trajectory.Get(next_point_index_);
413 prev_point_ = trajectory.Get(prev_point_index_);
414 }
415 }
416
417 if (current_time > next_point_.relative_time() +
418 current_trajectory_->header().timestamp_sec()) {
419 // Don't try to extrapolate if relative_time passes last point
420 *point = next_point_;
421 } else {
423 prev_point_, next_point_,
424 current_time - current_trajectory_->header().timestamp_sec());
425 }
426 return true;
427}
428
429void SimPerfectControl::PublishChassis(double cur_speed,
430 Chassis::GearPosition gear_position) {
431 auto chassis = std::make_shared<Chassis>();
432 FillHeader("SimPerfectControl", chassis.get());
433
434 chassis->set_engine_started(true);
435 chassis->set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
436 chassis->set_gear_location(gear_position);
437
438 chassis->set_speed_mps(static_cast<float>(cur_speed));
439 if (gear_position == canbus::Chassis::GEAR_REVERSE) {
440 chassis->set_speed_mps(-chassis->speed_mps());
441 }
442
443 chassis->set_throttle_percentage(0.0);
444 chassis->set_brake_percentage(0.0);
445
446 chassis_writer_->Write(chassis);
447}
448
449void SimPerfectControl::PublishLocalization(const TrajectoryPoint &point) {
450 auto localization = std::make_shared<LocalizationEstimate>();
451 FillHeader("SimPerfectControl", localization.get());
452 auto *pose = localization->mutable_pose();
453 auto prev = prev_point_.path_point();
454 auto next = next_point_.path_point();
455
456 // Set position
457 pose->mutable_position()->set_x(point.path_point().x());
458 pose->mutable_position()->set_y(point.path_point().y());
459 pose->mutable_position()->set_z(point.path_point().z());
460 // Set orientation and heading
461 double cur_theta = point.path_point().theta();
462
463 if (FLAGS_use_navigation_mode) {
464 double flu_x = point.path_point().x();
465 double flu_y = point.path_point().y();
466
467 Eigen::Vector2d enu_coordinate =
468 common::math::RotateVector2d({flu_x, flu_y}, cur_theta);
469
470 enu_coordinate.x() += adc_position_.x();
471 enu_coordinate.y() += adc_position_.y();
472 pose->mutable_position()->set_x(enu_coordinate.x());
473 pose->mutable_position()->set_y(enu_coordinate.y());
474 }
475
476 Eigen::Quaternion<double> cur_orientation =
477 HeadingToQuaternion<double>(cur_theta);
478 pose->mutable_orientation()->set_qw(cur_orientation.w());
479 pose->mutable_orientation()->set_qx(cur_orientation.x());
480 pose->mutable_orientation()->set_qy(cur_orientation.y());
481 pose->mutable_orientation()->set_qz(cur_orientation.z());
482 pose->set_heading(cur_theta);
483
484 // Set linear_velocity
485 pose->mutable_linear_velocity()->set_x(std::cos(cur_theta) * point.v());
486 pose->mutable_linear_velocity()->set_y(std::sin(cur_theta) * point.v());
487 pose->mutable_linear_velocity()->set_z(0);
488
489 // Set angular_velocity in both map reference frame and vehicle reference
490 // frame
491 pose->mutable_angular_velocity()->set_x(0);
492 pose->mutable_angular_velocity()->set_y(0);
493 pose->mutable_angular_velocity()->set_z(point.v() *
494 point.path_point().kappa());
495
496 TransformToVRF(pose->angular_velocity(), pose->orientation(),
497 pose->mutable_angular_velocity_vrf());
498
499 // Set linear_acceleration in both map reference frame and vehicle reference
500 // frame
501 auto *linear_acceleration = pose->mutable_linear_acceleration();
502 linear_acceleration->set_x(std::cos(cur_theta) * point.a());
503 linear_acceleration->set_y(std::sin(cur_theta) * point.a());
504 linear_acceleration->set_z(0);
505
506 TransformToVRF(pose->linear_acceleration(), pose->orientation(),
507 pose->mutable_linear_acceleration_vrf());
508 localization_writer_->Write(localization);
509
510 adc_position_.set_x(pose->position().x());
511 adc_position_.set_y(pose->position().y());
512 adc_position_.set_z(pose->position().z());
513}
514
515void SimPerfectControl::PublishDummyPrediction() {
516 auto prediction = std::make_shared<PredictionObstacles>();
517 {
518 std::lock_guard<std::mutex> lock(mutex_);
519 if (!send_dummy_prediction_) {
520 return;
521 }
522 FillHeader("SimPrediction", prediction.get());
523 }
524 prediction_writer_->Write(prediction);
525}
526
527} // namespace dreamview
528} // namespace apollo
a singleton clock that can be used to get the current timestamp.
Definition clock.h:39
static double NowInSeconds()
gets the current time in second.
Definition clock.cc:56
bool PointIsValid(const double x, const double y) const
bool GetStartPoint(apollo::common::PointENU *start_point) const
bool GetPoseWithRegardToLane(const double x, const double y, double *theta, double *s) const
Interface of simulated control algorithm
void TransformToVRF(const apollo::common::Point3D &point_mrf, const apollo::common::Quaternion &orientation, apollo::common::Point3D *point_vrf)
SimPerfectControl(const MapService *map_service)
Constructor of SimPerfectControl.
void Reset() override
Resets the internal state.
void ReSetPoinstion(double x, double y, double heading) override
Set vehicle position.
void Start() override
Starts the timer to publish simulated localization and chassis messages.
void Stop() override
Stops the timer.
void RunOnce() override
Main logic of the simulated control algorithm.
void Init(bool set_start_point, nlohmann::json start_point_attr, bool use_start_point_position=false) override
setup callbacks and timer
Linear interpolation functions.
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
Math-related util functions.
Some string util functions.
Some util functions.
nlohmann::json Json
SLPoint InterpolateUsingLinearApproximation(const SLPoint &p0, const SLPoint &p1, const double w)
Eigen::Quaternion< T > HeadingToQuaternion(T heading)
Definition quaternion.h:88
Eigen::Vector3d InverseQuaternionRotate(const Quaternion &orientation, const Eigen::Vector3d &rotated)
Definition quaternion.h:110
Eigen::Vector2d RotateVector2d(const Eigen::Vector2d &v_in, const double theta)
Definition math_utils.cc:82
class register implement
Definition arena_queue.h:37
Definition future.h:29
Contains a number of helper functions related to quaternions.