目录
monitor_manager 分析
结构分析
// Centralized monitor config and status manager.
class MonitorManager {
public:
void Init(const std::shared_ptr<apollo::cyber::Node>& node);
// Start and end a monitoring frame.
bool StartFrame(const double current_time);
void EndFrame();
// Getters.
const apollo::dreamview::HMIMode& GetHMIMode() const { return mode_config_; }
bool IsInAutonomousMode() const { return in_autonomous_driving_; }
SystemStatus* GetStatus() { return &status_; }
apollo::common::monitor::MonitorLogBuffer& LogBuffer() { return log_buffer_; }
// Cyber reader / writer creator.
template <class T>
std::shared_ptr<cyber::Reader<T>> CreateReader(const std::string& channel) {
if (readers_.find(channel) == readers_.end()) {
readers_.emplace(channel, node_->CreateReader<T>(channel));
}
return std::dynamic_pointer_cast<cyber::Reader<T>>(readers_[channel]);
}
template <class T>
std::shared_ptr<cyber::Writer<T>> CreateWriter(const std::string& channel) {
return node_->CreateWriter<T>(channel);
}
private:
SystemStatus status_;
// Input statuses.
std::string current_mode_;
const apollo::dreamview::HMIConfig hmi_config_;
apollo::dreamview::HMIMode mode_config_;
bool in_autonomous_driving_ = false;
bool CheckAutonomousDriving(const double current_time);
apollo::common::monitor::MonitorLogBuffer log_buffer_;
std::shared_ptr<apollo::cyber::Node> node_;
std::unordered_map<std::string, std::shared_ptr<cyber::ReaderBase>> readers_;
DECLARE_SINGLETON(MonitorManager)
};
DECLARE_SINGLETON(MonitorManager)
单例模式宏定义
#define DECLARE_SINGLETON(classname) \
public: \
static classname *Instance(bool create_if_needed = true) { \
static classname *instance = nullptr; \
if (!instance && create_if_needed) { \
static std::once_flag flag; \
std::call_once(flag, \
[&] { instance = new (std::nothrow) classname(); }); \
} \
return instance; \
} \
\
static void CleanUp() { \
auto instance = Instance(false); \
if (instance != nullptr) { \
CallShutdown(instance); \
} \
} \
\
private: \
classname(); \
DISALLOW_COPY_AND_ASSIGN(classname)
描述现在的系统状态
SystemStatus status_
HMI上显示的状态信息
std::string current_mode_
仿真判断状态
const apollo::dreamview::HMIConfig hmi_config_; apollo::dreamview::HMIMode mode_config_;
判断是不是自动驾驶状态
bool in_autonomous_driving_ = false; bool CheckAutonomousDriving(const double current_time);
日志缓存
apollo::common::monitor::MonitorLogBuffer log_buffer_;
当前node
std::shared_ptr<apollo::cyber::Node> node_;
所有monitor 的reader 管理map
std::unordered_map<std::string, std::shared_ptr<cyber::ReaderBase>> readers_;
开启一次监控
bool StartFrame(const double current_time);
void EndFrame();
bool MonitorManager::StartFrame(const double current_time) {
// Get latest HMIStatus.
static auto hmi_status_reader =
CreateReader<apollo::dreamview::HMIStatus>(FLAGS_hmi_status_topic);
hmi_status_reader->Observe();
const auto hmi_status = hmi_status_reader->GetLatestObserved();
if (hmi_status == nullptr) {
AERROR << "No HMIStatus was received.";
return false;
}
if (current_mode_ != hmi_status->current_mode()) {
// Mode changed, update configs and monitored.
current_mode_ = hmi_status->current_mode();
mode_config_ = HMIWorker::LoadMode(hmi_config_.modes().at(current_mode_));
status_.clear_hmi_modules();
for (const auto& iter : mode_config_.modules()) {
status_.mutable_hmi_modules()->insert({iter.first, {}});
}
status_.clear_components();
for (const auto& iter : mode_config_.monitored_components()) {
status_.mutable_components()->insert({iter.first, {}});
}
status_.clear_other_components();
for (const auto& iter : mode_config_.other_components()) {
status_.mutable_other_components()->insert({iter.first, {}});
}
} else {
// Mode not changed, clear component summary from the last frame.
for (auto& iter : *status_.mutable_components()) {
iter.second.clear_summary();
}
}
in_autonomous_driving_ = CheckAutonomousDriving(current_time);
return true;
}
void MonitorManager::EndFrame() {
// Print and publish all monitor logs.
log_buffer_.Publish();
}
start frame分析
1. 获取最近的HMI状态
1.1. 如果获取不到就返回false
2. 如果当前的状态和上一次的状态(HMI状态)不同,就update
2.1. status_ update 最新的状态
3. 如果当前的状态与上一次的状态(HMI状态)相同,就清除component summary
// Mode not changed, clear component summary from the last frame.
for (auto& iter : *status_.mutable_components()) {
iter.second.clear_summary();
}
end frame分析
把当前的监控过程中利用MonitorLogBuffrt::AddMonitorMsgItem 添加的日志信息打印并发布出去
发布topic: /apollo/monitor
// modules/common/monitor_log/monitor_log_buffer.cc
void MonitorLogBuffer::AddMonitorMsgItem(
const MonitorMessageItem::LogLevel log_level, const std::string &msg) {
level_ = log_level;
monitor_msg_items_.push_back(std::make_pair(log_level, msg));
}
//modules/common/monitor_log/monitor_logger.cc
MonitorLogger::MonitorLogger() {
const std::string node_name =
absl::StrCat("monitor_logger", Time::Now().ToNanosecond());
node_ = cyber::CreateNode(node_name);
if (node_ != nullptr) {
monitor_msg_writer_ =
node_->CreateWriter<MonitorMessage>("/apollo/monitor");
}
}
recurrent_runner 分析
结构分析
class RecurrentRunner {
public:
RecurrentRunner(const std::string &name, const double interval);
virtual ~RecurrentRunner() = default;
// Tick once, which may or may not execute the RunOnce() function, based on
// the interval setting.
void Tick(const double current_time);
// Do the actual work.
virtual void RunOnce(const double current_time) = 0;
protected:
std::string name_;
unsigned int round_count_ = 0;
private:
double interval_;
double next_round_ = 0;
};
从类的命名上可以看出,这个类是要负责重复工作的。
Tick 的含义是钟表滴答,可以代表周期性执行任务,上面也有注视写了,Tick 函数可能会执行RunOnce函数,但是也可能不会,执行的周期是以下面的interval_来规定的。
roundcount指的是执行了多少轮。
nextround指的是下次执行的时间。
RunOnce是一个纯虚函数,所以这个类是一个接口,并不可以直接new。
Tick 函数分析
void RecurrentRunner::Tick(const double current_time) {
if (next_round_ <= current_time) {
++round_count_;
AINFO_EVERY(100) << name_ << " is running round #" << round_count_;
next_round_ = current_time + interval_;
RunOnce(current_time);
}
}
执行一次更新下一次要执行的时间,然后执行runOnce 函数,并把当前时间传入。