59 const std::string& function_name,
const nlohmann::json& param_json)>;
61 explicit HMIWorker(
const std::shared_ptr<apollo::cyber::Node>& node);
73 std::function<void(
const bool status_changed, HMIStatus* status)>;
75 status_update_handlers_.push_back(handler);
80 const int audio_type,
const int moving_result,
81 const int audio_direction,
const bool is_siren_on);
85 const std::string& event_msg,
86 const std::vector<std::string>& event_types,
87 const bool is_reportable);
99 const std::string& scenario_set_name);
101 const std::string& scenario_set_name,
110 std::string* scenario_set_path);
115 void InitReadersAndWriters();
117 void StatusUpdateThreadLoop();
119 std::string GetCommandRes(
const std::string& cmd);
122 void SetupMode()
const;
123 void ResetMode()
const;
124 bool ResetSimObstacle(
const std::string& scenario_id);
127 void ChangeMode(
const std::string& mode_name);
128 bool ChangeMap(
const std::string& map_name,
129 bool restart_dynamic_model =
true);
130 void ChangeVehicle(
const std::string& vehicle_name);
131 void ChangeScenarioSet(
const std::string& scenario_set_id);
132 void ChangeRecord(
const std::string& record_id);
133 void ChangeDynamicModel(
const std::string& dynamic_model_name);
134 void ChangeScenario(
const std::string& scenario_id);
137 bool LoadScenarios();
139 bool LoadDynamicModels();
141 void DeleteScenarioSet(
const std::string& scenario_set_id);
142 void DeleteRecord(
const std::string& record_id);
143 void DeleteDynamicModel(
const std::string& dynamic_model_name);
145 bool GetScenarioResourcePath(std::string* scenario_resource_path);
146 bool GetRecordPath(std::string* record_path);
151 void StartModule(
const std::string& module)
const;
152 void StopModule(
const std::string& module)
const;
153 bool StopModuleByCommand(
const std::string& stop_command)
const;
154 void StopRecordPlay();
156 void ResetComponentStatusTimer();
165 bool LoadVehicleDefinedMode(
const std::string& mode_config_path,
166 const std::string& current_vehicle_path,
174 void MergeToCurrentMode(
HMIMode* mode);
179 void UpdateModeModulesAndMonitoredComponents();
185 std::atomic<double> last_status_received_s_;
186 bool monitor_timed_out_{
true};
187 HMIMode current_mode_;
188 bool status_changed_ =
false;
189 size_t last_status_fingerprint_{};
191 mutable boost::shared_mutex status_mutex_;
192 mutable size_t record_count_ = 0;
193 std::future<void> thread_future_;
194 std::vector<StatusUpdateHandler> status_update_handlers_;
197 std::shared_ptr<apollo::cyber::Node> node_;
198 std::shared_ptr<cyber::Reader<apollo::canbus::Chassis>> chassis_reader_;
199 std::shared_ptr<cyber::Reader<apollo::localization::LocalizationEstimate>>
200 localization_reader_;
201 std::shared_ptr<cyber::Writer<HMIStatus>> status_writer_;
205 action_command_client_;
209 lane_follow_command_client_;
210 std::shared_ptr<cyber::Writer<apollo::audio::AudioEvent>> audio_event_writer_;
211 std::shared_ptr<cyber::Writer<apollo::common::DriveEvent>>