24 #include <boost/thread/locks.hpp> 25 #include <boost/thread/shared_mutex.hpp> 27 #include "modules/audio/proto/audio_event.pb.h" 28 #include "modules/canbus/proto/chassis.pb.h" 29 #include "modules/common/proto/drive_event.pb.h" 30 #include "modules/control/proto/pad_msg.pb.h" 31 #include "modules/dreamview/proto/hmi_config.pb.h" 32 #include "modules/dreamview/proto/hmi_mode.pb.h" 33 #include "modules/dreamview/proto/hmi_status.pb.h" 34 #include "modules/localization/proto/localization.pb.h" 50 explicit HMIWorker(
const std::shared_ptr<apollo::cyber::Node>& node);
55 bool Trigger(
const HMIAction action);
56 bool Trigger(
const HMIAction action,
const std::string&
value);
62 std::function<void(const bool status_changed, HMIStatus* status)>;
64 status_update_handlers_.push_back(handler);
69 const int audio_type,
const int moving_result,
70 const int audio_direction,
const bool is_siren_on);
74 const std::string& event_msg,
75 const std::vector<std::string>& event_types,
76 const bool is_reportable);
89 static HMIMode
LoadMode(
const std::string& mode_config_path);
92 void InitReadersAndWriters();
94 void StatusUpdateThreadLoop();
97 void SetupMode()
const;
98 void ResetMode()
const;
101 void ChangeMode(
const std::string& mode_name);
102 void ChangeMap(
const std::string& map_name);
103 void ChangeVehicle(
const std::string& vehicle_name);
104 bool ChangeDrivingMode(
const apollo::canbus::Chassis::DrivingMode mode);
107 void StartModule(
const std::string& module)
const;
108 void StopModule(
const std::string& module)
const;
110 void ResetComponentStatusTimer();
111 void UpdateComponentStatus();
113 const HMIConfig config_;
117 std::atomic<double> last_status_received_s_;
118 bool monitor_timed_out_{
true};
119 HMIMode current_mode_;
120 bool status_changed_ =
false;
121 size_t last_status_fingerprint_{};
123 mutable boost::shared_mutex status_mutex_;
124 mutable size_t record_count_ = 0;
125 std::future<void> thread_future_;
126 std::vector<StatusUpdateHandler> status_update_handlers_;
129 std::shared_ptr<apollo::cyber::Node> node_;
130 std::shared_ptr<cyber::Reader<apollo::canbus::Chassis>> chassis_reader_;
131 std::shared_ptr<cyber::Reader<apollo::localization::LocalizationEstimate>>
132 localization_reader_;
133 std::shared_ptr<cyber::Writer<HMIStatus>> status_writer_;
134 std::shared_ptr<cyber::Writer<apollo::control::PadMessage>> pad_writer_;
135 std::shared_ptr<cyber::Writer<apollo::audio::AudioEvent>> audio_event_writer_;
136 std::shared_ptr<cyber::Writer<apollo::common::DriveEvent>>
void RegisterStatusUpdateHandler(StatusUpdateHandler handler)
Definition: hmi_worker.h:63
static HMIConfig LoadConfig()
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::function< void(const bool status_changed, HMIStatus *status)> StatusUpdateHandler
Definition: hmi_worker.h:62
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)
std::unique_ptr< Node > CreateNode(const std::string &node_name, const std::string &name_space="")
bool Trigger(const HMIAction action)
HMIStatus GetStatus() const
static HMIMode LoadMode(const std::string &mode_config_path)
void SubmitDriveEvent(const uint64_t event_time_ms, const std::string &event_msg, const std::vector< std::string > &event_types, const bool is_reportable)
Definition: hmi_worker.h:47
apollo::cyber::base::std value
void SensorCalibrationPreprocess(const std::string &task_type)
void VehicleCalibrationPreprocess()
HMIWorker()
Definition: hmi_worker.h:49