Apollo 10.0
自动驾驶开放平台
hmi_worker.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 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 "absl/strings/str_cat.h"
20#include "absl/strings/str_join.h"
21#include "absl/strings/str_split.h"
22
23#include "cyber/proto/dag_conf.pb.h"
24#include "modules/common_msgs/monitor_msgs/system_status.pb.h"
25#include "modules/dreamview/proto/scenario.pb.h"
26
27#include "cyber/common/file.h"
41
42namespace apollo {
43namespace dreamview {
44namespace {
45
60using apollo::monitor::ComponentStatus;
61using apollo::monitor::SystemStatus;
62using google::protobuf::util::JsonStringToMessage;
63using RLock = boost::shared_lock<boost::shared_mutex>;
64using WLock = boost::unique_lock<boost::shared_mutex>;
65using Json = nlohmann::json;
66
67constexpr char kNavigationModeName[] = "Navigation";
68
69template <class FlagType, class ValueType>
70void SetGlobalFlag(std::string_view flag_name, const ValueType &value,
71 FlagType *flag) {
72 // change to relative path for portability
73 constexpr char kGlobalFlagfile[] = "modules/common/data/global_flagfile.txt";
74 if (*flag != value) {
75 *flag = value;
76 // Overwrite global flagfile.
77 std::ofstream fout(kGlobalFlagfile, std::ios_base::app);
78 ACHECK(fout) << "Fail to open global flagfile " << kGlobalFlagfile;
79 fout << "\n--" << flag_name << "=" << value << std::endl;
80 }
81}
82
83void System(std::string_view cmd) {
84 const int ret = std::system(cmd.data());
85 if (ret == 0) {
86 AINFO << "SUCCESS: " << cmd;
87 } else {
88 AERROR << "FAILED(" << ret << "): " << cmd;
89 }
90}
91
92} // namespace
93
94HMIWorker::HMIWorker(const std::shared_ptr<Node> &node)
95 : config_(util::HMIUtil::LoadConfig(FLAGS_dv_hmi_modes_config_path)),
96 node_(node) {
97 InitStatus();
98}
99
100void HMIWorker::Start(DvCallback callback_api) {
101 callback_api_ = callback_api;
102 InitReadersAndWriters();
103 RegisterStatusUpdateHandler(
104 [this](const bool status_changed, HMIStatus *status) {
105 apollo::common::util::FillHeader("HMI", status);
106 status_writer_->Write(*status);
107 status->clear_header();
108 });
109 ResetComponentStatusTimer();
110 thread_future_ = cyber::Async(&HMIWorker::StatusUpdateThreadLoop, this);
111}
112
113void HMIWorker::Stop() {
114 stop_ = true;
115 if (thread_future_.valid()) {
116 thread_future_.get();
117 }
118}
119
120bool HMIWorker::LoadVehicleDefinedMode(const std::string &mode_config_path,
121 const std::string &current_vehicle_path,
122 HMIMode *self_defined_mode) {
123 const std::string mode_file_name =
124 cyber::common::GetFileName(mode_config_path);
125 const std::string vehicle_mode_config_path =
126 current_vehicle_path + "/dreamview_conf/hmi_modes/" + mode_file_name;
127 if (!cyber::common::PathExists(vehicle_mode_config_path)) {
128 return false;
129 }
130 ACHECK(cyber::common::GetProtoFromFile(vehicle_mode_config_path,
131 self_defined_mode))
132 << "Unable to parse vehicle self defined HMIMode from file "
133 << vehicle_mode_config_path;
134 util::HMIUtil::TranslateCyberModules(self_defined_mode);
135 return true;
136}
137
138void HMIWorker::InitStatus() {
139 static constexpr char kDockerImageEnv[] = "DOCKER_IMG";
140 status_.set_docker_image(cyber::common::GetEnv(kDockerImageEnv));
141 status_.set_utm_zone_id(FLAGS_local_utm_zone_id);
142
143 // Populate modes and current_mode.
144 const auto &modes = config_.modes();
145 for (const auto &iter : modes) {
146 const std::string &mode = iter.first;
147 status_.add_modes(mode);
148 if (mode == FLAGS_vehicle_calibration_mode) {
149 FuelMonitorManager::Instance()->RegisterFuelMonitor(
150 mode, std::make_unique<DataCollectionMonitor>());
151 FuelMonitorManager::Instance()->RegisterFuelMonitor(
152 mode, std::make_unique<PreprocessMonitor>());
153 } else if (mode == FLAGS_lidar_calibration_mode) {
154 FuelMonitorManager::Instance()->RegisterFuelMonitor(
155 mode, std::make_unique<PreprocessMonitor>("lidar_to_gnss"));
156 } else if (mode == FLAGS_camera_calibration_mode) {
157 FuelMonitorManager::Instance()->RegisterFuelMonitor(
158 mode, std::make_unique<PreprocessMonitor>("camera_to_lidar"));
159 }
160 }
161
162 // Populate maps and current_map.
163 for (const auto &map_entry : config_.maps()) {
164 status_.add_maps(map_entry.first);
165
166 // If current FLAG_map_dir is available, set it as current_map.
167 if (map_entry.second == FLAGS_map_dir) {
168 status_.set_current_map(map_entry.first);
169 }
170 }
171
172 // Populate vehicles and current_vehicle.
173 for (const auto &vehicle : config_.vehicles()) {
174 status_.add_vehicles(vehicle.first);
175 }
176
177 // Initial HMIMode by priority:
178 // 1. NavigationMode if --use_navigation_mode is specified explicitly.
179 // 2. CachedMode if it's stored in KV database.
180 // 3. default_hmi_mode if it is available.
181 // 4. Pick the first available mode.
182 const std::string cached_mode =
183 KVDB::Get(FLAGS_current_mode_db_key).value_or("");
184 if (FLAGS_use_navigation_mode && ContainsKey(modes, kNavigationModeName)) {
185 ChangeMode(kNavigationModeName);
186 } else if (ContainsKey(modes, cached_mode)) {
187 ChangeMode(cached_mode);
188 } else if (ContainsKey(modes, FLAGS_default_hmi_mode)) {
189 ChangeMode(FLAGS_default_hmi_mode);
190 } else {
191 ChangeMode(modes.begin()->first);
192 }
193}
194
195void HMIWorker::InitReadersAndWriters() {
196 status_writer_ = node_->CreateWriter<HMIStatus>(FLAGS_hmi_status_topic);
197 action_command_client_ = node_->CreateClient<ActionCommand, CommandStatus>(
198 FLAGS_action_command_topic);
199 lane_follow_command_client_ =
200 node_->CreateClient<LaneFollowCommand, CommandStatus>(
201 FLAGS_lane_follow_command_topic);
202 audio_event_writer_ =
203 node_->CreateWriter<AudioEvent>(FLAGS_audio_event_topic);
204 drive_event_writer_ =
205 node_->CreateWriter<DriveEvent>(FLAGS_drive_event_topic);
206
207 node_->CreateReader<SystemStatus>(
208 FLAGS_system_status_topic,
209 [this](const std::shared_ptr<SystemStatus> &system_status) {
210 this->ResetComponentStatusTimer();
211
212 WLock wlock(status_mutex_);
213
214 const bool is_realtime_msg =
215 FLAGS_use_sim_time
216 ? system_status->is_realtime_in_simulation()
218 system_status->header().timestamp_sec() <
219 FLAGS_system_status_lifetime_seconds;
220 // Update modules running status from realtime SystemStatus.
221 if (is_realtime_msg) {
222 for (auto &iter : *status_.mutable_modules()) {
223 auto *status = FindOrNull(system_status->hmi_modules(), iter.first);
224 iter.second =
225 status != nullptr && status->status() == ComponentStatus::OK;
226 }
227 }
228 // Update monitored components status.
229 for (auto &iter : *status_.mutable_monitored_components()) {
230 auto *status = FindOrNull(system_status->components(), iter.first);
231 if (status != nullptr) {
232 iter.second = status->summary();
233 } else {
234 iter.second.set_status(ComponentStatus::UNKNOWN);
235 iter.second.set_message("Status not reported by Monitor.");
236 }
237 }
238
239 // Update other components status.
240 for (auto &iter : *status_.mutable_other_components()) {
241 auto *status =
242 FindOrNull(system_status->other_components(), iter.first);
243 if (status != nullptr) {
244 iter.second.CopyFrom(*status);
245 } else {
246 iter.second.set_status(ComponentStatus::UNKNOWN);
247 iter.second.set_message("Status not reported by Monitor.");
248 }
249 }
250
251 // Check if the status is changed.
252 const size_t new_fingerprint =
254 if (last_status_fingerprint_ != new_fingerprint) {
255 status_changed_ = true;
256 last_status_fingerprint_ = new_fingerprint;
257 }
258 });
259
260 localization_reader_ =
261 node_->CreateReader<LocalizationEstimate>(FLAGS_localization_topic);
262 // Received Chassis, trigger action if there is high beam signal.
263 chassis_reader_ = node_->CreateReader<Chassis>(
264 FLAGS_chassis_topic, [this](const std::shared_ptr<Chassis> &chassis) {
265 if (Clock::NowInSeconds() - chassis->header().timestamp_sec() <
266 FLAGS_system_status_lifetime_seconds) {
267 if (chassis->signal().high_beam()) {
268 // Currently we do nothing on high_beam signal.
269 const bool ret = Trigger(HMIAction::NONE);
270 AERROR_IF(!ret) << "Failed to execute high_beam action.";
271 }
272 }
273 });
274}
275
276bool HMIWorker::Trigger(const HMIAction action) {
277 AERROR << "HMIAction " << HMIAction_Name(action) << " was triggered!";
278 switch (action) {
279 case HMIAction::NONE:
280 break;
281 case HMIAction::SETUP_MODE:
282 SetupMode();
283 break;
284 case HMIAction::ENTER_AUTO_MODE:
285 return ChangeDrivingMode(Chassis::COMPLETE_AUTO_DRIVE);
286 case HMIAction::DISENGAGE:
287 return ChangeDrivingMode(Chassis::COMPLETE_MANUAL);
288 case HMIAction::RESET_MODE:
289 ResetMode();
290 break;
291 case HMIAction::LOAD_SCENARIOS:
292 LoadScenarios();
293 break;
294 case HMIAction::LOAD_DYNAMIC_MODELS:
295 LoadDynamicModels();
296 break;
297 case HMIAction::LOAD_RECORDS:
298 LoadRecords();
299 break;
300 case HMIAction::STOP_RECORD:
301 StopRecordPlay();
302 break;
303 default:
304 AERROR << "HMIAction not implemented, yet!";
305 return false;
306 }
307 return true;
308}
309
310bool HMIWorker::Trigger(const HMIAction action, const std::string &value) {
311 AINFO << "HMIAction " << HMIAction_Name(action) << "(" << value
312 << ") was triggered!";
313 switch (action) {
314 case HMIAction::CHANGE_MODE:
315 ChangeMode(value);
316 break;
317 case HMIAction::CHANGE_MAP:
318 ChangeMap(value);
319 break;
320 case HMIAction::CHANGE_VEHICLE:
321 ChangeVehicle(value);
322 break;
323 case HMIAction::START_MODULE:
324 StartModule(value);
325 break;
326 case HMIAction::STOP_MODULE:
327 StopModule(value);
328 break;
329 case HMIAction::CHANGE_SCENARIO_SET:
330 ChangeScenarioSet(value);
331 break;
332 case HMIAction::DELETE_SCENARIO_SET:
333 DeleteScenarioSet(value);
334 ChangeScenario("");
335 break;
336 case HMIAction::CHANGE_SCENARIO:
337 ChangeScenario(value);
338 break;
339 case HMIAction::CHANGE_DYNAMIC_MODEL:
340 ChangeDynamicModel(value);
341 break;
342 case HMIAction::DELETE_DYNAMIC_MODEL:
343 DeleteDynamicModel(value);
344 break;
345 case HMIAction::DELETE_RECORD:
346 DeleteRecord(value);
347 break;
348 case HMIAction::CHANGE_RECORD:
349 ChangeRecord(value);
350 break;
351 default:
352 AERROR << "HMIAction not implemented, yet!";
353 return false;
354 }
355 return true;
356}
357
358void HMIWorker::SubmitAudioEvent(const uint64_t event_time_ms,
359 const int obstacle_id, const int audio_type,
360 const int moving_result,
361 const int audio_direction,
362 const bool is_siren_on) {
363 std::shared_ptr<AudioEvent> audio_event = std::make_shared<AudioEvent>();
364 apollo::common::util::FillHeader("HMI", audio_event.get());
365 // Here we reuse the header time field as the event occurring time.
366 // A better solution might be adding an event time field to DriveEvent proto
367 // to make it clear.
368 audio_event->mutable_header()->set_timestamp_sec(
369 static_cast<double>(event_time_ms) / 1000.0);
370 audio_event->set_id(obstacle_id);
371 audio_event->set_audio_type(
372 static_cast<apollo::audio::AudioType>(audio_type));
373 audio_event->set_moving_result(
374 static_cast<apollo::audio::MovingResult>(moving_result));
375 audio_event->set_audio_direction(
376 static_cast<apollo::audio::AudioDirection>(audio_direction));
377 audio_event->set_siren_is_on(is_siren_on);
378
379 // Read the current localization pose
380 localization_reader_->Observe();
381 if (localization_reader_->Empty()) {
382 AERROR << "Failed to get localization associated with the audio event: "
383 << audio_event->DebugString() << "\n Localization reader is empty!";
384 return;
385 }
386
387 const std::shared_ptr<LocalizationEstimate> localization =
388 localization_reader_->GetLatestObserved();
389 audio_event->mutable_pose()->CopyFrom(localization->pose());
390 AINFO << "AudioEvent: " << audio_event->DebugString();
391
392 audio_event_writer_->Write(audio_event);
393}
394
395void HMIWorker::SubmitDriveEvent(const uint64_t event_time_ms,
396 const std::string &event_msg,
397 const std::vector<std::string> &event_types,
398 const bool is_reportable) {
399 std::shared_ptr<DriveEvent> drive_event = std::make_shared<DriveEvent>();
400 apollo::common::util::FillHeader("HMI", drive_event.get());
401 // TODO(xiaoxq): Here we reuse the header time field as the event occurring
402 // time. A better solution might be adding the field to DriveEvent proto to
403 // make it clear.
404 drive_event->mutable_header()->set_timestamp_sec(
405 static_cast<double>(event_time_ms) / 1000.0);
406 drive_event->set_event(event_msg);
407 drive_event->set_is_reportable(is_reportable);
408 for (const auto &type_name : event_types) {
409 DriveEvent::Type type;
410 if (DriveEvent::Type_Parse(type_name, &type)) {
411 drive_event->add_type(type);
412 } else {
413 AERROR << "Failed to parse drive event type:" << type_name;
414 }
415 }
416 drive_event_writer_->Write(drive_event);
417}
418
419void HMIWorker::SensorCalibrationPreprocess(const std::string &task_type) {
420 std::string start_command = absl::StrCat(
421 "nohup bash modules/tools/sensor_calibration/extract_data.sh -t ",
422 task_type, " &");
423 System(start_command);
424}
425
426void HMIWorker::VehicleCalibrationPreprocess() {
427 std::string start_command = absl::StrCat(
428 "nohup bash modules/tools/vehicle_calibration/preprocess.sh "
429 "--vehicle_type=\"",
430 status_.current_vehicle(), "\" --record_num=", record_count_, " &");
431 System(start_command);
432}
433
434bool HMIWorker::ChangeDrivingMode(const Chassis::DrivingMode mode) {
435 // Always reset to MANUAL mode before changing to other mode.
436 const std::string mode_name = Chassis::DrivingMode_Name(mode);
437 if (mode != Chassis::COMPLETE_MANUAL) {
438 if (!ChangeDrivingMode(Chassis::COMPLETE_MANUAL)) {
439 AERROR << "Failed to reset to MANUAL before changing to " << mode_name;
440 return false;
441 }
442 }
443
444 auto command = std::make_shared<ActionCommand>();
445
446 switch (mode) {
447 case Chassis::COMPLETE_MANUAL:
448 command->set_command(
450 break;
451 case Chassis::COMPLETE_AUTO_DRIVE:
452 command->set_command(
454 break;
455 default:
456 AFATAL << "Change driving mode to " << mode_name << " not implemented!";
457 return false;
458 }
459
460 static constexpr int kMaxTries = 1;
461 static constexpr auto kTryInterval = std::chrono::milliseconds(500);
462 for (int i = 0; i < kMaxTries; ++i) {
463 // Send driving action periodically until entering target driving mode.
464 common::util::FillHeader("HMI", command.get());
465 // Shorten the timeout period to prevent users from waiting too long
466 action_command_client_->SendRequest(command, std::chrono::seconds(1));
467
468 std::this_thread::sleep_for(kTryInterval);
469
470 chassis_reader_->Observe();
471 if (chassis_reader_->Empty()) {
472 AERROR << "No Chassis message received!";
473 } else if (chassis_reader_->GetLatestObserved()->driving_mode() == mode) {
474 return true;
475 }
476 }
477 AERROR << "Failed to change driving mode to " << mode_name;
478 return false;
479}
480
481bool HMIWorker::ChangeMap(const std::string &map_name,
482 const bool restart_dynamic_model) {
483 if (status_.current_map() == map_name && restart_dynamic_model == false) {
484 return true;
485 }
486 const std::string *map_dir = FindOrNull(config_.maps(), map_name);
487 if (map_dir == nullptr) {
488 AERROR << "Unknown map " << map_name;
489 return false;
490 }
491
492 if (map_name != status_.current_map()) {
493 {
494 // Update current_map status.
495 WLock wlock(status_mutex_);
496 status_.set_current_map(map_name);
497 status_changed_ = true;
498 }
499 SetGlobalFlag("map_dir", *map_dir, &FLAGS_map_dir);
500 ResetMode();
501 }
502
503 // true : restart dynamic model on change map
504 // false : change scenario not restart
505 // 1. 场景切换到空场景
506 // 2. 场景切换到其他地图
507 if (restart_dynamic_model) {
508 callback_api_("RestartDynamicModel", {});
509 // 场景id不为空进行切换地图需要停止sim_obstacle
510 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
511 {
512 WLock wlock(status_mutex_);
513 status_.set_current_scenario_id("");
514 status_changed_ = true;
515 }
516 }
517 return true;
518}
519
520void HMIWorker::UpdateModeModulesAndMonitoredComponents() {
521 status_.clear_modules();
522 for (const auto &iter : current_mode_.modules()) {
523 status_.mutable_modules()->insert({iter.first, false});
524 }
525
526 // Update monitored components of current mode.
527 status_.clear_monitored_components();
528 for (const auto &iter : current_mode_.monitored_components()) {
529 status_.mutable_monitored_components()->insert({iter.first, {}});
530 }
531}
532
533void HMIWorker::ChangeVehicle(const std::string &vehicle_name) {
534 const std::string *vehicle_dir = FindOrNull(config_.vehicles(), vehicle_name);
535 if (vehicle_dir == nullptr) {
536 AERROR << "Unknown vehicle " << vehicle_name;
537 return;
538 }
539 std::string current_mode;
540
541 {
542 // Update current_vehicle status.
543 WLock wlock(status_mutex_);
544 current_mode = status_.current_mode();
545 if (status_.current_vehicle() == vehicle_name) {
546 return;
547 }
548 try {
549 // try to get vehicle type from calibration data directory
550 // TODO(jinping): add vehicle config specs and move to vehicle config
551 const std::string vehicle_type_file_path = *vehicle_dir + "/vehicle_type";
552 std::string vehicle_type_str;
553 cyber::common::GetContent(vehicle_type_file_path, &vehicle_type_str);
554 int vehicle_type = std::stoi(vehicle_type_str);
555 status_.set_current_vehicle_type(vehicle_type);
556 } catch (const std::exception &e) {
557 AWARN << "get vehicle type config failed: " << e.what();
558 status_.clear_current_vehicle_type();
559 }
560 status_.set_current_vehicle(vehicle_name);
561 status_changed_ = true;
562 }
563 ResetMode();
564 // before reset mode
565 HMIMode vehicle_defined_mode;
566 const std::string mode_config_path = config_.modes().at(current_mode);
567 if (LoadVehicleDefinedMode(mode_config_path, *vehicle_dir,
568 &vehicle_defined_mode)) {
569 MergeToCurrentMode(&vehicle_defined_mode);
570 } else {
571 // modules may have been modified the last time selected a vehicle
572 // need to be recovery by load mode
573 current_mode_ = util::HMIUtil::LoadMode(mode_config_path);
574 }
575 {
576 WLock wlock(status_mutex_);
577 UpdateModeModulesAndMonitoredComponents();
578 }
579 ACHECK(VehicleManager::Instance()->UseVehicle(*vehicle_dir));
580 // Restart Fuel Monitor
581 auto *monitors = FuelMonitorManager::Instance()->GetCurrentMonitors();
582 if (monitors != nullptr) {
583 for (const auto &monitor : *monitors) {
584 if (monitor.second->IsEnabled()) {
585 monitor.second->Restart();
586 }
587 }
588 }
589}
590
591void HMIWorker::MergeToCurrentMode(HMIMode *mode) {
592 current_mode_.clear_modules();
593 current_mode_.clear_cyber_modules();
594 current_mode_.clear_monitored_components();
595 current_mode_.mutable_modules()->swap(*(mode->mutable_modules()));
596 current_mode_.mutable_monitored_components()->swap(
597 *(mode->mutable_monitored_components()));
598}
599
600void HMIWorker::ChangeMode(const std::string &mode_name) {
601 if (!ContainsKey(config_.modes(), mode_name)) {
602 AERROR << "Cannot change to unknown mode " << mode_name;
603 return;
604 }
605
606 {
607 RLock rlock(status_mutex_);
608 // Skip if mode doesn't actually change.
609 if (status_.current_mode() == mode_name) {
610 return;
611 }
612 }
613 ResetMode();
614
615 {
616 WLock wlock(status_mutex_);
617 status_.set_current_mode(mode_name);
618 current_mode_ = util::HMIUtil::LoadMode(config_.modes().at(mode_name));
619 // for vehicle self-defined module
620 HMIMode vehicle_defined_mode;
621 const std::string *vehicle_dir =
622 FindOrNull(config_.vehicles(), status_.current_vehicle());
623 if (vehicle_dir != nullptr &&
624 LoadVehicleDefinedMode(config_.modes().at(mode_name), *vehicle_dir,
625 &vehicle_defined_mode)) {
626 MergeToCurrentMode(&vehicle_defined_mode);
627 }
628 UpdateModeModulesAndMonitoredComponents();
629
630 status_.clear_other_components();
631 for (const auto &iter : current_mode_.other_components()) {
632 status_.mutable_other_components()->insert({iter.first, {}});
633 }
634 status_changed_ = true;
635 }
636
637 FuelMonitorManager::Instance()->SetCurrentMode(mode_name);
638 KVDB::Put(FLAGS_current_mode_db_key, mode_name);
639
640 // Toggle Mode Set scenario to empty
641 {
642 WLock wlock(status_mutex_);
643 status_.set_current_scenario_id("");
644 status_changed_ = true;
645 }
646 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
647}
648
649void HMIWorker::StartModule(const std::string &module) const {
650 const Module *module_conf = FindOrNull(current_mode_.modules(), module);
651 if (module_conf != nullptr) {
652 System(module_conf->start_command());
653 } else {
654 AERROR << "Cannot find module " << module;
655 }
656
657 if (module == "Recorder") {
658 auto *monitors = FuelMonitorManager::Instance()->GetCurrentMonitors();
659 if (monitors != nullptr) {
660 auto iter = monitors->find(FLAGS_data_collection_monitor_name);
661 if (iter != monitors->end()) {
662 auto *data_collection_monitor = iter->second.get();
663 if (data_collection_monitor->IsEnabled() && record_count_ == 0) {
664 data_collection_monitor->Restart();
665 }
666 }
667 ++record_count_;
668 }
669 }
670}
671
672void HMIWorker::StopModule(const std::string &module) const {
673 const Module *module_conf = FindOrNull(current_mode_.modules(), module);
674 if (module_conf != nullptr) {
675 System(module_conf->stop_command());
676 } else {
677 AERROR << "Cannot find module " << module;
678 }
679}
680
681HMIStatus HMIWorker::GetStatus() const {
682 RLock rlock(status_mutex_);
683 return status_;
684}
685
686void HMIWorker::SetupMode() const {
687 for (const auto &iter : current_mode_.modules()) {
688 System(iter.second.start_command());
689 }
690}
691
692void HMIWorker::ResetMode() const {
693 for (const auto &iter : current_mode_.modules()) {
694 System(iter.second.stop_command());
695 }
696 record_count_ = 0;
697}
698
699void HMIWorker::StatusUpdateThreadLoop() {
700 constexpr int kLoopIntervalMs = 200;
701 while (!stop_) {
702 std::this_thread::sleep_for(std::chrono::milliseconds(kLoopIntervalMs));
703 UpdateComponentStatus();
704 bool status_changed = false;
705 {
706 WLock wlock(status_mutex_);
707 status_changed = status_changed_;
708 status_changed_ = false;
709 }
710 // If status doesn't change, check if we reached update interval.
711 if (!status_changed) {
712 static double next_update_time = 0;
713 const double now = Clock::NowInSeconds();
714 if (now < next_update_time) {
715 continue;
716 }
717 next_update_time = now + FLAGS_status_publish_interval;
718 }
719
720 // Trigger registered status change handlers.
721 HMIStatus status = GetStatus();
722 for (const auto handler : status_update_handlers_) {
723 handler(status_changed, &status);
724 }
725 }
726}
727
728void HMIWorker::ResetComponentStatusTimer() {
729 last_status_received_s_ = Clock::NowInSeconds();
730 last_status_fingerprint_ = 0;
731}
732
733void HMIWorker::UpdateComponentStatus() {
734 constexpr double kSecondsTillTimeout(2.5);
735 const double now = Clock::NowInSeconds();
736 if (now - last_status_received_s_.load() > kSecondsTillTimeout) {
737 if (!monitor_timed_out_) {
738 WLock wlock(status_mutex_);
739
740 const uint64_t now_ms = static_cast<uint64_t>(now * 2e3);
741 static constexpr bool kIsReportable = true;
742 SubmitDriveEvent(now_ms, "Monitor timed out", {"PROBLEM"}, kIsReportable);
743 AWARN << "System fault. Auto disengage.";
744 Trigger(HMIAction::DISENGAGE);
745
746 for (auto &monitored_component :
747 *status_.mutable_monitored_components()) {
748 monitored_component.second.set_status(ComponentStatus::UNKNOWN);
749 monitored_component.second.set_message(
750 "Status not reported by Monitor.");
751 }
752 status_changed_ = true;
753 }
754 monitor_timed_out_ = true;
755 } else {
756 monitor_timed_out_ = false;
757 }
758}
759
760void HMIWorker::ChangeScenarioSet(const std::string &scenario_set_id) {
761 {
762 RLock rlock(status_mutex_);
763 auto &scenario_set = status_.scenario_set();
764 if ((!scenario_set_id.empty()) &&
765 (scenario_set.find(scenario_set_id) == scenario_set.end())) {
766 AERROR << "Cannot change to unknown scenario set!";
767 return;
768 }
769 if (status_.current_scenario_set_id() == scenario_set_id) {
770 return;
771 }
772 }
773
774 {
775 WLock wlock(status_mutex_);
776 status_.set_current_scenario_set_id(scenario_set_id);
777 status_changed_ = true;
778 }
779 return;
780}
781
782bool HMIWorker::GetScenarioResourcePath(std::string *scenario_resource_path) {
783 CHECK_NOTNULL(scenario_resource_path);
784 const std::string home = cyber::common::GetEnv("HOME");
785 if (home.empty()) {
786 return false;
787 }
788 *scenario_resource_path = home + FLAGS_resource_scenario_path;
789 return true;
790}
791
792bool HMIWorker::GetScenarioSetPath(const std::string &scenario_set_id,
793 std::string *scenario_set_path) {
794 CHECK_NOTNULL(scenario_set_path);
795 if (!GetScenarioResourcePath(scenario_set_path)) {
796 return false;
797 }
798 *scenario_set_path = *scenario_set_path + scenario_set_id;
799 return true;
800}
801
802bool HMIWorker::StopModuleByCommand(const std::string &stop_command) const {
803 int ret = std::system(stop_command.data());
804 if (ret < 0 || !WIFEXITED(ret)) {
805 // 256 does not means failure
806 AERROR << "Failed to stop sim obstacle";
807 return false;
808 }
809 return true;
810}
811
812bool HMIWorker::ResetSimObstacle(const std::string &scenario_id) {
813 bool startObstacle = true;
814 std::string cur_scenario_id;
815 if (scenario_id.empty()) {
816 startObstacle = false;
817 cur_scenario_id = status_.current_scenario_id();
818 } else {
819 cur_scenario_id = scenario_id;
820 }
821
822 std::string absolute_path;
824 FLAGS_sim_obstacle_path, "APOLLO_DISTRIBUTION_HOME", &absolute_path)) {
825 AERROR << "Failed to find agent server from file: " +
826 FLAGS_sim_obstacle_path;
827 return false;
828 }
829
830 // found sim_obstacle binary
831 const std::string command = "which sim_obstacle";
832 std::string result = GetCommandRes(command);
833 if (result != "") {
834 absolute_path = result;
835 } else if (!cyber::common::PathExists(absolute_path)) {
836 AWARN << "Not found sim obstacle";
837 startObstacle = false;
838 }
839 AINFO << "sim_obstacle binary path : " << absolute_path;
840
841 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
842 std::string scenario_set_id;
843 {
844 RLock rlock(status_mutex_);
845 scenario_set_id = status_.current_scenario_set_id();
846 }
847 std::string scenario_set_path;
848 if (!GetScenarioSetPath(scenario_set_id, &scenario_set_path)) {
849 AERROR << "Failed to get scenario set path!";
850 return false;
851 }
852 const std::string scenario_path =
853 scenario_set_path + "/scenarios/" + cur_scenario_id + ".json";
854 AINFO << "scenario path : " << scenario_path;
855 if (!cyber::common::PathExists(scenario_path)) {
856 AERROR << "Failed to find scenario!";
857 return false;
858 }
859 std::string map_name = "";
860 double x;
861 double y;
862 bool need_to_change_map = true;
863 {
864 RLock rlock(status_mutex_);
865 auto &scenario_set = status_.scenario_set();
866 if (scenario_set.find(scenario_set_id) == scenario_set.end()) {
867 AERROR << "Failed to find scenario set!";
868 return false;
869 }
870 for (auto &scenario : scenario_set.at(scenario_set_id).scenarios()) {
871 if (scenario.scenario_id() == cur_scenario_id) {
872 map_name = scenario.map_name();
873 x = scenario.start_point().x();
874 y = scenario.start_point().y();
875 break;
876 }
877 }
878 if (map_name.empty()) {
879 AERROR << "Failed to find scenario and get map dir!";
880 return false;
881 }
882 need_to_change_map = (status_.current_map() != map_name);
883 }
884 // resetmodule before save open modules
885 std::vector<std::string> modules_open;
886 auto modulesMap = status_.modules();
887 for (auto it = modulesMap.begin(); it != modulesMap.end(); ++it) {
888 if (it->second == true) {
889 modules_open.push_back(it->first);
890 }
891 }
892 if (need_to_change_map) {
893 if (!ChangeMap(map_name, false)) {
894 AERROR << "Failed to change map!";
895 return false;
896 }
897 callback_api_("MapServiceReloadMap", {});
898 }
899 // TODO(huanguang): if not changing map don't need to reset module
900 // for (const auto &module : modules_open) {
901 // StartModule(module);
902 // }
903 // After changing the map, reset the start point from the scenario by
904 // sim_control
905 Json info;
906 info["x"] = x;
907 info["y"] = y;
908 callback_api_("SimControlRestart", info);
909 if (startObstacle) {
910 // 启动sim obstacle
911 const std::string start_command = "nohup " + absolute_path + " " +
912 scenario_path + FLAGS_gflag_command_arg +
913 " &";
914 AINFO << "start sim_obstacle command : " << start_command;
915 int ret = std::system(start_command.data());
916 if (ret != 0) {
917 AERROR << "Failed to start sim obstacle";
918 return false;
919 }
920 }
921
922 return true;
923}
924
925std::string HMIWorker::GetCommandRes(const std::string &cmd) {
926 if (cmd.size() > 128) {
927 AERROR << "command size exceeds 128";
928 return "";
929 }
930 const char *cmdPtr = cmd.c_str();
931 char buffer[128];
932 std::string result = "";
933
934 FILE *pipe = popen(cmdPtr, "r");
935 while (fgets(buffer, sizeof(buffer), pipe) != nullptr) {
936 result += buffer;
937 }
938 if (result.back() == '\n') {
939 result.pop_back();
940 }
941 pclose(pipe);
942 return result;
943}
944
945void HMIWorker::ChangeScenario(const std::string &scenario_id) {
946 {
947 RLock rlock(status_mutex_);
948 // Skip if mode doesn't actually change.
949 if (status_.current_scenario_id() == scenario_id) {
950 return;
951 }
952 if (scenario_id.empty()) {
953 // stop sim obstacle
954 // todo: add check status
955 // directly think pkill successful
956 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
957 } else {
958 auto scenario_set = status_.mutable_scenario_set();
959 auto &scenario_set_id = status_.current_scenario_set_id();
960 if (scenario_set->find(scenario_set_id) == scenario_set->end()) {
961 AERROR << "Current scenario set is invalid!";
962 return;
963 }
964 bool find_res = false;
965 for (auto &scenario : (*scenario_set)[scenario_set_id].scenarios()) {
966 if (scenario.scenario_id() == scenario_id) {
967 find_res = true;
968 break;
969 }
970 }
971 if (!find_res) {
972 AERROR << "Cannot change to unknown scenario!";
973 return;
974 }
975 }
976 }
977
978 // restart sim obstacle
979 // move sim obstacle position for rlock wlock together will result to dead
980 // lock
981 if (!ResetSimObstacle(scenario_id)) {
982 AERROR << "Cannot start sim obstacle by new scenario!";
983 return;
984 }
985
986 {
987 WLock wlock(status_mutex_);
988 status_.set_current_scenario_id(scenario_id);
989 status_changed_ = true;
990 }
991 return;
992}
993
994void HMIWorker::ChangeDynamicModel(const std::string &dynamic_model_name) {
995 // To avoid toggle sim control and always choose simulation perfect control
996 // {
997 // RLock rlock(status_mutex_);
998 // // Skip if mode doesn't actually change.
999 // if (status_.current_dynamic_model() == dynamic_model_name) {
1000 // return;
1001 // }
1002 // }
1003 if (dynamic_model_name.empty()) {
1004 AERROR << "Failed to change empty dynamic model!";
1005 return;
1006 }
1007 Json param_json({});
1008 param_json["dynamic_model_name"] = dynamic_model_name;
1009 Json callback_res = callback_api_("ChangeDynamicModel", param_json);
1010 if (!callback_res.contains("result") || !callback_res["result"]) {
1011 // badcase1:sim control is not enabled. badcase2:miss params
1012 // badcase3:change dynamic model is not registered. resolution:return with
1013 // no action,keep sim control not enabled or use original dynamic model!
1014 AERROR << "Failed to change dynamic model! Please check if the param is "
1015 "valid!";
1016 return;
1017 }
1018 std::string current_dynamic_model_name = dynamic_model_name;
1019 {
1020 WLock wlock(status_mutex_);
1021 status_.set_current_dynamic_model(dynamic_model_name);
1022 status_changed_ = true;
1023 }
1024
1025 return;
1026}
1027
1028bool HMIWorker::UpdateScenarioSetToStatus(
1029 const std::string &scenario_set_id, const std::string &scenario_set_name) {
1030 ScenarioSet new_scenario_set;
1031 if (!UpdateScenarioSet(scenario_set_id, scenario_set_name,
1032 &new_scenario_set)) {
1033 AERROR << "Failed to update scenario_set!";
1034 return false;
1035 }
1036 {
1037 WLock wlock(status_mutex_);
1038 auto scenario_set = status_.mutable_scenario_set();
1039 scenario_set->erase(scenario_set_id);
1040 (*scenario_set)[scenario_set_id] = new_scenario_set;
1041 status_changed_ = true;
1042 }
1043 return true;
1044}
1045
1046bool HMIWorker::UpdateDynamicModelToStatus(
1047 const std::string &dynamic_model_name) {
1048 Json param_json({});
1049 param_json["dynamic_model_name"] = dynamic_model_name;
1050 Json callback_res = callback_api_("AddDynamicModel", param_json);
1051 if (!callback_res.contains("result") || !callback_res["result"]) {
1052 AERROR << "Failed to add dynamic model to local dynamic model list for "
1053 "register failed!";
1054 return false;
1055 }
1056 {
1057 WLock wlock(status_mutex_);
1058 for (const auto &iter : status_.dynamic_models()) {
1059 if (iter == dynamic_model_name) {
1060 AERROR << "Do not need to add new dynamic model for is duplicate!";
1061 return true;
1062 }
1063 }
1064 status_.add_dynamic_models(dynamic_model_name);
1065 status_changed_ = true;
1066 }
1067 return true;
1068}
1069
1070bool HMIWorker::UpdateScenarioSet(const std::string &scenario_set_id,
1071 const std::string &scenario_set_name,
1072 ScenarioSet *new_scenario_set) {
1073 std::string scenario_set_directory_path;
1074 if (!GetScenarioSetPath(scenario_set_id, &scenario_set_directory_path)) {
1075 AERROR << "Cannot get scenario set path!";
1076 return false;
1077 }
1078 scenario_set_directory_path = scenario_set_directory_path + "/scenarios/";
1079 new_scenario_set->set_scenario_set_name(scenario_set_name);
1080 if (!cyber::common::PathExists(scenario_set_directory_path)) {
1081 AERROR << "Scenario set has no scenarios!";
1082 return true;
1083 }
1084 DIR *directory = opendir(scenario_set_directory_path.c_str());
1085 if (directory == nullptr) {
1086 AERROR << "Cannot open directory " << scenario_set_directory_path;
1087 return false;
1088 }
1089
1090 struct dirent *file;
1091 while ((file = readdir(directory)) != nullptr) {
1092 // skip directory_path/. and directory_path/..
1093 if (!strcmp(file->d_name, ".") || !strcmp(file->d_name, "..")) {
1094 continue;
1095 }
1096 const std::string file_name = file->d_name;
1097 if (!absl::EndsWith(file_name, ".json")) {
1098 continue;
1099 }
1100 const int index = file_name.rfind(".json");
1101 if (index == 0) {
1102 // name: ".json" is invalid.
1103 continue;
1104 }
1105 const std::string scenario_id = file_name.substr(0, index);
1106 const std::string file_path = scenario_set_directory_path + file_name;
1107 SimTicket new_sim_ticket;
1108 if (!cyber::common::GetProtoFromJsonFile(file_path, &new_sim_ticket)) {
1109 AERROR << "Cannot parse this scenario:" << file_path;
1110 return false;
1111 }
1112 if (!new_sim_ticket.has_scenario()) {
1113 AERROR << "Cannot get scenario.";
1114 return false;
1115 }
1116 if (!new_sim_ticket.description_en_tokens_size()) {
1117 AERROR << "Cannot get scenario name.";
1118 return false;
1119 }
1120 if (!new_sim_ticket.scenario().has_map_dir()) {
1121 AERROR << "Cannot get scenario map dir.";
1122 return false;
1123 }
1124 if (!new_sim_ticket.scenario().has_start()) {
1125 AERROR << "Cannot get scenario start_point.";
1126 return false;
1127 }
1128 auto &scenario_start_point = new_sim_ticket.scenario().start();
1129 if (!scenario_start_point.has_x() || !scenario_start_point.has_y()) {
1130 AERROR << "Scenario start_point is invalid!";
1131 return false;
1132 }
1133 std::string scenario_name = new_sim_ticket.description_en_tokens(0);
1134 for (int i = 1; i < new_sim_ticket.description_en_tokens_size(); i++) {
1135 scenario_name =
1136 scenario_name + "_" + new_sim_ticket.description_en_tokens(i);
1137 }
1138 ScenarioInfo *scenario_info = new_scenario_set->add_scenarios();
1139 scenario_info->set_scenario_id(scenario_id);
1140 scenario_info->set_scenario_name(scenario_name);
1141 // change scenario json map dir to map name
1142 // format:modules/map/data/${map_name}
1143 const std::string map_dir = new_sim_ticket.scenario().map_dir();
1144 size_t idx = map_dir.find_last_of('/');
1145 if (idx == map_dir.npos) {
1146 AERROR << "Cannot get scenario map name.";
1147 return false;
1148 }
1149 const std::string map_name = map_dir.substr(idx + 1);
1150 if (map_name.empty()) {
1151 AERROR << "Cannot get scenario map name.";
1152 return false;
1153 }
1154 // replay engine use xx_xx like:apollo_map
1155 // dv need Apollo Map
1156 scenario_info->set_map_name(util::HMIUtil::TitleCase(map_name));
1157 auto start_point = scenario_info->mutable_start_point();
1158 start_point->set_x(scenario_start_point.x());
1159 start_point->set_y(scenario_start_point.y());
1160 }
1161 closedir(directory);
1162 return true;
1163}
1164
1165bool HMIWorker::LoadScenarios() {
1166 std::string directory_path;
1167 if (!GetScenarioResourcePath(&directory_path)) {
1168 AERROR << "Failed to get scenario resource path!";
1169 return false;
1170 }
1171 if (!cyber::common::PathExists(directory_path)) {
1172 AERROR << "Failed to find scenario_set!";
1173 return false;
1174 }
1175 DIR *directory = opendir(directory_path.c_str());
1176 if (directory == nullptr) {
1177 AERROR << "Cannot open directory " << directory_path;
1178 return false;
1179 }
1180 struct dirent *file;
1181 std::map<std::string, ScenarioSet> scenario_sets;
1182 while ((file = readdir(directory)) != nullptr) {
1183 // skip directory_path/. and directory_path/..
1184 if (!strcmp(file->d_name, ".") || !strcmp(file->d_name, "..")) {
1185 continue;
1186 }
1187 if (file->d_type != DT_DIR) {
1188 continue;
1189 }
1190 const std::string scenario_set_id = file->d_name;
1191 const std::string scenario_set_json_path =
1192 directory_path + scenario_set_id + "/scenario_set.json";
1193 // scenario_set.json use message:UserAdsGroup
1194 UserAdsGroup user_ads_group_info;
1195 if (!cyber::common::GetProtoFromJsonFile(scenario_set_json_path,
1196 &user_ads_group_info)) {
1197 AERROR << "Unable to parse UserAdsGroup from file "
1198 << scenario_set_json_path;
1199 continue;
1200 }
1201 if (!user_ads_group_info.has_name()) {
1202 AERROR << "Failed to get ads group name!";
1203 continue;
1204 }
1205 const std::string scenario_set_name = user_ads_group_info.name();
1206 ScenarioSet new_scenario_set;
1207 if (!UpdateScenarioSet(scenario_set_id, scenario_set_name,
1208 &new_scenario_set)) {
1209 AERROR << "Failed to update scenario_set!";
1210 continue;
1211 }
1212 scenario_sets[scenario_set_id] = new_scenario_set;
1213 }
1214 closedir(directory);
1215 {
1216 WLock wlock(status_mutex_);
1217 auto scenario_set = status_.mutable_scenario_set();
1218 // clear old data
1219 scenario_set->clear();
1220 for (auto iter = scenario_sets.begin(); iter != scenario_sets.end();
1221 iter++) {
1222 (*scenario_set)[iter->first] = iter->second;
1223 }
1224 status_changed_ = true;
1225 }
1226 return true;
1227}
1228
1229bool HMIWorker::LoadDynamicModels() {
1230 Json load_res = callback_api_("LoadDynamicModels", {});
1231 if (!load_res.contains("result") || !load_res["result"]) {
1232 return false;
1233 }
1234
1235 {
1236 WLock wlock(status_mutex_);
1237 auto dynamic_models = status_.mutable_dynamic_models();
1238 // clear old data
1239 for (auto iter = dynamic_models->begin(); iter != dynamic_models->end();) {
1240 iter = dynamic_models->erase(iter);
1241 }
1242 for (const auto &dynamic_model : load_res["loaded_dynamic_models"]) {
1243 status_.add_dynamic_models(dynamic_model);
1244 }
1245 status_changed_ = true;
1246 }
1247 return load_res["result"];
1248}
1249
1250void HMIWorker::DeleteScenarioSet(const std::string &scenario_set_id) {
1251 if (scenario_set_id.empty()) {
1252 return;
1253 }
1254 std::string directory_path;
1255 if (!GetScenarioResourcePath(&directory_path)) {
1256 AERROR << "Failed to get scenario resource path!";
1257 return;
1258 }
1259 // check scenario set id is valid to avoid path traversal
1260 if (scenario_set_id.find('/') != std::string::npos ||
1261 scenario_set_id.find("..") != std::string::npos ||
1262 scenario_set_id.find("~") != std::string::npos ||
1263 scenario_set_id.find(' ') != std::string::npos) {
1264 AERROR << "Scenario set id should not contain '/' ,' ',~ and ..";
1265 return;
1266 }
1267 directory_path = directory_path + scenario_set_id;
1268 if (!cyber::common::PathExists(directory_path)) {
1269 AERROR << "Failed to find scenario_set!";
1270 return;
1271 }
1272 std::string command = "rm -fr " + directory_path;
1273 // use cyber::common::removeFiles do not support sub-directory
1274 // use rmdir do not support not empty directory
1275 if (std::system(command.data()) != 0) {
1276 AERROR << "Failed to delete scenario set directory for: "
1277 << std::strerror(errno);
1278 return;
1279 }
1280
1281 {
1282 RLock rlock(status_mutex_);
1283 auto &scenario_set = status_.scenario_set();
1284 if (scenario_set.find(scenario_set_id) == scenario_set.end()) {
1285 AERROR << "Cannot find unknown scenario set!";
1286 return;
1287 }
1288 // do not allowed remove changed current scenario set
1289 if (scenario_set_id == status_.current_scenario_set_id()) {
1290 AERROR << "Cannotdelete current scenario set!";
1291 return;
1292 }
1293 }
1294
1295 {
1296 WLock wlock(status_mutex_);
1297 status_.mutable_scenario_set()->erase(scenario_set_id);
1298 status_changed_ = true;
1299 }
1300 return;
1301}
1302
1303void HMIWorker::DeleteDynamicModel(const std::string &dynamic_model_name) {
1304 if (dynamic_model_name.empty()) {
1305 AERROR << "Invalid param:empty dynamic model name!";
1306 return;
1307 }
1308 {
1309 RLock rlock(status_mutex_);
1310 // do not allowed remove changed current dynamic model
1311 if (dynamic_model_name == status_.current_dynamic_model()) {
1312 AERROR << "Cannot delete current dynamic model!";
1313 return;
1314 }
1315 if (dynamic_model_name == FLAGS_sim_perfect_control) {
1316 AERROR << "Cannot delete default sim control:SimPerfectControl!";
1317 return;
1318 }
1319 }
1320 Json param_json({});
1321 param_json["dynamic_model_name"] = dynamic_model_name;
1322 Json callback_res = callback_api_("DeleteDynamicModel", param_json);
1323 if (!callback_res.contains("result") || !callback_res["result"]) {
1324 // badcase1: sim control is not enable. badcase2: miss param
1325 // badcase3: Failed to delete file
1326 AERROR << "Failed to delete dynamic model!";
1327 return;
1328 }
1329 {
1330 WLock wlock(status_mutex_);
1331 auto iter = status_.dynamic_models().begin();
1332 while (iter != status_.dynamic_models().end()) {
1333 if (*iter == dynamic_model_name) {
1334 break;
1335 }
1336 iter++;
1337 }
1338 if (iter != status_.dynamic_models().end()) {
1339 status_.mutable_dynamic_models()->erase(iter);
1340 status_changed_ = true;
1341 } else {
1342 AWARN << "Can not find dynamic model to delete!";
1343 }
1344 }
1345 return;
1346}
1347
1348bool HMIWorker::GetRecordPath(std::string *record_path) {
1349 CHECK_NOTNULL(record_path);
1350 const std::string home = cyber::common::GetEnv("HOME");
1351 if (home.empty()) {
1352 // Failed to get environment variable HOME
1353 return false;
1354 }
1355 *record_path = home + FLAGS_resource_record_path;
1356 return true;
1357}
1358
1359bool HMIWorker::RePlayRecord(const std::string &record_id) {
1360 std::string record_path;
1361 if (!GetRecordPath(&record_path)) {
1362 AERROR << "Failed to get record path!";
1363 return false;
1364 }
1365 record_path = record_path + record_id + ".record";
1366
1367 if (!cyber::common::PathExists(record_path)) {
1368 AERROR << "Failed to find record!";
1369 return false;
1370 }
1371 // play the record
1372 const std::string play_command =
1373 absl::StrCat("nohup cyber_recorder play -l -f ", record_path, " &");
1374 int ret = std::system(play_command.data());
1375 if (ret != 0) {
1376 AERROR << "Failed to start cyber play command";
1377 return false;
1378 }
1379 return true;
1380}
1381void HMIWorker::StopRecordPlay() {
1382 WLock wlock(status_mutex_);
1383 { status_.set_current_record_id(""); }
1384 if (!StopModuleByCommand(FLAGS_cyber_recorder_stop_command)) {
1385 AERROR << "stop record failed";
1386 }
1387 status_changed_ = true;
1388}
1389void HMIWorker::ChangeRecord(const std::string &record_id) {
1390 StopRecordPlay();
1391 {
1392 RLock rlock(status_mutex_);
1393 auto status_records = status_.mutable_records();
1394 if (status_records->find(record_id) == status_records->end()) {
1395 AERROR << "Cannot change to unknown record!";
1396 return;
1397 }
1398 if (!RePlayRecord(record_id)) {
1399 return;
1400 }
1401 }
1402 WLock wlock(status_mutex_);
1403 status_.set_current_record_id(record_id);
1404 status_changed_ = true;
1405 return;
1406}
1407bool HMIWorker::LoadRecords() {
1408 std::string directory_path;
1409 if (!GetRecordPath(&directory_path)) {
1410 AERROR << "Failed to get record path!";
1411 return false;
1412 }
1413 if (!cyber::common::PathExists(directory_path)) {
1414 AERROR << "Failed to find records!";
1415 return false;
1416 }
1417 DIR *directory = opendir(directory_path.c_str());
1418 if (directory == nullptr) {
1419 AERROR << "Cannot open record directory" << directory_path;
1420 return false;
1421 }
1422 struct dirent *file;
1423 std::map<std::string, LoadRecordInfo> new_records;
1424 while ((file = readdir(directory)) != nullptr) {
1425 if (!strcmp(file->d_name, ".") || !strcmp(file->d_name, "..")) {
1426 continue;
1427 }
1428 if (file->d_type == DT_DIR) {
1429 continue;
1430 }
1431 const std::string record_id = file->d_name;
1432 const int index = record_id.rfind(".record");
1433 // Skip format that dv cannot parse: record not ending in record
1434 size_t record_suffix_length = 7;
1435 if (record_id.length() - index != record_suffix_length) {
1436 continue;
1437 }
1438 if (index != -1 && record_id[0] != '.') {
1439 const std::string local_record_resource = record_id.substr(0, index);
1440 // compatible records with dv and dv_plus
1441 new_records[local_record_resource] = {};
1442 new_records[local_record_resource].set_download_status(1);
1443 }
1444 }
1445 closedir(directory);
1446 {
1447 WLock wlock(status_mutex_);
1448 auto status_records = status_.mutable_records();
1449 status_records->clear();
1450 for (auto iter = new_records.begin(); iter != new_records.end(); iter++) {
1451 (*status_records)[iter->first] = iter->second;
1452 }
1453 status_changed_ = true;
1454 }
1455 return true;
1456}
1457
1458void HMIWorker::DeleteRecord(const std::string &record_id) {
1459 StopRecordPlay();
1460 if (record_id.empty()) {
1461 return;
1462 }
1463 std::string record_path;
1464 if (!GetRecordPath(&record_path)) {
1465 AERROR << "Failed to get record path!";
1466 return;
1467 }
1468 // check record id for security
1469 if (record_id.find('/') != std::string::npos ||
1470 record_id.find("..") != std::string::npos ||
1471 record_id.find(' ') != std::string::npos ||
1472 record_id.find("~") != std::string::npos) {
1473 AERROR << "Record id should not contain '/' ,' ',~ and ..";
1474 return;
1475 }
1476 record_path = record_path + record_id + ".record";
1477 if (!cyber::common::PathExists(record_path)) {
1478 return;
1479 }
1480 // find the delete record if exist and judge the record whether playing now
1481 {
1482 RLock rlock(status_mutex_);
1483 auto &status_records = status_.records();
1484 if (status_records.find(record_id) == status_records.end()) {
1485 return;
1486 }
1487 if (record_id == status_.current_record_id()) {
1488 return;
1489 }
1490 }
1491 {
1492 WLock wlock(status_mutex_);
1493 status_.mutable_records()->erase(record_id);
1494 status_changed_ = true;
1495 }
1496
1497 // delete record from disk
1498 std::string command = "rm -rf " + record_path;
1499 if (std::system(command.data()) != 0) {
1500 AERROR << "Failed to delete record for: " << std::strerror(errno);
1501 return;
1502 }
1503 return;
1504}
1505bool HMIWorker::ReloadVehicles() {
1506 AINFO << "load config";
1507 HMIConfig config = util::HMIUtil::LoadConfig(FLAGS_dv_hmi_modes_config_path);
1508 std::string msg;
1509 AINFO << "serialize new config";
1510 config.SerializeToString(&msg);
1511
1512 WLock wlock(status_mutex_);
1513 AINFO << "parse new config";
1514 config_.ParseFromString(msg);
1515 AINFO << "init status";
1516 // status_.clear_modes();
1517 // status_.clear_maps();
1518 AINFO << "clear vehicles";
1519 status_.clear_vehicles();
1520 // InitStatus();
1521 // Populate vehicles and current_vehicle.
1522 AINFO << "reload vehicles";
1523 for (const auto &vehicle : config_.vehicles()) {
1524 status_.add_vehicles(vehicle.first);
1525 }
1526 status_changed_ = true;
1527 return true;
1528}
1529
1530void HMIWorker::UpdateCameraSensorChannelToStatus(
1531 const std::string &channel_name) {
1532 {
1533 WLock wlock(status_mutex_);
1534 if (status_.current_camera_sensor_channel() == channel_name) {
1535 AINFO << "Input channel name is current camera sensor channel";
1536 return;
1537 }
1538 status_.set_current_camera_sensor_channel(channel_name);
1539 status_changed_ = true;
1540 }
1541}
1542
1543void HMIWorker::UpdatePointCloudChannelToStatus(
1544 const std::string &channel_name) {
1545 {
1546 WLock wlock(status_mutex_);
1547 if (status_.current_point_cloud_channel() == channel_name) {
1548 AINFO << "Input channel name is current camera sensor channel";
1549 return;
1550 }
1551 status_.set_current_point_cloud_channel(channel_name);
1552 status_changed_ = true;
1553 }
1554}
1555} // namespace dreamview
1556} // namespace apollo
Lightweight key-value database to store system-wide parameters.
Definition kv_db.h:39
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
Node is the fundamental building block of Cyber RT.
Definition node.h:44
std::function< nlohmann::json(const std::string &function_name, const nlohmann::json &param_json)> DvCallback
Definition hmi_worker.h:59
#define ACHECK(cond)
Definition log.h:80
#define AERROR
Definition log.h:44
#define AERROR_IF(cond)
Definition log.h:74
#define AFATAL
Definition log.h:45
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
Some map util functions.
Some string util functions.
nlohmann::json Json
size_t MessageFingerprint(const google::protobuf::Message &message)
bool GetFilePathWithEnv(const std::string &path, const std::string &env_var, std::string *file_path)
get file path, judgement priority:
Definition file.cc:436
bool LoadConfig(const std::string &relative_path, T *config)
Definition file.h:265
boost::shared_lock< boost::shared_mutex > RLock
boost::unique_lock< boost::shared_mutex > WLock
class register implement
Definition arena_queue.h:37
repeated string description_en_tokens
optional apollo::simulation::Scenario scenario