Apollo 10.0
自动驾驶开放平台
apollo::monitor::MonitorManager类 参考

#include <monitor_manager.h>

apollo::monitor::MonitorManager 的协作图:

Public 成员函数

void Init (const std::shared_ptr< apollo::cyber::Node > &node)
 
bool StartFrame (const double current_time)
 
void EndFrame ()
 
const apollo::dreamview::HMIModeGetHMIMode () const
 
bool IsInAutonomousMode () const
 
SystemStatus * GetStatus ()
 
apollo::common::monitor::MonitorLogBufferLogBuffer ()
 
template<class T >
std::shared_ptr< cyber::Reader< T > > CreateReader (const std::string &channel)
 
template<class T >
std::shared_ptr< cyber::Writer< T > > CreateWriter (const std::string &channel)
 

详细描述

在文件 monitor_manager.h38 行定义.

成员函数说明

◆ CreateReader()

template<class T >
std::shared_ptr< cyber::Reader< T > > apollo::monitor::MonitorManager::CreateReader ( const std::string &  channel)
inline

在文件 monitor_manager.h54 行定义.

54 {
55 if (readers_.find(channel) == readers_.end()) {
56 readers_.emplace(channel, node_->CreateReader<T>(channel));
57 }
58 return std::dynamic_pointer_cast<cyber::Reader<T>>(readers_[channel]);
59 }

◆ CreateWriter()

template<class T >
std::shared_ptr< cyber::Writer< T > > apollo::monitor::MonitorManager::CreateWriter ( const std::string &  channel)
inline

在文件 monitor_manager.h62 行定义.

62 {
63 return node_->CreateWriter<T>(channel);
64 }

◆ EndFrame()

void apollo::monitor::MonitorManager::EndFrame ( )

在文件 monitor_manager.cc96 行定义.

96 {
97 // Print and publish all monitor logs.
98 log_buffer_.Publish();
99}
void Publish()
publish the monitor messages

◆ GetHMIMode()

const apollo::dreamview::HMIMode & apollo::monitor::MonitorManager::GetHMIMode ( ) const
inline

在文件 monitor_manager.h47 行定义.

47{ return mode_config_; }

◆ GetStatus()

SystemStatus * apollo::monitor::MonitorManager::GetStatus ( )
inline

在文件 monitor_manager.h49 行定义.

49{ return &status_; }

◆ Init()

void apollo::monitor::MonitorManager::Init ( const std::shared_ptr< apollo::cyber::Node > &  node)

在文件 monitor_manager.cc39 行定义.

39 {
40 node_ = node;
41 if (FLAGS_use_sim_time) {
42 status_.set_is_realtime_in_simulation(true);
43 }
44}

◆ IsInAutonomousMode()

bool apollo::monitor::MonitorManager::IsInAutonomousMode ( ) const
inline

在文件 monitor_manager.h48 行定义.

48{ return in_autonomous_driving_; }

◆ LogBuffer()

apollo::common::monitor::MonitorLogBuffer & apollo::monitor::MonitorManager::LogBuffer ( )
inline

在文件 monitor_manager.h50 行定义.

50{ return log_buffer_; }

◆ StartFrame()

bool apollo::monitor::MonitorManager::StartFrame ( const double  current_time)

在文件 monitor_manager.cc46 行定义.

46 {
47 status_.set_detect_immediately(false);
48 // Get latest HMIStatus.
49 static auto hmi_status_reader =
50 CreateReader<apollo::dreamview::HMIStatus>(FLAGS_hmi_status_topic);
51 hmi_status_reader->Observe();
52 const auto hmi_status = hmi_status_reader->GetLatestObserved();
53 if (hmi_status == nullptr) {
54 AERROR << "No HMIStatus was received.";
55 return false;
56 } else if (hmi_status->expected_modules() > 0) {
57 status_.set_detect_immediately(true);
58 }
59
60 if (current_mode_ != hmi_status->current_mode()) {
61 // Mode changed, update configs and monitored.
62 current_mode_ = hmi_status->current_mode();
64 hmi_config_.modes().at(current_mode_));
65 status_.clear_hmi_modules();
66 for (const auto& iter : mode_config_.modules()) {
67 status_.mutable_hmi_modules()->insert({iter.first, {}});
68 }
69 status_.clear_components();
70 for (const auto& iter : mode_config_.monitored_components()) {
71 status_.mutable_components()->insert({iter.first, {}});
72 }
73 status_.clear_other_components();
74 for (const auto& iter : mode_config_.other_components()) {
75 status_.mutable_other_components()->insert({iter.first, {}});
76 }
77 status_.clear_global_components();
78 for (const auto& iter : mode_config_.global_components()) {
79 status_.mutable_global_components()->insert({iter.first, {}});
80 }
81 } else {
82 // Mode not changed, clear component summary from the last frame.
83 for (auto& iter : *status_.mutable_components()) {
84 iter.second.clear_summary();
85 }
86 // clear global component summary from the last frame.
87 for (auto& iter : *status_.mutable_global_components()) {
88 iter.second.clear_summary();
89 }
90 }
91
92 in_autonomous_driving_ = CheckAutonomousDriving(current_time);
93 return true;
94}
static apollo::dreamview::HMIMode LoadMode(const std::string &mode_config_path)
Load HMIMode.
Definition hmi_util.cc:100
#define AERROR
Definition log.h:44
map< string, string > modes

该类的文档由以下文件生成: