39using apollo::common::util::FillHeader;
46using Json = nlohmann::json;
50void TransformToVRF(
const Point3D &point_mrf,
const Quaternion &orientation,
52 Eigen::Vector3d v_mrf(point_mrf.x(), point_mrf.y(), point_mrf.z());
54 point_vrf->set_x(v_vrf.x());
55 point_vrf->set_y(v_vrf.y());
56 point_vrf->set_z(v_vrf.z());
59bool IsSameHeader(
const Header &lhs,
const Header &rhs) {
60 return lhs.sequence_num() == rhs.sequence_num() &&
61 lhs.timestamp_sec() == rhs.timestamp_sec();
68 map_service_(map_service),
69 node_(cyber::CreateNode(
"sim_perfect_control")),
74void SimPerfectControl::InitTimerAndIO() {
75 localization_reader_ =
78 FLAGS_planning_trajectory_topic,
79 [
this](
const std::shared_ptr<ADCTrajectory> &trajectory) {
80 this->OnPlanning(trajectory);
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);
87 navigation_reader_ = node_->CreateReader<NavigationInfo>(
88 FLAGS_navigation_topic,
89 [
this](
const std::shared_ptr<NavigationInfo> &navigation_info) {
90 this->OnReceiveNavigationInfo(navigation_info);
92 prediction_reader_ = node_->CreateReader<PredictionObstacles>(
93 FLAGS_prediction_topic,
94 [
this](
const std::shared_ptr<PredictionObstacles> &obstacles) {
95 this->OnPredictionObstacles(obstacles);
98 localization_writer_ =
99 node_->CreateWriter<LocalizationEstimate>(FLAGS_localization_topic);
100 chassis_writer_ = node_->CreateWriter<Chassis>(FLAGS_chassis_topic);
102 node_->CreateWriter<PredictionObstacles>(FLAGS_prediction_topic);
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(); },
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"]);
121void SimPerfectControl::InitStartPoint(
double x,
double y,
122 double start_velocity,
123 double start_acceleration) {
126 start_point_from_localization_ =
false;
127 point.mutable_path_point()->set_x(x);
128 point.mutable_path_point()->set_y(y);
130 point.mutable_path_point()->set_z(0);
134 point.mutable_path_point()->set_theta(theta);
135 point.set_v(start_velocity);
136 point.set_a(start_acceleration);
137 SetStartPoint(point);
141 std::lock_guard<std::mutex> lock(mutex_);
143 point.mutable_path_point()->set_x(x);
144 point.mutable_path_point()->set_y(y);
146 point.mutable_path_point()->set_z(0);
147 point.mutable_path_point()->set_theta(heading);
148 SetStartPoint(point);
152void SimPerfectControl::InitStartPoint(
double start_velocity,
153 double start_acceleration) {
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());
168 std::hypot(pose.linear_velocity().x(), pose.linear_velocity().y()));
173 pose.linear_acceleration().x() * pose.linear_velocity().x() +
174 pose.linear_acceleration().y() * pose.linear_velocity().y();
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;
184 if (!start_point_from_localization_) {
187 AWARN <<
"Failed to get a dummy start point from map!";
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());
197 point.mutable_path_point()->set_theta(theta);
198 point.set_v(start_velocity);
199 point.set_a(start_acceleration);
201 SetStartPoint(point);
204void SimPerfectControl::SetStartPoint(
const TrajectoryPoint &start_point) {
205 next_point_ = start_point;
206 prev_point_index_ = next_point_index_ = 0;
207 received_planning_ =
false;
211 std::lock_guard<std::mutex> lock(mutex_);
218 std::lock_guard<std::mutex> lock(timer_mutex_);
219 sim_control_timer_->Stop();
220 sim_prediction_timer_->Stop();
226void SimPerfectControl::InternalReset() {
227 current_routing_header_.Clear();
228 send_dummy_prediction_ =
true;
232void SimPerfectControl::ClearPlanning() {
233 current_trajectory_->Clear();
234 received_planning_ =
false;
237void SimPerfectControl::OnReceiveNavigationInfo(
238 const std::shared_ptr<NavigationInfo> &navigation_info) {
239 std::lock_guard<std::mutex> lock(mutex_);
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);
251void SimPerfectControl::OnPlanningCommand(
252 const std::shared_ptr<PlanningCommand> &planning_command) {
253 std::lock_guard<std::mutex> lock(mutex_);
259 send_dummy_prediction_ =
true;
260 current_routing_header_ = planning_command->header();
261 AINFO <<
"planning_command: " << planning_command->DebugString();
288void SimPerfectControl::OnPredictionObstacles(
289 const std::shared_ptr<PredictionObstacles> &obstacles) {
290 std::lock_guard<std::mutex> lock(mutex_);
296 send_dummy_prediction_ = obstacles->header().module_name() ==
"SimPrediction";
300 std::lock_guard<std::mutex> lock(mutex_);
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);
316 std::lock_guard<std::mutex> lock(timer_mutex_);
317 sim_control_timer_->Start();
318 sim_prediction_timer_->Start();
325 std::lock_guard<std::mutex> lock(mutex_);
329 InitStartPoint(x, y, v, a);
331 sim_control_timer_->Start();
332 sim_prediction_timer_->Start();
337void SimPerfectControl::OnPlanning(
338 const std::shared_ptr<ADCTrajectory> &trajectory) {
339 std::lock_guard<std::mutex> lock(mutex_);
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;
357void SimPerfectControl::Freeze() {
358 next_point_.set_v(0.0);
359 next_point_.set_a(0.0);
360 prev_point_ = next_point_;
364 std::lock_guard<std::mutex> lock(mutex_);
368 if (!PerfectControlModel(&trajectory_point, &gear_position)) {
369 AERROR <<
"Failed to calculate next point with perfect control model";
373 PublishChassis(trajectory_point.
v(), gear_position);
374 PublishLocalization(trajectory_point);
377bool SimPerfectControl::PerfectControlModel(
381 const auto &trajectory = current_trajectory_->trajectory_point();
382 *gear_position = current_trajectory_->gear();
384 if (!received_planning_) {
385 prev_point_ = next_point_;
387 if (current_trajectory_->estop().is_estop()) {
391 }
else if (next_point_index_ >= trajectory.size()) {
392 prev_point_ = next_point_;
395 while (next_point_index_ < trajectory.size() &&
396 current_time > trajectory.Get(next_point_index_).relative_time() +
397 current_trajectory_->header().timestamp_sec()) {
401 if (next_point_index_ >= trajectory.size()) {
402 next_point_index_ = trajectory.size() - 1;
405 if (next_point_index_ == 0) {
406 AERROR <<
"First trajectory point is a future point!";
410 prev_point_index_ = next_point_index_ - 1;
412 next_point_ = trajectory.Get(next_point_index_);
413 prev_point_ = trajectory.Get(prev_point_index_);
418 current_trajectory_->header().timestamp_sec()) {
420 *point = next_point_;
423 prev_point_, next_point_,
424 current_time - current_trajectory_->header().timestamp_sec());
429void SimPerfectControl::PublishChassis(
double cur_speed,
431 auto chassis = std::make_shared<Chassis>();
432 FillHeader(
"SimPerfectControl", chassis.get());
434 chassis->set_engine_started(
true);
436 chassis->set_gear_location(gear_position);
438 chassis->set_speed_mps(
static_cast<float>(cur_speed));
440 chassis->set_speed_mps(-chassis->speed_mps());
443 chassis->set_throttle_percentage(0.0);
444 chassis->set_brake_percentage(0.0);
446 chassis_writer_->Write(chassis);
449void SimPerfectControl::PublishLocalization(
const TrajectoryPoint &point) {
450 auto localization = std::make_shared<LocalizationEstimate>();
451 FillHeader(
"SimPerfectControl", localization.get());
452 auto *pose = localization->mutable_pose();
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());
461 double cur_theta = point.path_point().
theta();
463 if (FLAGS_use_navigation_mode) {
464 double flu_x = point.path_point().x();
465 double flu_y = point.path_point().y();
467 Eigen::Vector2d enu_coordinate =
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());
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);
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);
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());
497 pose->mutable_angular_velocity_vrf());
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);
507 pose->mutable_linear_acceleration_vrf());
508 localization_writer_->Write(localization);
510 adc_position_.set_x(pose->position().x());
511 adc_position_.set_y(pose->position().y());
512 adc_position_.set_z(pose->position().z());
515void SimPerfectControl::PublishDummyPrediction() {
516 auto prediction = std::make_shared<PredictionObstacles>();
518 std::lock_guard<std::mutex> lock(mutex_);
519 if (!send_dummy_prediction_) {
522 FillHeader(
"SimPrediction", prediction.get());
524 prediction_writer_->Write(prediction);
a singleton clock that can be used to get the current timestamp.
static double NowInSeconds()
gets the current time in second.
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.
Math-related util functions.
Some string util functions.
SLPoint InterpolateUsingLinearApproximation(const SLPoint &p0, const SLPoint &p1, const double w)
Eigen::Quaternion< T > HeadingToQuaternion(T heading)
Eigen::Vector3d InverseQuaternionRotate(const Quaternion &orientation, const Eigen::Vector3d &rotated)
Eigen::Vector2d RotateVector2d(const Eigen::Vector2d &v_in, const double theta)
Contains a number of helper functions related to quaternions.
optional double relative_time
optional PathPoint path_point