26#include <boost/thread/locks.hpp>
27#include <boost/thread/shared_mutex.hpp>
29#include "nlohmann/json.hpp"
31#include "modules/common_msgs/audio_msgs/audio_event.pb.h"
32#include "modules/common_msgs/basic_msgs/drive_event.pb.h"
33#include "modules/common_msgs/chassis_msgs/chassis.pb.h"
34#include "modules/common_msgs/control_msgs/pad_msg.pb.h"
35#include "modules/common_msgs/dreamview_msgs/hmi_config.pb.h"
36#include "modules/common_msgs/dreamview_msgs/hmi_mode.pb.h"
37#include "modules/common_msgs/dreamview_msgs/hmi_status.pb.h"
38#include "modules/common_msgs/external_command_msgs/action_command.pb.h"
39#include "modules/common_msgs/external_command_msgs/command_status.pb.h"
40#include "modules/common_msgs/localization_msgs/localization.pb.h"
41#include "modules/common_msgs/monitor_msgs/system_status.pb.h"
59 const std::string& function_name,
const nlohmann::json& param_json)>;
62 :
HMIWorker(cyber::CreateNode(
"HMI"), monitor_log_buffer) {}
64 const std::shared_ptr<apollo::cyber::Node>& node,
77 std::function<void(
const bool status_changed, HMIStatus* status)>;
79 status_update_handlers_.push_back(handler);
84 const int audio_type,
const int moving_result,
85 const int audio_direction,
const bool is_siren_on);
89 const std::string& event_msg,
90 const std::vector<std::string>& event_types,
91 const bool is_reportable);
109 bool LoadRecord(
const std::string& record_name,
110 const std::string& record_file_path,
double* total_time_s);
130 std::string* scenario_set_path);
155 const std::string& type);
178 void InitReadersAndWriters();
180 void StatusUpdateThreadLoop();
187 void ChangeMode(
const std::string& mode_name);
188 bool ChangeMap(
const std::string& map_name);
189 bool SelectAndReloadMap(
const std::string& map_name);
190 void ChangeVehicle(
const std::string& vehicle_name);
191 void ChangeRecord(
const std::string& record_id);
192 void ChangeRtkRecord(
const std::string& record_id);
193 void ChangeOperation(
const std::string& operation_str);
194 void ChangeDynamicModel(
const std::string& dynamic_model_name);
196 void ClearRecordInfo();
197 void ClearRtkRecordInfo();
198 void ClearInvalidRecordStatus(
const HMIModeOperation& operation);
207 void ClearInvalidResourceUnderChangeOperation(
208 const HMIModeOperation operation);
211 bool LoadDynamicModels();
212 void DeleteMap(
const std::string& map_name);
213 void DeleteScenarioSet(
const std::string& scenario_set_id);
214 void DeleteRecord(
const std::string& record_id);
215 void DeleteDynamicModel(
const std::string& dynamic_model_name);
216 void DeleteVehicleConfig(
const std::string& vehicle_name);
219 void DeleteV2xConfig(
const std::string& vehicle_name);
220 bool GetScenarioResourcePath(std::string* scenario_resource_path);
221 bool GetRecordPath(std::string* record_path);
222 void GetRtkRecordPath(std::string* record_path);
225 void StartModule(
const std::string& module);
226 void StopModule(
const std::string& module);
227 void LockModule(
const std::string& module,
const bool& lock_flag);
229 void StopRecordPlay(
const std::string& record_id =
"");
231 void ResetComponentStatusTimer();
233 bool ReadRecordInfo(
const std::string& file,
double* total_time_s)
const;
235 void OnTimer(
const double &overtime_time);
244 bool LoadVehicleDefinedMode(
const std::string& mode_config_path,
245 const std::string& current_vehicle_path,
253 void MergeToCurrentMode(
HMIMode* mode);
258 void UpdateModeModulesAndMonitoredComponents();
263 void AddExpectedModules(
const HMIAction& action);
268 bool PackageExist(
const std::string& package_name);
272 void LoadDvPluginPanelsJson();
278 std::atomic<double> last_status_received_s_;
279 bool monitor_timed_out_{
true};
281 bool status_changed_ =
false;
282 size_t last_status_fingerprint_{};
285 uint32_t time_interval_ms_;
287 double overtime_time_;
288 mutable boost::shared_mutex status_mutex_;
289 mutable size_t record_count_ = 0;
290 std::future<void> thread_future_;
291 std::vector<StatusUpdateHandler> status_update_handlers_;
292 std::map<std::string, bool> previous_modules_lock_;
294 std::shared_ptr<apollo::cyber::Node> node_;
295 std::shared_ptr<cyber::Reader<apollo::canbus::Chassis>> chassis_reader_;
296 std::shared_ptr<cyber::Reader<apollo::localization::LocalizationEstimate>>
297 localization_reader_;
298 std::shared_ptr<cyber::Reader<apollo::monitor::SystemStatus>>
300 std::shared_ptr<cyber::Writer<HMIStatus>> status_writer_;
304 action_command_client_;
305 std::shared_ptr<cyber::Writer<apollo::audio::AudioEvent>> audio_event_writer_;
306 std::shared_ptr<cyber::Writer<apollo::common::DriveEvent>>
309 std::unique_ptr<cyber::Timer> monitor_timer_;
311 nlohmann::json plugin_panels_json_;
Client get Response from a responding Service by sending a Request
bool DeleteDataRecorder()
bool handlePlayRecordProcess(const std::string &action_type)
control the nohup play record process by action_type
std::string GetCurrentModeDefaultLayout()
Get dv current mode default layout.
bool RecordIsLoaded(const std::string &record_id)
bool LoadRecord(const std::string &record_name, const std::string &record_file_path, double *total_time_s)
int SaveRtkDataRecorder(const std::string &new_name)
bool DeleteObjectToDB(const std::string &key)
bool Trigger(const HMIAction action, const std::string &value)
bool Trigger(const HMIAction action)
bool DeleteRtkDataRecorder()
HMIStatus GetStatus() const
void UpdateCameraSensorChannelToStatus(const std::string &channel_name)
void ChangeMapVal(const std::string &map_name)
bool StopPlayRtkRecorder()
void GetScenarioSetPath(const std::string &scenario_set_id, std::string *scenario_set_path)
bool UpdateMapToStatus(const std::string &map_name)
bool LoadRecordAndChangeStatus(const std::string &record_name)
bool isProcessRunning(const std::string &process_name)
Check if a process exists
std::function< void(const bool status_changed, HMIStatus *status)> StatusUpdateHandler
void SubmitAudioEvent(const uint64_t event_time_ms, const int obstacle_id, const int audio_type, const int moving_result, const int audio_direction, const bool is_siren_on)
bool ResetRecordProgress(const double &progress)
reset the play record progress to jump.
bool StopRtkDataRecorder()
std::vector< std::pair< std::string, std::string > > GetTuplesWithTypeFromDB(const std::string &type)
void RegisterStatusUpdateHandler(StatusUpdateHandler handler)
bool AddOrModifyObjectToDB(const std::string &key, const std::string &value)
HMIWorker(const std::shared_ptr< apollo::cyber::Node > &node, const apollo::common::monitor::MonitorLogBuffer &monitor_log_buffer)
bool UpdateDynamicModelToStatus(const std::string &dynamic_model_name)
std::string GetDvPluginPanelsJsonStr()
Get dv plugin panels json of frontend.
std::function< nlohmann::json(const std::string &function_name, const nlohmann::json ¶m_json)> DvCallback
void SensorCalibrationPreprocess(const std::string &task_type)
void UpdateRtkRecordToStatus(const std::string &new_name)
nlohmann::json StartPlayRtkRecorder()
bool StartRtkDataRecorder()
void SubmitDriveEvent(const uint64_t event_time_ms, const std::string &event_msg, const std::vector< std::string > &event_types, const bool is_reportable)
int SaveDataRecorder(const std::string &new_name)
void Start(DvCallback callback_api)
HMIWorker(apollo::common::monitor::MonitorLogBuffer monitor_log_buffer)
void VehicleCalibrationPreprocess()
std::string GetObjectFromDB(const std::string &key)
void UpdatePointCloudChannelToStatus(const std::string &channel_name)
void UpdateComponentStatus()
The class of MonitorLogBuffer