19#include "absl/strings/str_cat.h"
20#include "absl/strings/str_join.h"
21#include "absl/strings/str_split.h"
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"
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;
67constexpr char kNavigationModeName[] =
"Navigation";
69template <
class FlagType,
class ValueType>
70void SetGlobalFlag(std::string_view flag_name,
const ValueType &value,
73 constexpr char kGlobalFlagfile[] =
"modules/common/data/global_flagfile.txt";
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;
83void System(std::string_view cmd) {
84 const int ret = std::system(cmd.data());
86 AINFO <<
"SUCCESS: " << cmd;
88 AERROR <<
"FAILED(" << ret <<
"): " << cmd;
95 : config_(util::HMIUtil::
LoadConfig(FLAGS_dv_hmi_modes_config_path)),
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();
109 ResetComponentStatusTimer();
110 thread_future_ = cyber::Async(&HMIWorker::StatusUpdateThreadLoop,
this);
113void HMIWorker::Stop() {
115 if (thread_future_.valid()) {
116 thread_future_.get();
120bool HMIWorker::LoadVehicleDefinedMode(
const std::string &mode_config_path,
121 const std::string ¤t_vehicle_path,
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)) {
130 ACHECK(cyber::common::GetProtoFromFile(vehicle_mode_config_path,
132 <<
"Unable to parse vehicle self defined HMIMode from file "
133 << vehicle_mode_config_path;
134 util::HMIUtil::TranslateCyberModules(self_defined_mode);
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);
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"));
163 for (
const auto &map_entry : config_.maps()) {
164 status_.add_maps(map_entry.first);
167 if (map_entry.second == FLAGS_map_dir) {
168 status_.set_current_map(map_entry.first);
173 for (
const auto &vehicle : config_.vehicles()) {
174 status_.add_vehicles(vehicle.first);
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);
191 ChangeMode(modes.begin()->first);
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);
207 node_->CreateReader<SystemStatus>(
208 FLAGS_system_status_topic,
209 [
this](
const std::shared_ptr<SystemStatus> &system_status) {
210 this->ResetComponentStatusTimer();
212 WLock wlock(status_mutex_);
214 const bool is_realtime_msg =
216 ? system_status->is_realtime_in_simulation()
218 system_status->header().timestamp_sec() <
219 FLAGS_system_status_lifetime_seconds;
221 if (is_realtime_msg) {
222 for (
auto &iter : *status_.mutable_modules()) {
223 auto *status = FindOrNull(system_status->hmi_modules(), iter.first);
225 status !=
nullptr && status->status() == ComponentStatus::OK;
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();
234 iter.second.set_status(ComponentStatus::UNKNOWN);
235 iter.second.set_message(
"Status not reported by Monitor.");
240 for (
auto &iter : *status_.mutable_other_components()) {
242 FindOrNull(system_status->other_components(), iter.first);
243 if (status !=
nullptr) {
244 iter.second.CopyFrom(*status);
246 iter.second.set_status(ComponentStatus::UNKNOWN);
247 iter.second.set_message(
"Status not reported by Monitor.");
252 const size_t new_fingerprint =
254 if (last_status_fingerprint_ != new_fingerprint) {
255 status_changed_ =
true;
256 last_status_fingerprint_ = new_fingerprint;
260 localization_reader_ =
261 node_->CreateReader<LocalizationEstimate>(FLAGS_localization_topic);
263 chassis_reader_ = node_->CreateReader<Chassis>(
264 FLAGS_chassis_topic, [
this](
const std::shared_ptr<Chassis> &chassis) {
266 FLAGS_system_status_lifetime_seconds) {
267 if (chassis->signal().high_beam()) {
269 const bool ret = Trigger(HMIAction::NONE);
270 AERROR_IF(!ret) <<
"Failed to execute high_beam action.";
277 AERROR <<
"HMIAction " << HMIAction_Name(action) <<
" was triggered!";
279 case HMIAction::NONE:
281 case HMIAction::SETUP_MODE:
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:
291 case HMIAction::LOAD_SCENARIOS:
294 case HMIAction::LOAD_DYNAMIC_MODELS:
297 case HMIAction::LOAD_RECORDS:
300 case HMIAction::STOP_RECORD:
304 AERROR <<
"HMIAction not implemented, yet!";
310bool HMIWorker::Trigger(
const HMIAction action,
const std::string &value) {
311 AINFO <<
"HMIAction " << HMIAction_Name(action) <<
"(" << value
312 <<
") was triggered!";
314 case HMIAction::CHANGE_MODE:
317 case HMIAction::CHANGE_MAP:
320 case HMIAction::CHANGE_VEHICLE:
321 ChangeVehicle(value);
323 case HMIAction::START_MODULE:
326 case HMIAction::STOP_MODULE:
329 case HMIAction::CHANGE_SCENARIO_SET:
330 ChangeScenarioSet(value);
332 case HMIAction::DELETE_SCENARIO_SET:
333 DeleteScenarioSet(value);
336 case HMIAction::CHANGE_SCENARIO:
337 ChangeScenario(value);
339 case HMIAction::CHANGE_DYNAMIC_MODEL:
340 ChangeDynamicModel(value);
342 case HMIAction::DELETE_DYNAMIC_MODEL:
343 DeleteDynamicModel(value);
345 case HMIAction::DELETE_RECORD:
348 case HMIAction::CHANGE_RECORD:
352 AERROR <<
"HMIAction not implemented, yet!";
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());
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(
373 audio_event->set_moving_result(
375 audio_event->set_audio_direction(
377 audio_event->set_siren_is_on(is_siren_on);
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!";
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();
392 audio_event_writer_->Write(audio_event);
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());
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) {
410 if (DriveEvent::Type_Parse(type_name, &type)) {
411 drive_event->add_type(type);
413 AERROR <<
"Failed to parse drive event type:" << type_name;
416 drive_event_writer_->Write(drive_event);
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 ",
423 System(start_command);
426void HMIWorker::VehicleCalibrationPreprocess() {
427 std::string start_command = absl::StrCat(
428 "nohup bash modules/tools/vehicle_calibration/preprocess.sh "
430 status_.current_vehicle(),
"\" --record_num=", record_count_,
" &");
431 System(start_command);
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;
444 auto command = std::make_shared<ActionCommand>();
447 case Chassis::COMPLETE_MANUAL:
448 command->set_command(
451 case Chassis::COMPLETE_AUTO_DRIVE:
452 command->set_command(
456 AFATAL <<
"Change driving mode to " << mode_name <<
" not implemented!";
460 static constexpr int kMaxTries = 1;
461 static constexpr auto kTryInterval = std::chrono::milliseconds(500);
462 for (
int i = 0; i < kMaxTries; ++i) {
464 common::util::FillHeader(
"HMI", command.get());
466 action_command_client_->SendRequest(command, std::chrono::seconds(1));
468 std::this_thread::sleep_for(kTryInterval);
470 chassis_reader_->Observe();
471 if (chassis_reader_->Empty()) {
472 AERROR <<
"No Chassis message received!";
473 }
else if (chassis_reader_->GetLatestObserved()->driving_mode() == mode) {
477 AERROR <<
"Failed to change driving mode to " << mode_name;
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) {
486 const std::string *map_dir = FindOrNull(config_.maps(), map_name);
487 if (map_dir ==
nullptr) {
488 AERROR <<
"Unknown map " << map_name;
492 if (map_name != status_.current_map()) {
495 WLock wlock(status_mutex_);
496 status_.set_current_map(map_name);
497 status_changed_ =
true;
499 SetGlobalFlag(
"map_dir", *map_dir, &FLAGS_map_dir);
507 if (restart_dynamic_model) {
508 callback_api_(
"RestartDynamicModel", {});
510 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
512 WLock wlock(status_mutex_);
513 status_.set_current_scenario_id(
"");
514 status_changed_ =
true;
520void HMIWorker::UpdateModeModulesAndMonitoredComponents() {
521 status_.clear_modules();
522 for (
const auto &iter : current_mode_.
modules()) {
523 status_.mutable_modules()->insert({iter.first,
false});
527 status_.clear_monitored_components();
528 for (
const auto &iter : current_mode_.monitored_components()) {
529 status_.mutable_monitored_components()->insert({iter.first, {}});
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;
539 std::string current_mode;
543 WLock wlock(status_mutex_);
544 current_mode = status_.current_mode();
545 if (status_.current_vehicle() == vehicle_name) {
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();
560 status_.set_current_vehicle(vehicle_name);
561 status_changed_ =
true;
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);
573 current_mode_ = util::HMIUtil::LoadMode(mode_config_path);
576 WLock wlock(status_mutex_);
577 UpdateModeModulesAndMonitoredComponents();
579 ACHECK(VehicleManager::Instance()->UseVehicle(*vehicle_dir));
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();
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()));
600void HMIWorker::ChangeMode(
const std::string &mode_name) {
601 if (!ContainsKey(config_.modes(), mode_name)) {
602 AERROR <<
"Cannot change to unknown mode " << mode_name;
607 RLock rlock(status_mutex_);
609 if (status_.current_mode() == mode_name) {
616 WLock wlock(status_mutex_);
617 status_.set_current_mode(mode_name);
618 current_mode_ = util::HMIUtil::LoadMode(config_.modes().at(mode_name));
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);
628 UpdateModeModulesAndMonitoredComponents();
630 status_.clear_other_components();
631 for (
const auto &iter : current_mode_.other_components()) {
632 status_.mutable_other_components()->insert({iter.first, {}});
634 status_changed_ =
true;
637 FuelMonitorManager::Instance()->SetCurrentMode(mode_name);
638 KVDB::Put(FLAGS_current_mode_db_key, mode_name);
642 WLock wlock(status_mutex_);
643 status_.set_current_scenario_id(
"");
644 status_changed_ =
true;
646 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
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());
654 AERROR <<
"Cannot find module " <<
module;
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();
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());
677 AERROR <<
"Cannot find module " <<
module;
681HMIStatus HMIWorker::GetStatus()
const {
682 RLock rlock(status_mutex_);
686void HMIWorker::SetupMode()
const {
687 for (
const auto &iter : current_mode_.
modules()) {
688 System(iter.second.start_command());
692void HMIWorker::ResetMode()
const {
693 for (
const auto &iter : current_mode_.
modules()) {
694 System(iter.second.stop_command());
699void HMIWorker::StatusUpdateThreadLoop() {
700 constexpr int kLoopIntervalMs = 200;
702 std::this_thread::sleep_for(std::chrono::milliseconds(kLoopIntervalMs));
703 UpdateComponentStatus();
704 bool status_changed =
false;
706 WLock wlock(status_mutex_);
707 status_changed = status_changed_;
708 status_changed_ =
false;
711 if (!status_changed) {
712 static double next_update_time = 0;
714 if (now < next_update_time) {
717 next_update_time = now + FLAGS_status_publish_interval;
721 HMIStatus status = GetStatus();
722 for (
const auto handler : status_update_handlers_) {
723 handler(status_changed, &status);
728void HMIWorker::ResetComponentStatusTimer() {
730 last_status_fingerprint_ = 0;
733void HMIWorker::UpdateComponentStatus() {
734 constexpr double kSecondsTillTimeout(2.5);
736 if (now - last_status_received_s_.load() > kSecondsTillTimeout) {
737 if (!monitor_timed_out_) {
738 WLock wlock(status_mutex_);
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);
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.");
752 status_changed_ =
true;
754 monitor_timed_out_ =
true;
756 monitor_timed_out_ =
false;
760void HMIWorker::ChangeScenarioSet(
const std::string &scenario_set_id) {
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!";
769 if (status_.current_scenario_set_id() == scenario_set_id) {
775 WLock wlock(status_mutex_);
776 status_.set_current_scenario_set_id(scenario_set_id);
777 status_changed_ =
true;
782bool HMIWorker::GetScenarioResourcePath(std::string *scenario_resource_path) {
783 CHECK_NOTNULL(scenario_resource_path);
784 const std::string home = cyber::common::GetEnv(
"HOME");
788 *scenario_resource_path = home + FLAGS_resource_scenario_path;
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)) {
798 *scenario_set_path = *scenario_set_path + scenario_set_id;
802bool HMIWorker::StopModuleByCommand(
const std::string &stop_command)
const {
803 int ret = std::system(stop_command.data());
804 if (ret < 0 || !WIFEXITED(ret)) {
806 AERROR <<
"Failed to stop sim obstacle";
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();
819 cur_scenario_id = scenario_id;
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;
831 const std::string command =
"which sim_obstacle";
832 std::string result = GetCommandRes(command);
834 absolute_path = result;
835 }
else if (!cyber::common::PathExists(absolute_path)) {
836 AWARN <<
"Not found sim obstacle";
837 startObstacle =
false;
839 AINFO <<
"sim_obstacle binary path : " << absolute_path;
841 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
842 std::string scenario_set_id;
844 RLock rlock(status_mutex_);
845 scenario_set_id = status_.current_scenario_set_id();
847 std::string scenario_set_path;
848 if (!GetScenarioSetPath(scenario_set_id, &scenario_set_path)) {
849 AERROR <<
"Failed to get scenario set path!";
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!";
859 std::string map_name =
"";
862 bool need_to_change_map =
true;
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!";
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();
878 if (map_name.empty()) {
879 AERROR <<
"Failed to find scenario and get map dir!";
882 need_to_change_map = (status_.current_map() != map_name);
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);
892 if (need_to_change_map) {
893 if (!ChangeMap(map_name,
false)) {
894 AERROR <<
"Failed to change map!";
897 callback_api_(
"MapServiceReloadMap", {});
908 callback_api_(
"SimControlRestart", info);
911 const std::string start_command =
"nohup " + absolute_path +
" " +
912 scenario_path + FLAGS_gflag_command_arg +
914 AINFO <<
"start sim_obstacle command : " << start_command;
915 int ret = std::system(start_command.data());
917 AERROR <<
"Failed to start sim obstacle";
925std::string HMIWorker::GetCommandRes(
const std::string &cmd) {
926 if (cmd.size() > 128) {
927 AERROR <<
"command size exceeds 128";
930 const char *cmdPtr = cmd.c_str();
932 std::string result =
"";
934 FILE *pipe = popen(cmdPtr,
"r");
935 while (fgets(buffer,
sizeof(buffer), pipe) !=
nullptr) {
938 if (result.back() ==
'\n') {
945void HMIWorker::ChangeScenario(
const std::string &scenario_id) {
947 RLock rlock(status_mutex_);
949 if (status_.current_scenario_id() == scenario_id) {
952 if (scenario_id.empty()) {
956 StopModuleByCommand(FLAGS_sim_obstacle_stop_command);
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!";
964 bool find_res =
false;
965 for (
auto &scenario : (*scenario_set)[scenario_set_id].scenarios()) {
966 if (scenario.scenario_id() == scenario_id) {
972 AERROR <<
"Cannot change to unknown scenario!";
981 if (!ResetSimObstacle(scenario_id)) {
982 AERROR <<
"Cannot start sim obstacle by new scenario!";
987 WLock wlock(status_mutex_);
988 status_.set_current_scenario_id(scenario_id);
989 status_changed_ =
true;
994void HMIWorker::ChangeDynamicModel(
const std::string &dynamic_model_name) {
1003 if (dynamic_model_name.empty()) {
1004 AERROR <<
"Failed to change empty dynamic model!";
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"]) {
1014 AERROR <<
"Failed to change dynamic model! Please check if the param is "
1018 std::string current_dynamic_model_name = dynamic_model_name;
1020 WLock wlock(status_mutex_);
1021 status_.set_current_dynamic_model(dynamic_model_name);
1022 status_changed_ =
true;
1028bool HMIWorker::UpdateScenarioSetToStatus(
1029 const std::string &scenario_set_id,
const std::string &scenario_set_name) {
1031 if (!UpdateScenarioSet(scenario_set_id, scenario_set_name,
1032 &new_scenario_set)) {
1033 AERROR <<
"Failed to update scenario_set!";
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;
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 "
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!";
1064 status_.add_dynamic_models(dynamic_model_name);
1065 status_changed_ =
true;
1070bool HMIWorker::UpdateScenarioSet(
const std::string &scenario_set_id,
1071 const std::string &scenario_set_name,
1073 std::string scenario_set_directory_path;
1074 if (!GetScenarioSetPath(scenario_set_id, &scenario_set_directory_path)) {
1075 AERROR <<
"Cannot get scenario set path!";
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!";
1084 DIR *directory = opendir(scenario_set_directory_path.c_str());
1085 if (directory ==
nullptr) {
1086 AERROR <<
"Cannot open directory " << scenario_set_directory_path;
1090 struct dirent *file;
1091 while ((file = readdir(directory)) !=
nullptr) {
1093 if (!strcmp(file->d_name,
".") || !strcmp(file->d_name,
"..")) {
1096 const std::string file_name = file->d_name;
1097 if (!absl::EndsWith(file_name,
".json")) {
1100 const int index = file_name.rfind(
".json");
1105 const std::string scenario_id = file_name.substr(0, index);
1106 const std::string file_path = scenario_set_directory_path + file_name;
1108 if (!cyber::common::GetProtoFromJsonFile(file_path, &new_sim_ticket)) {
1109 AERROR <<
"Cannot parse this scenario:" << file_path;
1112 if (!new_sim_ticket.has_scenario()) {
1113 AERROR <<
"Cannot get scenario.";
1116 if (!new_sim_ticket.description_en_tokens_size()) {
1117 AERROR <<
"Cannot get scenario name.";
1120 if (!new_sim_ticket.
scenario().has_map_dir()) {
1121 AERROR <<
"Cannot get scenario map dir.";
1124 if (!new_sim_ticket.
scenario().has_start()) {
1125 AERROR <<
"Cannot get scenario start_point.";
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!";
1134 for (
int i = 1; i < new_sim_ticket.description_en_tokens_size(); i++) {
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);
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.";
1149 const std::string map_name = map_dir.substr(idx + 1);
1150 if (map_name.empty()) {
1151 AERROR <<
"Cannot get scenario map name.";
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());
1161 closedir(directory);
1165bool HMIWorker::LoadScenarios() {
1166 std::string directory_path;
1167 if (!GetScenarioResourcePath(&directory_path)) {
1168 AERROR <<
"Failed to get scenario resource path!";
1171 if (!cyber::common::PathExists(directory_path)) {
1172 AERROR <<
"Failed to find scenario_set!";
1175 DIR *directory = opendir(directory_path.c_str());
1176 if (directory ==
nullptr) {
1177 AERROR <<
"Cannot open directory " << directory_path;
1180 struct dirent *file;
1181 std::map<std::string, ScenarioSet> scenario_sets;
1182 while ((file = readdir(directory)) !=
nullptr) {
1184 if (!strcmp(file->d_name,
".") || !strcmp(file->d_name,
"..")) {
1187 if (file->d_type != DT_DIR) {
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";
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;
1201 if (!user_ads_group_info.has_name()) {
1202 AERROR <<
"Failed to get ads group name!";
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!";
1212 scenario_sets[scenario_set_id] = new_scenario_set;
1214 closedir(directory);
1216 WLock wlock(status_mutex_);
1217 auto scenario_set = status_.mutable_scenario_set();
1219 scenario_set->clear();
1220 for (
auto iter = scenario_sets.begin(); iter != scenario_sets.end();
1222 (*scenario_set)[iter->first] = iter->second;
1224 status_changed_ =
true;
1229bool HMIWorker::LoadDynamicModels() {
1230 Json load_res = callback_api_(
"LoadDynamicModels", {});
1231 if (!load_res.contains(
"result") || !load_res[
"result"]) {
1236 WLock wlock(status_mutex_);
1237 auto dynamic_models = status_.mutable_dynamic_models();
1239 for (
auto iter = dynamic_models->begin(); iter != dynamic_models->end();) {
1240 iter = dynamic_models->erase(iter);
1242 for (
const auto &dynamic_model : load_res[
"loaded_dynamic_models"]) {
1243 status_.add_dynamic_models(dynamic_model);
1245 status_changed_ =
true;
1247 return load_res[
"result"];
1250void HMIWorker::DeleteScenarioSet(
const std::string &scenario_set_id) {
1251 if (scenario_set_id.empty()) {
1254 std::string directory_path;
1255 if (!GetScenarioResourcePath(&directory_path)) {
1256 AERROR <<
"Failed to get scenario resource path!";
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 ..";
1267 directory_path = directory_path + scenario_set_id;
1268 if (!cyber::common::PathExists(directory_path)) {
1269 AERROR <<
"Failed to find scenario_set!";
1272 std::string command =
"rm -fr " + directory_path;
1275 if (std::system(command.data()) != 0) {
1276 AERROR <<
"Failed to delete scenario set directory for: "
1277 << std::strerror(errno);
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!";
1289 if (scenario_set_id == status_.current_scenario_set_id()) {
1290 AERROR <<
"Cannotdelete current scenario set!";
1296 WLock wlock(status_mutex_);
1297 status_.mutable_scenario_set()->erase(scenario_set_id);
1298 status_changed_ =
true;
1303void HMIWorker::DeleteDynamicModel(
const std::string &dynamic_model_name) {
1304 if (dynamic_model_name.empty()) {
1305 AERROR <<
"Invalid param:empty dynamic model name!";
1309 RLock rlock(status_mutex_);
1311 if (dynamic_model_name == status_.current_dynamic_model()) {
1312 AERROR <<
"Cannot delete current dynamic model!";
1315 if (dynamic_model_name == FLAGS_sim_perfect_control) {
1316 AERROR <<
"Cannot delete default sim control:SimPerfectControl!";
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"]) {
1326 AERROR <<
"Failed to delete dynamic model!";
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) {
1338 if (iter != status_.dynamic_models().end()) {
1339 status_.mutable_dynamic_models()->erase(iter);
1340 status_changed_ =
true;
1342 AWARN <<
"Can not find dynamic model to delete!";
1348bool HMIWorker::GetRecordPath(std::string *record_path) {
1349 CHECK_NOTNULL(record_path);
1350 const std::string home = cyber::common::GetEnv(
"HOME");
1355 *record_path = home + FLAGS_resource_record_path;
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!";
1365 record_path = record_path + record_id +
".record";
1367 if (!cyber::common::PathExists(record_path)) {
1368 AERROR <<
"Failed to find 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());
1376 AERROR <<
"Failed to start cyber play command";
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";
1387 status_changed_ =
true;
1389void HMIWorker::ChangeRecord(
const std::string &record_id) {
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!";
1398 if (!RePlayRecord(record_id)) {
1402 WLock wlock(status_mutex_);
1403 status_.set_current_record_id(record_id);
1404 status_changed_ =
true;
1407bool HMIWorker::LoadRecords() {
1408 std::string directory_path;
1409 if (!GetRecordPath(&directory_path)) {
1410 AERROR <<
"Failed to get record path!";
1413 if (!cyber::common::PathExists(directory_path)) {
1414 AERROR <<
"Failed to find records!";
1417 DIR *directory = opendir(directory_path.c_str());
1418 if (directory ==
nullptr) {
1419 AERROR <<
"Cannot open record directory" << directory_path;
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,
"..")) {
1428 if (file->d_type == DT_DIR) {
1431 const std::string record_id = file->d_name;
1432 const int index = record_id.rfind(
".record");
1434 size_t record_suffix_length = 7;
1435 if (record_id.length() - index != record_suffix_length) {
1438 if (index != -1 && record_id[0] !=
'.') {
1439 const std::string local_record_resource = record_id.substr(0, index);
1441 new_records[local_record_resource] = {};
1442 new_records[local_record_resource].set_download_status(1);
1445 closedir(directory);
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;
1453 status_changed_ =
true;
1458void HMIWorker::DeleteRecord(
const std::string &record_id) {
1460 if (record_id.empty()) {
1463 std::string record_path;
1464 if (!GetRecordPath(&record_path)) {
1465 AERROR <<
"Failed to get record path!";
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 ..";
1476 record_path = record_path + record_id +
".record";
1477 if (!cyber::common::PathExists(record_path)) {
1482 RLock rlock(status_mutex_);
1483 auto &status_records = status_.records();
1484 if (status_records.find(record_id) == status_records.end()) {
1487 if (record_id == status_.current_record_id()) {
1492 WLock wlock(status_mutex_);
1493 status_.mutable_records()->erase(record_id);
1494 status_changed_ =
true;
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);
1505bool HMIWorker::ReloadVehicles() {
1506 AINFO <<
"load config";
1507 HMIConfig config = util::HMIUtil::LoadConfig(FLAGS_dv_hmi_modes_config_path);
1509 AINFO <<
"serialize new config";
1510 config.SerializeToString(&msg);
1512 WLock wlock(status_mutex_);
1513 AINFO <<
"parse new config";
1514 config_.ParseFromString(msg);
1515 AINFO <<
"init status";
1518 AINFO <<
"clear vehicles";
1519 status_.clear_vehicles();
1522 AINFO <<
"reload vehicles";
1523 for (
const auto &vehicle : config_.vehicles()) {
1524 status_.add_vehicles(vehicle.first);
1526 status_changed_ =
true;
1530void HMIWorker::UpdateCameraSensorChannelToStatus(
1531 const std::string &channel_name) {
1533 WLock wlock(status_mutex_);
1534 if (status_.current_camera_sensor_channel() == channel_name) {
1535 AINFO <<
"Input channel name is current camera sensor channel";
1538 status_.set_current_camera_sensor_channel(channel_name);
1539 status_changed_ =
true;
1543void HMIWorker::UpdatePointCloudChannelToStatus(
1544 const std::string &channel_name) {
1546 WLock wlock(status_mutex_);
1547 if (status_.current_point_cloud_channel() == channel_name) {
1548 AINFO <<
"Input channel name is current camera sensor channel";
1551 status_.set_current_point_cloud_channel(channel_name);
1552 status_changed_ =
true;
Lightweight key-value database to store system-wide parameters.
a singleton clock that can be used to get the current timestamp.
static double NowInSeconds()
gets the current time in second.
Node is the fundamental building block of Cyber RT.
std::function< nlohmann::json(const std::string &function_name, const nlohmann::json ¶m_json)> DvCallback
Some string util functions.
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:
bool LoadConfig(const std::string &relative_path, T *config)
boost::shared_lock< boost::shared_mutex > RLock
boost::unique_lock< boost::shared_mutex > WLock
repeated string description_en_tokens
optional apollo::simulation::Scenario scenario