Apollo  6.0
Open source self driving car software
hmi_worker.h
Go to the documentation of this file.
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 <memory>
21 #include <string>
22 #include <vector>
23 
24 #include <boost/thread/locks.hpp>
25 #include <boost/thread/shared_mutex.hpp>
26 
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"
35 
36 #include "cyber/cyber.h"
37 #include "cyber/time/time.h"
38 
43 namespace apollo {
44 namespace dreamview {
45 
46 // Singleton worker which does the actual work of HMI actions.
47 class HMIWorker {
48  public:
50  explicit HMIWorker(const std::shared_ptr<apollo::cyber::Node>& node);
51  void Start();
52  void Stop();
53 
54  // HMI action trigger.
55  bool Trigger(const HMIAction action);
56  bool Trigger(const HMIAction action, const std::string& value);
57 
58  // Register handler which will be called on HMIStatus update.
59  // It will be called ASAP if there are changes, or else periodically
60  // controlled by FLAGS_hmi_status_update_interval.
61  using StatusUpdateHandler =
62  std::function<void(const bool status_changed, HMIStatus* status)>;
64  status_update_handlers_.push_back(handler);
65  }
66 
67  // Submit an AudioEvent
68  void SubmitAudioEvent(const uint64_t event_time_ms, const int obstacle_id,
69  const int audio_type, const int moving_result,
70  const int audio_direction, const bool is_siren_on);
71 
72  // Submit a DriveEvent.
73  void SubmitDriveEvent(const uint64_t event_time_ms,
74  const std::string& event_msg,
75  const std::vector<std::string>& event_types,
76  const bool is_reportable);
77 
78  // Run sensor calibration preprocess
79  void SensorCalibrationPreprocess(const std::string& task_type);
80 
81  // Run vehicle calibration preprocess
83 
84  // Get current HMI status.
85  HMIStatus GetStatus() const;
86 
87  // Load HMIConfig and HMIMode.
88  static HMIConfig LoadConfig();
89  static HMIMode LoadMode(const std::string& mode_config_path);
90 
91  private:
92  void InitReadersAndWriters();
93  void InitStatus();
94  void StatusUpdateThreadLoop();
95 
96  // Start / reset current mode.
97  void SetupMode() const;
98  void ResetMode() const;
99 
100  // Change current mode, launch, map, vehicle and driving mode.
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);
105 
106  // Start / stop a module.
107  void StartModule(const std::string& module) const;
108  void StopModule(const std::string& module) const;
109 
110  void ResetComponentStatusTimer();
111  void UpdateComponentStatus();
112 
113  const HMIConfig config_;
114 
115  // HMI status maintenance.
116  HMIStatus status_;
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_{};
122  bool stop_ = false;
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_;
127 
128  // Cyber members.
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>>
137  drive_event_writer_;
138 };
139 
140 } // namespace dreamview
141 } // namespace apollo
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)
HMIWorker()
Definition: hmi_worker.h:49