mainboard模块是cyber的程序入口,启动模块,我们可以使用类似roslaunch的方式启动,cyberRT的launch也是封装了mainboard模块,也可以直接使用mainboard -p <process_group> -d … &启动某一个模块。
minaboard模块中一共有五个文件,两个类(module_argument、module_controller)和一个主文件mainboard.cc。
首先先看mainboard.cc
#include "cyber/common/global_data.h"
#include "cyber/common/log.h"
#include "cyber/init.h"
#include "cyber/mainboard/module_argument.h"
#include "cyber/mainboard/module_controller.h"
#include "cyber/state.h"
using apollo::cyber::mainboard::ModuleArgument;
using apollo::cyber::mainboard::ModuleController;
int main(int argc, char** argv) {
// parse the argument
ModuleArgument module_args;
module_args.ParseArgument(argc, argv);
// initialize cyber
apollo::cyber::Init(argv[0]);
// start module
ModuleController controller(module_args);
if (!controller.Init()) {
controller.Clear();
AERROR << "module start error.";
return -1;
}
apollo::cyber::WaitForShutdown();
controller.Clear();
AINFO << "exit mainboard.";
return 0;
}
从include来看,导入了全局量和log功能,导入了cyber下的init类和state类,以及自己mainboard模块下的ModuleArgument参数类和ModuleController模块类。
main()函数
- 实例化ModuleArgument,并调用ParseArgument进行参数的解析
- apollo::cyber::Init(argv[0]),传递文件名,初始化日志线程,并加入调度器
scheduler::Instance()->SetInnerThreadAttr("async_log", thread);
注册退出的句柄并设置状态(状态在state类中可以看到枚举)
if (!g_atexit_registered) {
if (std::atexit(ExitHandle) != 0) {
AERROR << "Register exit handle failed";
return false;
}
AINFO << "Register exit handle succ.";
g_atexit_registered = true;
}
SetState(STATE_INITIALIZED);
- 使用参数类实例化模板控制器
ModuleController controller(module_args);
if (!controller.Init()) {
controller.Clear();
AERROR << "module start error.";
return -1;
}
- 等待程序结束并清除控制器
关于state,init,cyber以及binary,我会在(三)具体分析,这里只看代码知道大概功能即可。
ModuleArgument
class ModuleArgument {
public:
ModuleArgument() = default;
virtual ~ModuleArgument() = default;
void DisplayUsage();
void ParseArgument(int argc, char* const argv[]);
void GetOptions(const int argc, char* const argv[]);
const std::string& GetBinaryName() const;
const std::string& GetProcessGroup() const;
const std::string& GetSchedName() const;
const std::list<std::string>& GetDAGConfList() const;
private:
std::list<std::string> dag_conf_list_;
std::string binary_name_;
std::string process_group_;
std::string sched_name_;
};
inline const std::string& ModuleArgument::GetBinaryName() const {
return binary_name_;
}
inline const std::string& ModuleArgument::GetProcessGroup() const {
return process_group_;
}
inline const std::string& ModuleArgument::GetSchedName() const {
return sched_name_;
}
inline const std::list<std::string>& ModuleArgument::GetDAGConfList() const {
return dag_conf_list_;
}
ModuleArgement实现了DisplayUsage(),ParseArgument(),GetOptions()等功能。
|–DisplayUsage()
这个功能挺简单的且关键的,调用Google glog stream输出信息。
void ModuleArgument::DisplayUsage() {
AINFO << "Usage: \n " << binary_name_ << " [OPTION]...\n"
<< "Description: \n"
<< " -h, --help : help information \n"
<< " -d, --dag_conf=CONFIG_FILE : module dag config file\n"
<< " -p, --process_group=process_group: the process "
"namespace for running this module, default in manager process\n"
<< " -s, --sched_name=sched_name: sched policy "
"conf for hole process, sched_name should be conf in cyber.pb.conf\n"
<< "Example:\n"
<< " " << binary_name_ << " -h\n"
<< " " << binary_name_ << " -d dag_conf_file1 -d dag_conf_file2 "
<< "-p process_group -s sched_name\n";
}
/cyber/common/log.h
#define AINFO ALOG_MODULE(MODULE_NAME, INFO)
#ifndef ALOG_MODULE
#define ALOG_MODULE(module, log_severity) \
ALOG_MODULE_STREAM(log_severity)(module)
#endif
#ifndef ALOG_MODULE_STREAM
#define ALOG_MODULE_STREAM(log_severity) ALOG_MODULE_STREAM_##log_severity
#endif
#define ALOG_MODULE_STREAM_INFO(module) \
google::LogMessage(__FILE__, __LINE__, google::INFO).stream() \
<< LEFT_BRACKET << module << RIGHT_BRACKET
#define ALOG_MODULE_STREAM_WARN(module) \
google::LogMessage(__FILE__, __LINE__, google::WARNING).stream() \
<< LEFT_BRACKET << module << RIGHT_BRACKET
#define ALOG_MODULE_STREAM_ERROR(module) \
google::LogMessage(__FILE__, __LINE__, google::ERROR).stream() \
<< LEFT_BRACKET << module << RIGHT_BRACKET
#define ALOG_MODULE_STREAM_FATAL(module) \
google::LogMessage(__FILE__, __LINE__, google::FATAL).stream() \
<< LEFT_BRACKET << module << RIGHT_BRACKET
#define ALOG_MODULE_STREAM(log_severity) ALOG_MODULE_STREAM_##log_severity中,会将log_severity与ALOG_MODULE_STREAM_拼接到一起,调用不同严重性级别的宏定义stream()。
|–ParseArgument()
这个函数会调用GetOptions函数读取argc,argv,话不多说,先看代码
void ModuleArgument::ParseArgument(const int argc, char* const argv[]) {
binary_name_ = std::string(basename(argv[0]));
GetOptions(argc, argv);
if (process_group_.empty()) {
process_group_ = DEFAULT_process_group_;
}
if (sched_name_.empty()) {
sched_name_ = DEFAULT_sched_name_;
}
GlobalData::Instance()->SetProcessGroup(process_group_);
GlobalData::Instance()->SetSchedName(sched_name_);
AINFO << "binary_name_ is " << binary_name_ << ", process_group_ is "
<< process_group_ << ", has " << dag_conf_list_.size() << " dag conf";
for (std::string& dag : dag_conf_list_) {
AINFO << "dag_conf: " << dag;
}
}
ParseArgument和构造函数挺相似的,首先赋值了binary_name_,basename这个函数在libgen.h中,获得最后一个/之后的字符串.
#include<iostream>
#include <libgen.h>
int main(int argc, char** argv) {
std::cout << basename(argv[0]) << '\n';
}
输入 ./../code-test/test.o
输出 test.o
在cyber中mainboard -p <process_group> -d … &启动模块 binary_name_ 应为是mainboard。然后调用GetOptions()读取参数。设置process_group_和sched_name_,并在GlobalData设置。process_group_是模块名,sched_name_是调度策略,输出并显示信息
|–GetOptions()
主要是对后面的命令行进行解析,show me code
void ModuleArgument::GetOptions(const int argc, char* const argv[]) {
opterr = 0; // extern int opterr
int long_index = 0;
const std::string short_opts = "hd:p:s:";
static const struct option long_opts[] = {
{"help", no_argument, nullptr, 'h'},
{"dag_conf", required_argument, nullptr, 'd'},
{"process_name", required_argument, nullptr, 'p'},
{"sched_name", required_argument, nullptr, 's'},
{NULL, no_argument, nullptr, 0}};
// log command for info
std::string cmd("");
for (int i = 0; i < argc; ++i) {
cmd += argv[i];
cmd += " ";
}
AINFO << "command: " << cmd;
if (1 == argc) {
DisplayUsage();
exit(0);
}
do {
int opt =
getopt_long(argc, argv, short_opts.c_str(), long_opts, &long_index);
if (opt == -1) {
break;
}
switch (opt) {
case 'd':
dag_conf_list_.emplace_back(std::string(optarg));
for (int i = optind; i < argc; i++) {
if (*argv[i] != '-') {
dag_conf_list_.emplace_back(std::string(argv[i]));
} else {
break;
}
}
break;
case 'p':
process_group_ = std::string(optarg);
break;
case 's':
sched_name_ = std::string(optarg);
break;
case 'h':
DisplayUsage();
exit(0);
default:
break;
}
} while (true);
if (optind < argc) {
AINFO << "Found non-option ARGV-element \"" << argv[optind++] << "\"";
DisplayUsage();
exit(1);
}
if (dag_conf_list_.empty()) {
AINFO << "-d parameter must be specified";
DisplayUsage();
exit(1);
}
}
opterr 是#include <getopt.h>被引入的,
extern char *optarg;
extern int optind;
extern int opterr;
extern int optopt;
char *optarg:如果有参数,则包含当前选项参数字符串
int optind:argv的当前索引值。当getopt函数在while循环中使用时,剩下的字符串为操作数,下标从optind到argc-1。
int opterr:这个变量非零时,getopt()函数为“无效选项”和“缺少参数选项,并输出其错误信息。
int optopt:当发现无效选项字符之时,getopt()函数或返回 \’ ? \’ 字符,或返回字符 \’ : \’ ,并且optopt包含了所发现的无效选项字符。
定义了optstring的字符串。单个字符,字符后面接一个冒号说明后面跟随一个选项参数,字符后面接两个冒号说明后面跟随一个可有可无的选项参数。具体说明看long_opts是对每个参数的说明。option类也是在getopt中被定义。
struct option
{
const char *name;
int has_arg;
int *flag;
int val;
};
#define no_argument 0
#define required_argument 1
#define optional_argument 2
记录下指令,当argc==1时,说明没有任何的参数,调用DisplayUsage()并退出,否则调用getopt_long,不停获取参数并设置-d dag_conf_list_,-p process_group_, -s sched_name_。
ModuleController
class ModuleController {
public:
explicit ModuleController(const ModuleArgument& args);
virtual ~ModuleController() = default;
bool Init();
bool LoadAll();
void Clear();
private:
bool LoadModule(const std::string& path);
bool LoadModule(const DagConfig& dag_config);
int GetComponentNum(const std::string& path);
int total_component_nums = 0;
bool has_timer_component = false;
ModuleArgument args_;
class_loader::ClassLoaderManager class_loader_manager_;
std::vector<std::shared_ptr<ComponentBase>> component_list_;
};
整个类里面有五个参数,组件数量,是否存在timer组件,ModuleArgument参数,模块加载管理器,组件列表,使用的是工厂方式,共实现了三个功能,初始化,加载组建,清零状态。为了实现三个功能,实现了两种方式的单个模块的加载,获得组件数量。
构造函数很简单,直接复制args_即可。Init()会直接调用loadAll()函数。
| – LoadALL()
bool ModuleController::LoadAll() {
const std::string work_root = common::WorkRoot();
const std::string current_path = common::GetCurrentPath();
const std::string dag_root_path = common::GetAbsolutePath(work_root, "dag");
std::vector<std::string> paths;
for (auto& dag_conf : args_.GetDAGConfList()) {
std::string module_path = "";
if (dag_conf == common::GetFileName(dag_conf)) {
// case dag conf argument var is a filename
module_path = common::GetAbsolutePath(dag_root_path, dag_conf);
} else if (dag_conf[0] == '/') {
// case dag conf argument var is an absolute path
module_path = dag_conf;
} else {
// case dag conf argument var is a relative path
module_path = common::GetAbsolutePath(current_path, dag_conf);
if (!common::PathExists(module_path)) {
module_path = common::GetAbsolutePath(work_root, dag_conf);
}
}
total_component_nums += GetComponentNum(module_path);
paths.emplace_back(std::move(module_path));
}
if (has_timer_component) {
total_component_nums += scheduler::Instance()->TaskPoolSize();
}
common::GlobalData::Instance()->SetComponentNums(total_component_nums);
for (auto module_path : paths) {
AINFO << "Start initialize dag: " << module_path;
if (!LoadModule(module_path)) {
AERROR << "Failed to load module: " << module_path;
return false;
}
}
return true;
}
LoadALL()前面一直在获取模块的地址,调用LoadModule启动模块。
bool ModuleController::LoadModule(const std::string& path) {
DagConfig dag_config;
if (!common::GetProtoFromFile(path, &dag_config)) {
AERROR << "Get proto failed, file: " << path;
return false;
}
return LoadModule(dag_config);
}
bool ModuleController::LoadModule(const DagConfig& dag_config) {
const std::string work_root = common::WorkRoot();
for (auto module_config : dag_config.module_config()) {
std::string load_path;
if (module_config.module_library().front() == '/') {
load_path = module_config.module_library();
} else {
load_path =
common::GetAbsolutePath(work_root, module_config.module_library());
}
if (!common::PathExists(load_path)) {
AERROR << "Path does not exist: " << load_path;
return false;
}
class_loader_manager_.LoadLibrary(load_path);
for (auto& component : module_config.components()) {
const std::string& class_name = component.class_name();
std::shared_ptr<ComponentBase> base =
class_loader_manager_.CreateClassObj<ComponentBase>(class_name);
if (base == nullptr || !base->Initialize(component.config())) {
return false;
}
component_list_.emplace_back(std::move(base));
}
for (auto& component : module_config.timer_components()) {
const std::string& class_name = component.class_name();
std::shared_ptr<ComponentBase> base =
class_loader_manager_.CreateClassObj<ComponentBase>(class_name);
if (base == nullptr || !base->Initialize(component.config())) {
return false;
}
component_list_.emplace_back(std::move(base));
}
}
return true;
}
会将path路径中的dag配置文件进行读取,转换成DagConfig&,然后进行真正的调用
class_loader_manager_.LoadLibrary(load_path);
并创建组件加载管理器
std::shared_ptr<ComponentBase> base =
class_loader_manager_.CreateClassObj<ComponentBase>(class_name);