Apollo 10.0
自动驾驶开放平台
hmi_worker.h
浏览该文件的文档.
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
17#pragma once
18
19#include <atomic>
20#include <map>
21#include <memory>
22#include <string>
23#include <utility>
24#include <vector>
25
26#include <boost/thread/locks.hpp>
27#include <boost/thread/shared_mutex.hpp>
28
29#include "nlohmann/json.hpp"
30
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"
42
43#include "cyber/cyber.h"
44#include "cyber/time/time.h"
47
52namespace apollo {
53namespace dreamview {
54
55// Singleton worker which does the actual work of HMI actions.
56class HMIWorker {
57 public:
58 using DvCallback = std::function<nlohmann::json(
59 const std::string& function_name, const nlohmann::json& param_json)>;
60 explicit HMIWorker(
62 : HMIWorker(cyber::CreateNode("HMI"), monitor_log_buffer) {}
64 const std::shared_ptr<apollo::cyber::Node>& node,
65 const apollo::common::monitor::MonitorLogBuffer& monitor_log_buffer);
66 void Start(DvCallback callback_api);
67 void Stop();
68
69 // HMI action trigger.
70 bool Trigger(const HMIAction action);
71 bool Trigger(const HMIAction action, const std::string& value);
72
73 // Register handler which will be called on HMIStatus update.
74 // It will be called ASAP if there are changes, or else periodically
75 // controlled by FLAGS_hmi_status_update_interval.
77 std::function<void(const bool status_changed, HMIStatus* status)>;
79 status_update_handlers_.push_back(handler);
80 }
81
82 // Submit an AudioEvent
83 void SubmitAudioEvent(const uint64_t event_time_ms, const int obstacle_id,
84 const int audio_type, const int moving_result,
85 const int audio_direction, const bool is_siren_on);
86
87 // Submit a DriveEvent.
88 void SubmitDriveEvent(const uint64_t event_time_ms,
89 const std::string& event_msg,
90 const std::vector<std::string>& event_types,
91 const bool is_reportable);
92
93 // Run sensor calibration preprocess
94 void SensorCalibrationPreprocess(const std::string& task_type);
95
96 // Run vehicle calibration preprocess
98
99 // Get current HMI status.
100 HMIStatus GetStatus() const;
101
102 bool UpdateDynamicModelToStatus(const std::string& dynamic_model_name);
104 // bool UpdateRecordToStatus(const std::string& record_id,
105 // const std::string& record_status);
106 bool UpdateMapToStatus(const std::string& map_name);
108 bool LoadRecordAndChangeStatus(const std::string& record_name);
109 bool LoadRecord(const std::string& record_name,
110 const std::string& record_file_path, double* total_time_s);
111 bool RecordIsLoaded(const std::string& record_id);
112 bool RePlayRecord();
113 bool LoadRtkRecords();
114 void UpdateRtkRecordToStatus(const std::string &new_name);
121 bool handlePlayRecordProcess(const std::string& action_type);
127 bool ResetRecordProgress(const double& progress);
129 void GetScenarioSetPath(const std::string& scenario_set_id,
130 std::string* scenario_set_path);
131 void UpdateCameraSensorChannelToStatus(const std::string& channel_name);
132 void UpdatePointCloudChannelToStatus(const std::string& channel_name);
133
134 // Start / Stop Data Recorder
135 bool StartDataRecorder();
136 bool StopDataRecorder();
137 int SaveDataRecorder(const std::string& new_name);
138 bool DeleteDataRecorder();
139
140 // Start / Stop rtk Data Recorder
142 bool StopRtkDataRecorder();
144 int SaveRtkDataRecorder(const std::string& new_name);
145 bool StopPlayRtkRecorder();
146 nlohmann::json StartPlayRtkRecorder();
147
148 void ChangeMapVal(const std::string& map_name);
149
150 // kv database update interface
151 bool AddOrModifyObjectToDB(const std::string& key, const std::string& value);
152 bool DeleteObjectToDB(const std::string& key);
153 std::string GetObjectFromDB(const std::string& key);
154 std::vector<std::pair<std::string, std::string>> GetTuplesWithTypeFromDB(
155 const std::string& type);
156
157 bool StartTerminal();
158
164 bool isProcessRunning(const std::string& process_name);
169 std::string GetCurrentModeDefaultLayout();
170
175 std::string GetDvPluginPanelsJsonStr();
176
177 private:
178 void InitReadersAndWriters();
179 void InitStatus();
180 void StatusUpdateThreadLoop();
181
182 // Start / reset current mode.
183 void SetupMode();
184 void ResetMode();
185
186 // Change current mode, launch, map, vehicle and driving mode.
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);
195 bool ChangeDrivingMode(const apollo::canbus::Chassis::DrivingMode mode);
196 void ClearRecordInfo();
197 void ClearRtkRecordInfo();
198 void ClearInvalidRecordStatus(const HMIModeOperation& operation);
199 void ReloadMaps();
207 void ClearInvalidResourceUnderChangeOperation(
208 const HMIModeOperation operation);
209
210
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);
217 // Delete the v2x configuration file from the corresponding
218 // vehicle configuration file.
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);
223
224 // Start / stop a module.
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);
228 // Stop play current record process but current record not changed
229 void StopRecordPlay(const std::string& record_id = "");
230
231 void ResetComponentStatusTimer();
232
233 bool ReadRecordInfo(const std::string& file, double* total_time_s) const;
234 // Periodically check whether the monitor is turned on.
235 void OnTimer(const double &overtime_time);
236
244 bool LoadVehicleDefinedMode(const std::string& mode_config_path,
245 const std::string& current_vehicle_path,
246 HMIMode* self_defined_mode);
247
253 void MergeToCurrentMode(HMIMode* mode);
258 void UpdateModeModulesAndMonitoredComponents();
259
263 void AddExpectedModules(const HMIAction& action);
264
268 bool PackageExist(const std::string& package_name);
272 void LoadDvPluginPanelsJson();
273
274 HMIConfig config_;
275
276 // HMI status maintenance.
277 HMIStatus status_;
278 std::atomic<double> last_status_received_s_;
279 bool monitor_timed_out_{true};
280 HMIMode current_mode_;
281 bool status_changed_ = false;
282 size_t last_status_fingerprint_{};
283 bool stop_ = false;
284 // Used to detect the cycle time of monitor running.
285 uint32_t time_interval_ms_;
286 // The timeout period for monitor not returning a message.
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_;
293 // Cyber members.
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>>
299 monitor_reader_;
300 std::shared_ptr<cyber::Writer<HMIStatus>> status_writer_;
301 std::shared_ptr<
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>>
307 drive_event_writer_;
308 DvCallback callback_api_;
309 std::unique_ptr<cyber::Timer> monitor_timer_;
311 nlohmann::json plugin_panels_json_;
312};
313
314} // namespace dreamview
315} // namespace apollo
Client get Response from a responding Service by sending a Request
Definition client.h:47
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)
HMIStatus GetStatus() const
void UpdateCameraSensorChannelToStatus(const std::string &channel_name)
void ChangeMapVal(const std::string &map_name)
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
Definition hmi_worker.h:73
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.
std::vector< std::pair< std::string, std::string > > GetTuplesWithTypeFromDB(const std::string &type)
void RegisterStatusUpdateHandler(StatusUpdateHandler handler)
Definition hmi_worker.h:78
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 &param_json)> DvCallback
Definition hmi_worker.h:59
void SensorCalibrationPreprocess(const std::string &task_type)
void UpdateRtkRecordToStatus(const std::string &new_name)
nlohmann::json StartPlayRtkRecorder()
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)
Definition hmi_worker.h:60
std::string GetObjectFromDB(const std::string &key)
void UpdatePointCloudChannelToStatus(const std::string &channel_name)
The class of MonitorLogBuffer
class register implement
Definition arena_queue.h:37