sim_perfect_control.cc 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658
  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. #include "modules/dreamview/backend/common/sim_control_manager/dynamic_model/perfect_control/sim_perfect_control.h"
  17. #include "cyber/common/file.h"
  18. #include "cyber/time/clock.h"
  19. #include "modules/common/adapters/adapter_gflags.h"
  20. #include "modules/common/math/linear_interpolation.h"
  21. #include "modules/common/math/math_utils.h"
  22. #include "modules/common/math/quaternion.h"
  23. #include "modules/common/util/message_util.h"
  24. #include "modules/common/util/util.h"
  25. #include <math.h>
  26. namespace apollo {
  27. namespace dreamview {
  28. using apollo::canbus::Chassis;
  29. using apollo::common::Header;
  30. using apollo::common::Point3D;
  31. using apollo::common::Quaternion;
  32. using apollo::common::TrajectoryPoint;
  33. using apollo::common::math::HeadingToQuaternion;
  34. using apollo::common::math::InterpolateUsingLinearApproximation;
  35. using apollo::common::math::InverseQuaternionRotate;
  36. using apollo::common::util::FillHeader;
  37. using apollo::cyber::Clock;
  38. using apollo::localization::LocalizationEstimate;
  39. using apollo::planning::ADCTrajectory;
  40. using apollo::planning::PlanningCommand;
  41. using apollo::prediction::PredictionObstacles;
  42. using apollo::relative_map::NavigationInfo;
  43. using Json = nlohmann::json;
  44. #include <iostream>
  45. #include <fstream>
  46. #include <chrono>
  47. #include <iomanip>
  48. void adclog1(const char * strlog){
  49. std::ofstream myFile;
  50. // myFile.open("/home/yuchuli/adclog.txt", std::ios_base::app);
  51. myFile.open("/apollo/adclog.txt", std::ios_base::app);
  52. if(myFile.is_open())
  53. {
  54. auto now = std::chrono::system_clock::now();
  55. // std::time_t now_c = std::chrono::system_clock::to_time_t(now - std::chrono::hours(24));
  56. std::time_t now_c = std::chrono::system_clock::to_time_t(now);
  57. myFile<<std::put_time(std::localtime(&now_c), "%Y-%m-%d %X ") <<strlog<<std::endl;
  58. myFile.close();
  59. }
  60. else
  61. {
  62. std::cout<<"open fail"<<std::endl;
  63. }
  64. }
  65. // gflags定义类型 描述
  66. DEFINE_bool(use_realveh, true, "set use real vehicle"); // bool位整型
  67. DECLARE_bool(use_realveh);
  68. double fNowVel = 0.0;
  69. void LoadConfigFile(const std::string& file_path) {
  70. std::ifstream config_file(file_path);
  71. if (!config_file.is_open()) {
  72. std::cout << "Failed to open configuration file: " << file_path << std::endl;
  73. return;
  74. }
  75. std::string line;
  76. while (std::getline(config_file, line)) {
  77. std::istringstream iss(line);
  78. std::string key, value;
  79. if (std::getline(iss, key, '=') && std::getline(iss, value)) {
  80. // 去除前后的空白字符
  81. std::size_t first = value.find_first_not_of(" \t");
  82. std::size_t last = value.find_last_not_of(" \t");
  83. if (first != std::string::npos && last != std::string::npos) {
  84. value = value.substr(first, last - first + 1);
  85. // 这里可以处理不同的 flag 类型,这里简单处理为 string 类型
  86. if (key == "-use_realveh") {
  87. google::SetCommandLineOption("use_realveh", value.c_str());
  88. }
  89. // 可以添加更多类型的处理
  90. }
  91. }
  92. }
  93. config_file.close();
  94. }
  95. namespace {
  96. void TransformToVRF(const Point3D &point_mrf, const Quaternion &orientation,
  97. Point3D *point_vrf) {
  98. Eigen::Vector3d v_mrf(point_mrf.x(), point_mrf.y(), point_mrf.z());
  99. auto v_vrf = InverseQuaternionRotate(orientation, v_mrf);
  100. point_vrf->set_x(v_vrf.x());
  101. point_vrf->set_y(v_vrf.y());
  102. point_vrf->set_z(v_vrf.z());
  103. }
  104. bool IsSameHeader(const Header &lhs, const Header &rhs) {
  105. return lhs.sequence_num() == rhs.sequence_num() &&
  106. lhs.timestamp_sec() == rhs.timestamp_sec();
  107. }
  108. } // namespace
  109. SimPerfectControl::SimPerfectControl(const MapService *map_service)
  110. : SimControlBase(),
  111. map_service_(map_service),
  112. node_(cyber::CreateNode("sim_perfect_control")),
  113. current_trajectory_(std::make_shared<ADCTrajectory>()) {
  114. InitTimerAndIO();
  115. LoadConfigFile("/apollo/adcconfig.txt");
  116. if(FLAGS_use_realveh == true){
  117. adclog1("use real vehicle.");
  118. }else{
  119. adclog1("use simulate.");
  120. }
  121. }
  122. void SimPerfectControl::InitTimerAndIO() {
  123. std::cout<<"init timer."<<std::endl;
  124. localization_reader_ =
  125. node_->CreateReader<LocalizationEstimate>(FLAGS_localization_topic);
  126. localization_adc_reader_ = node_->CreateReader<LocalizationEstimate>(
  127. "/apollo/localization/adcpose",
  128. [this](const std::shared_ptr<LocalizationEstimate> &xloc) {
  129. this->onADCLoc(xloc);
  130. });
  131. planning_reader_ = node_->CreateReader<ADCTrajectory>(
  132. FLAGS_planning_trajectory_topic,
  133. [this](const std::shared_ptr<ADCTrajectory> &trajectory) {
  134. this->OnPlanning(trajectory);
  135. });
  136. planning_command_reader_ = node_->CreateReader<PlanningCommand>(
  137. FLAGS_planning_command,
  138. [this](const std::shared_ptr<PlanningCommand> &planning_command) {
  139. this->OnPlanningCommand(planning_command);
  140. });
  141. navigation_reader_ = node_->CreateReader<NavigationInfo>(
  142. FLAGS_navigation_topic,
  143. [this](const std::shared_ptr<NavigationInfo> &navigation_info) {
  144. this->OnReceiveNavigationInfo(navigation_info);
  145. });
  146. prediction_reader_ = node_->CreateReader<PredictionObstacles>(
  147. FLAGS_prediction_topic,
  148. [this](const std::shared_ptr<PredictionObstacles> &obstacles) {
  149. this->OnPredictionObstacles(obstacles);
  150. });
  151. control_command_reader_ = node_->CreateReader<apollo::control::ControlCommand>(
  152. "/apollo/control",
  153. [this](const std::shared_ptr<apollo::control::ControlCommand> &xctrlcmd) {
  154. this->onControl(xctrlcmd);
  155. });
  156. localization_writer_ =
  157. node_->CreateWriter<LocalizationEstimate>(FLAGS_localization_topic);
  158. chassis_writer_ = node_->CreateWriter<Chassis>(FLAGS_chassis_topic);
  159. prediction_writer_ =
  160. node_->CreateWriter<PredictionObstacles>(FLAGS_prediction_topic);
  161. // Start timer to publish localization and chassis messages.
  162. sim_control_timer_.reset(new cyber::Timer(
  163. kSimControlIntervalMs, [this]() { this->RunOnce(); }, false));
  164. sim_prediction_timer_.reset(new cyber::Timer(
  165. kSimPredictionIntervalMs, [this]() { this->PublishDummyPrediction(); },
  166. false));
  167. }
  168. void SimPerfectControl::Init(bool set_start_point,
  169. nlohmann::json start_point_attr,
  170. bool use_start_point_position) {
  171. if (set_start_point && !FLAGS_use_navigation_mode) {
  172. InitStartPoint(start_point_attr["start_velocity"],
  173. start_point_attr["start_acceleration"]);
  174. }
  175. }
  176. void SimPerfectControl::InitStartPoint(double x, double y,
  177. double start_velocity,
  178. double start_acceleration) {
  179. TrajectoryPoint point;
  180. // Use the scenario start point as start point,
  181. start_point_from_localization_ = false;
  182. point.mutable_path_point()->set_x(x);
  183. point.mutable_path_point()->set_y(y);
  184. // z use default 0
  185. point.mutable_path_point()->set_z(0);
  186. double theta = 0.0;
  187. double s = 0.0;
  188. map_service_->GetPoseWithRegardToLane(x, y, &theta, &s);
  189. point.mutable_path_point()->set_theta(theta);
  190. point.set_v(start_velocity);
  191. point.set_a(start_acceleration);
  192. SetStartPoint(point);
  193. }
  194. void SimPerfectControl::ReSetPoinstion(double x, double y, double heading) {
  195. std::lock_guard<std::mutex> lock(mutex_);
  196. TrajectoryPoint point;
  197. point.mutable_path_point()->set_x(x);
  198. point.mutable_path_point()->set_y(y);
  199. // z use default 0
  200. point.mutable_path_point()->set_z(0);
  201. point.mutable_path_point()->set_theta(heading);
  202. AINFO << "start point:" << point.DebugString();
  203. SetStartPoint(point);
  204. InternalReset();
  205. }
  206. void SimPerfectControl::InitStartPoint(double start_velocity,
  207. double start_acceleration) {
  208. TrajectoryPoint point;
  209. // Use the latest localization position as start point,
  210. // fall back to a dummy point from map
  211. localization_reader_->Observe();
  212. start_point_from_localization_ = false;
  213. if (!localization_reader_->Empty()) {
  214. const auto &localization = localization_reader_->GetLatestObserved();
  215. const auto &pose = localization->pose();
  216. if (map_service_->PointIsValid(pose.position().x(), pose.position().y())) {
  217. point.mutable_path_point()->set_x(pose.position().x());
  218. point.mutable_path_point()->set_y(pose.position().y());
  219. point.mutable_path_point()->set_z(pose.position().z());
  220. point.mutable_path_point()->set_theta(pose.heading());
  221. point.set_v(
  222. std::hypot(pose.linear_velocity().x(), pose.linear_velocity().y()));
  223. // Calculates the dot product of acceleration and velocity. The sign
  224. // of this projection indicates whether this is acceleration or
  225. // deceleration.
  226. double projection =
  227. pose.linear_acceleration().x() * pose.linear_velocity().x() +
  228. pose.linear_acceleration().y() * pose.linear_velocity().y();
  229. // Calculates the magnitude of the acceleration. Negate the value if
  230. // it is indeed a deceleration.
  231. double magnitude = std::hypot(pose.linear_acceleration().x(),
  232. pose.linear_acceleration().y());
  233. point.set_a(std::signbit(projection) ? -magnitude : magnitude);
  234. start_point_from_localization_ = true;
  235. }
  236. }
  237. if (!start_point_from_localization_) {
  238. apollo::common::PointENU start_point;
  239. if (!map_service_->GetStartPoint(&start_point)) {
  240. AWARN << "Failed to get a dummy start point from map!";
  241. return;
  242. }
  243. point.mutable_path_point()->set_x(start_point.x());
  244. point.mutable_path_point()->set_y(start_point.y());
  245. point.mutable_path_point()->set_z(start_point.z());
  246. double theta = 0.0;
  247. double s = 0.0;
  248. map_service_->GetPoseWithRegardToLane(start_point.x(), start_point.y(),
  249. &theta, &s);
  250. point.mutable_path_point()->set_theta(theta);
  251. point.set_v(start_velocity);
  252. point.set_a(start_acceleration);
  253. }
  254. SetStartPoint(point);
  255. }
  256. void SimPerfectControl::SetStartPoint(const TrajectoryPoint &start_point) {
  257. next_point_ = start_point;
  258. prev_point_index_ = next_point_index_ = 0;
  259. received_planning_ = false;
  260. }
  261. void SimPerfectControl::Reset() {
  262. std::lock_guard<std::mutex> lock(mutex_);
  263. InternalReset();
  264. }
  265. void SimPerfectControl::Stop() {
  266. if (enabled_) {
  267. {
  268. std::lock_guard<std::mutex> lock(timer_mutex_);
  269. sim_control_timer_->Stop();
  270. sim_prediction_timer_->Stop();
  271. }
  272. enabled_ = false;
  273. }
  274. }
  275. void SimPerfectControl::InternalReset() {
  276. current_routing_header_.Clear();
  277. send_dummy_prediction_ = true;
  278. ClearPlanning();
  279. }
  280. void SimPerfectControl::ClearPlanning() {
  281. current_trajectory_->Clear();
  282. received_planning_ = false;
  283. }
  284. void SimPerfectControl::OnReceiveNavigationInfo(
  285. const std::shared_ptr<NavigationInfo> &navigation_info) {
  286. std::lock_guard<std::mutex> lock(mutex_);
  287. if (!enabled_) {
  288. return;
  289. }
  290. if (navigation_info->navigation_path_size() > 0) {
  291. const auto &path = navigation_info->navigation_path(0).path();
  292. if (path.path_point_size() > 0) {
  293. adc_position_ = path.path_point(0);
  294. }
  295. }
  296. }
  297. void SimPerfectControl::onADCLoc(const std::shared_ptr<apollo::localization::LocalizationEstimate> &xloc){
  298. std::lock_guard<std::mutex> lock(mutex_);
  299. adcloc_ = xloc;
  300. receiveadcloc = true;
  301. }
  302. void SimPerfectControl::OnPlanningCommand(
  303. const std::shared_ptr<PlanningCommand> &planning_command) {
  304. std::lock_guard<std::mutex> lock(mutex_);
  305. if (!enabled_) {
  306. return;
  307. }
  308. // Avoid not sending prediction messages to planning after playing packets
  309. // with obstacles
  310. send_dummy_prediction_ = true;
  311. current_routing_header_ = planning_command->header();
  312. AINFO << "planning_command: " << planning_command->DebugString();
  313. if (planning_command->lane_follow_command()
  314. .routing_request()
  315. .is_start_pose_set()) {
  316. auto lane_follow_command = planning_command->mutable_lane_follow_command();
  317. const auto &start_pose =
  318. lane_follow_command->routing_request().waypoint(0).pose();
  319. ClearPlanning();
  320. TrajectoryPoint point;
  321. point.mutable_path_point()->set_x(start_pose.x());
  322. point.mutable_path_point()->set_y(start_pose.y());
  323. point.set_a(next_point_.has_a() ? next_point_.a() : 0.0);
  324. point.set_v(next_point_.has_v() ? next_point_.v() : 0.0);
  325. double theta = 0.0;
  326. double s = 0.0;
  327. // Find the lane nearest to the start pose and get its heading as theta.
  328. map_service_->GetPoseWithRegardToLane(start_pose.x(), start_pose.y(),
  329. &theta, &s);
  330. point.mutable_path_point()->set_theta(theta);
  331. SetStartPoint(point);
  332. }
  333. }
  334. void SimPerfectControl::onControl(
  335. const std::shared_ptr<apollo::control::ControlCommand> &xCmd) {
  336. // std::lock_guard<std::mutex> lock(mutex_);
  337. std::lock_guard<std::mutex> lock(mutex_);
  338. // std::cout<<"steer: "<<xCmd->steering_target()<<" acc: "<<xCmd->acceleration()<<" brake:"<<xCmd->brake()<<std::endl;
  339. fcmdsteer_ = xCmd->steering_target();
  340. fcmdbrake_ = xCmd->brake();
  341. fcmdacc_ = xCmd->throttle();
  342. }
  343. void SimPerfectControl::OnPredictionObstacles(
  344. const std::shared_ptr<PredictionObstacles> &obstacles) {
  345. std::lock_guard<std::mutex> lock(mutex_);
  346. if (!enabled_) {
  347. return;
  348. }
  349. send_dummy_prediction_ = obstacles->header().module_name() == "SimPrediction";
  350. }
  351. void SimPerfectControl::Start() {
  352. std::lock_guard<std::mutex> lock(mutex_);
  353. if (!enabled_) {
  354. // When there is no localization yet, Init(true) will use a
  355. // dummy point from the current map as an arbitrary start.
  356. // When localization is already available, we do not need to
  357. // reset/override the start point.
  358. localization_reader_->Observe();
  359. Json start_point_attr({});
  360. start_point_attr["start_velocity"] =
  361. next_point_.has_v() ? next_point_.v() : 0.0;
  362. start_point_attr["start_acceleration"] =
  363. next_point_.has_a() ? next_point_.a() : 0.0;
  364. Init(true, start_point_attr);
  365. InternalReset();
  366. {
  367. std::lock_guard<std::mutex> lock(timer_mutex_);
  368. sim_control_timer_->Start();
  369. sim_prediction_timer_->Start();
  370. }
  371. enabled_ = true;
  372. }
  373. }
  374. void SimPerfectControl::Start(double x, double y,double v , double a ) {
  375. std::lock_guard<std::mutex> lock(mutex_);
  376. if (!enabled_) {
  377. // Do not use localization info. use scenario start point to init start
  378. // point.
  379. InitStartPoint(x, y, v, a);
  380. InternalReset();
  381. sim_control_timer_->Start();
  382. sim_prediction_timer_->Start();
  383. enabled_ = true;
  384. }
  385. }
  386. void SimPerfectControl::OnPlanning(
  387. const std::shared_ptr<ADCTrajectory> &trajectory) {
  388. std::lock_guard<std::mutex> lock(mutex_);
  389. if (!enabled_) {
  390. return;
  391. }
  392. // Reset current trajectory and the indices upon receiving a new trajectory.
  393. // The routing SimPerfectControl owns must match with the one Planning has.
  394. if (IsSameHeader(trajectory->routing_header(), current_routing_header_)) {
  395. current_trajectory_ = trajectory;
  396. prev_point_index_ = 0;
  397. next_point_index_ = 0;
  398. received_planning_ = true;
  399. } else {
  400. ClearPlanning();
  401. }
  402. }
  403. void SimPerfectControl::Freeze() {
  404. next_point_.set_v(0.0);
  405. next_point_.set_a(0.0);
  406. prev_point_ = next_point_;
  407. }
  408. void SimPerfectControl::RunOnce() {
  409. std::lock_guard<std::mutex> lock(mutex_);
  410. TrajectoryPoint trajectory_point;
  411. Chassis::GearPosition gear_position;
  412. if (!PerfectControlModel(&trajectory_point, &gear_position)) {
  413. if(receiveadcloc == false){
  414. AERROR << "Failed to calculate next point with perfect control model";
  415. return;
  416. }
  417. }
  418. PublishChassis(trajectory_point.v(), gear_position);
  419. PublishLocalization(trajectory_point);
  420. }
  421. bool SimPerfectControl::PerfectControlModel(
  422. TrajectoryPoint *point, Chassis::GearPosition *gear_position) {
  423. // Result of the interpolation.
  424. auto current_time = Clock::NowInSeconds();
  425. const auto &trajectory = current_trajectory_->trajectory_point();
  426. *gear_position = current_trajectory_->gear();
  427. // adclog1("run perfect control model.");
  428. if (!received_planning_) {
  429. prev_point_ = next_point_;
  430. } else {
  431. if (current_trajectory_->estop().is_estop() ||
  432. next_point_index_ >= trajectory.size()) {
  433. // Freeze the car when there's an estop or the current trajectory has
  434. // been exhausted.
  435. Freeze();
  436. } else {
  437. // Determine the status of the car based on received planning message.
  438. while (next_point_index_ < trajectory.size() &&
  439. current_time > trajectory.Get(next_point_index_).relative_time() +
  440. current_trajectory_->header().timestamp_sec()) {
  441. ++next_point_index_;
  442. }
  443. if (next_point_index_ >= trajectory.size()) {
  444. next_point_index_ = trajectory.size() - 1;
  445. }
  446. if (next_point_index_ == 0) {
  447. AERROR << "First trajectory point is a future point!";
  448. return false;
  449. }
  450. prev_point_index_ = next_point_index_ - 1;
  451. next_point_ = trajectory.Get(next_point_index_);
  452. prev_point_ = trajectory.Get(prev_point_index_);
  453. }
  454. }
  455. if (current_time > next_point_.relative_time() +
  456. current_trajectory_->header().timestamp_sec()) {
  457. // Don't try to extrapolate if relative_time passes last point
  458. *point = next_point_;
  459. } else {
  460. *point = InterpolateUsingLinearApproximation(
  461. prev_point_, next_point_,
  462. current_time - current_trajectory_->header().timestamp_sec());
  463. }
  464. return true;
  465. }
  466. void SimPerfectControl::PublishChassis(double cur_speed,
  467. Chassis::GearPosition gear_position) {
  468. auto chassis = std::make_shared<Chassis>();
  469. FillHeader("SimPerfectControl", chassis.get());
  470. chassis->set_engine_started(true);
  471. chassis->set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
  472. chassis->set_gear_location(gear_position);
  473. chassis->set_speed_mps(static_cast<float>(cur_speed));
  474. if (gear_position == canbus::Chassis::GEAR_REVERSE) {
  475. chassis->set_speed_mps(-chassis->speed_mps());
  476. }
  477. if((FLAGS_use_realveh == true) && (receiveadcloc)){
  478. chassis->set_speed_mps(static_cast<float>(fNowVel));
  479. }
  480. chassis->set_throttle_percentage(fcmdacc_);
  481. chassis->set_brake_percentage(fcmdbrake_);
  482. chassis->set_steering_percentage(fcmdsteer_);
  483. chassis_writer_->Write(chassis);
  484. }
  485. void SimPerfectControl::PublishLocalization(const TrajectoryPoint &point) {
  486. auto localization = std::make_shared<LocalizationEstimate>();
  487. FillHeader("SimPerfectControl", localization.get());
  488. if((receiveadcloc))
  489. {
  490. localization = adcloc_;
  491. localization_writer_->Write(localization);
  492. auto *pose = localization->mutable_pose();
  493. fNowVel = sqrt(pow(pose->mutable_linear_velocity()->x(),2)+pow(pose->mutable_linear_velocity()->y(),2));
  494. adc_position_.set_x(pose->position().x());
  495. adc_position_.set_y(pose->position().y());
  496. adc_position_.set_z(pose->position().z());
  497. return;
  498. }
  499. auto *pose = localization->mutable_pose();
  500. auto prev = prev_point_.path_point();
  501. auto next = next_point_.path_point();
  502. // Set position 507530.95 4331929.85
  503. pose->mutable_position()->set_x(point.path_point().x());
  504. pose->mutable_position()->set_y(point.path_point().y());
  505. pose->mutable_position()->set_z(point.path_point().z());
  506. // Set orientation and heading
  507. double cur_theta = point.path_point().theta();
  508. if (FLAGS_use_navigation_mode) {
  509. double flu_x = point.path_point().x();
  510. double flu_y = point.path_point().y();
  511. Eigen::Vector2d enu_coordinate =
  512. common::math::RotateVector2d({flu_x, flu_y}, cur_theta);
  513. enu_coordinate.x() += adc_position_.x();
  514. enu_coordinate.y() += adc_position_.y();
  515. pose->mutable_position()->set_x(enu_coordinate.x());
  516. pose->mutable_position()->set_y(enu_coordinate.y());
  517. }
  518. Eigen::Quaternion<double> cur_orientation =
  519. HeadingToQuaternion<double>(cur_theta);
  520. pose->mutable_orientation()->set_qw(cur_orientation.w());
  521. pose->mutable_orientation()->set_qx(cur_orientation.x());
  522. pose->mutable_orientation()->set_qy(cur_orientation.y());
  523. pose->mutable_orientation()->set_qz(cur_orientation.z());
  524. pose->set_heading(cur_theta);
  525. // Set linear_velocity
  526. pose->mutable_linear_velocity()->set_x(std::cos(cur_theta) * point.v());
  527. pose->mutable_linear_velocity()->set_y(std::sin(cur_theta) * point.v());
  528. pose->mutable_linear_velocity()->set_z(0);
  529. // Set angular_velocity in both map reference frame and vehicle reference
  530. // frame
  531. pose->mutable_angular_velocity()->set_x(0);
  532. pose->mutable_angular_velocity()->set_y(0);
  533. pose->mutable_angular_velocity()->set_z(point.v() *
  534. point.path_point().kappa());
  535. TransformToVRF(pose->angular_velocity(), pose->orientation(),
  536. pose->mutable_angular_velocity_vrf());
  537. // Set linear_acceleration in both map reference frame and vehicle reference
  538. // frame
  539. auto *linear_acceleration = pose->mutable_linear_acceleration();
  540. linear_acceleration->set_x(std::cos(cur_theta) * point.a());
  541. linear_acceleration->set_y(std::sin(cur_theta) * point.a());
  542. linear_acceleration->set_z(0);
  543. TransformToVRF(pose->linear_acceleration(), pose->orientation(),
  544. pose->mutable_linear_acceleration_vrf());
  545. localization_writer_->Write(localization);
  546. adc_position_.set_x(pose->position().x());
  547. adc_position_.set_y(pose->position().y());
  548. adc_position_.set_z(pose->position().z());
  549. }
  550. void SimPerfectControl::PublishDummyPrediction() {
  551. if(receiveadcloc)return;
  552. auto prediction = std::make_shared<PredictionObstacles>();
  553. {
  554. std::lock_guard<std::mutex> lock(mutex_);
  555. if (!send_dummy_prediction_) {
  556. return;
  557. }
  558. FillHeader("SimPrediction", prediction.get());
  559. }
  560. prediction_writer_->Write(prediction);
  561. }
  562. } // namespace dreamview
  563. } // namespace apollo