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

#include <module_monitor.h>

类 apollo::monitor::ModuleMonitor 继承关系图:
apollo::monitor::ModuleMonitor 的协作图:

Public 类型

using NodeManagerPtr = std::shared_ptr< cyber::service_discovery::NodeManager >
 

Public 成员函数

 ModuleMonitor ()
 
void RunOnce (const double current_time) override
 
void UpdateStatus (const apollo::dreamview::ModuleMonitorConfig &config, const std::string &module_name, ComponentStatus *status)
 
- Public 成员函数 继承自 apollo::monitor::RecurrentRunner
 RecurrentRunner (const std::string &name, const double interval)
 
virtual ~RecurrentRunner ()=default
 
void Tick (const double current_time)
 

额外继承的成员函数

- Protected 属性 继承自 apollo::monitor::RecurrentRunner
std::string name_
 
unsigned int round_count_ = 0
 

详细描述

在文件 module_monitor.h30 行定义.

成员类型定义说明

◆ NodeManagerPtr

构造及析构函数说明

◆ ModuleMonitor()

apollo::monitor::ModuleMonitor::ModuleMonitor ( )

在文件 module_monitor.cc36 行定义.

37 : RecurrentRunner(absl::GetFlag(FLAGS_module_monitor_name),
38 absl::GetFlag(FLAGS_module_monitor_interval)) {
39 node_manager_ =
40 cyber::service_discovery::TopologyManager::Instance()->node_manager();
41}
RecurrentRunner(const std::string &name, const double interval)

成员函数说明

◆ RunOnce()

void apollo::monitor::ModuleMonitor::RunOnce ( const double  current_time)
overridevirtual

实现了 apollo::monitor::RecurrentRunner.

在文件 module_monitor.cc43 行定义.

43 {
44 auto manager = MonitorManager::Instance();
45 const auto& mode = manager->GetHMIMode();
46
47 // Check monitored components.
48 auto* components = manager->GetStatus()->mutable_components();
49 for (const auto& iter : mode.monitored_components()) {
50 const std::string& name = iter.first;
51 const auto& monitored_component = iter.second;
52 if (monitored_component.has_module() &&
53 apollo::common::util::ContainsKey(*components, name)) {
54 const auto& config = monitored_component.module();
55 auto* status = components->at(name).mutable_module_status();
56 UpdateStatus(config, name, status);
57 }
58 }
59}
void UpdateStatus(const apollo::dreamview::ModuleMonitorConfig &config, const std::string &module_name, ComponentStatus *status)

◆ UpdateStatus()

void apollo::monitor::ModuleMonitor::UpdateStatus ( const apollo::dreamview::ModuleMonitorConfig config,
const std::string &  module_name,
ComponentStatus *  status 
)

在文件 module_monitor.cc61 行定义.

63 {
64 status->clear_status();
65
66 bool all_nodes_matched = true;
67 for (const std::string& name : config.node_name()) {
68 if (!node_manager_->HasNode(name)) {
69 all_nodes_matched = false;
70 break;
71 }
72 }
73 if (all_nodes_matched) {
74 // Working nodes are all matched. The module is running.
75 SummaryMonitor::EscalateStatus(ComponentStatus::OK, module_name, status);
76 return;
77 }
78
79 SummaryMonitor::EscalateStatus(ComponentStatus::FATAL, "", status);
80}
static void EscalateStatus(const ComponentStatus::Status new_status, const std::string &message, ComponentStatus *current_status)

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