Apollo (阿波罗)是一个开放的、完整的、安全的平台,将帮助汽车行业及自动驾驶领域的合作伙伴结合车辆和硬件系统,快速搭建一套 属于自己的自动驾驶系统。
Cyber RT是一个高性能、高吞吐、低延时的计算运行框架,其中,动态加载技术和有向无环图(DAG)是其实现高性能重要途径之一。
Cyber RT采用了基于Component模块和有向无环图(DAG)的动态加载配置的工程框架。即将相关算法模块通过Component创建,并通过DAG拓扑定义对各Component依赖关系进行动态加载和配置,从而实现对算法进行统一调度,对资源进行统一分配。采用这个工程框架可以使算法与工程解耦,达到工程更专注工程,算法更专注算法的目的。
简介
由于 cyber 的代码非常多,所以我先从官方文档入手,讲解下 Cyber 的整体框架以及实现的目的。 总得来说,cyber 主要的目的就是代替 ROS 成为 Apollo 内部新的消息中间件。说到中间件,一个功能必不可少,那就是消息队列。消息队列主要负责任务的执行,接收和发送各个节点的消息,涉及到消息的发布、订阅和缓存。另一个实现的特性是任务调度,主要是为了自动驾驶算法模块的高实时性,需要对不同优先级的消息进行实时调度才能实现快速执行响应
。
除此之外,整个 cyber 还提供了灵活的用户接口以及丰富的 debug 工具,这个我们可以在官方文档上找到对应的借口文档以及 debug 工具的使用。 apollo.baidu.com/community/A…
代码解析
之前的一篇文章中其实已经介绍了cyber的源码,但是当时是按照我自己对cyber的理解进行的解读,可能有些同学和我的思路不一样的话会有些看不懂。这篇文章会从main函数先入手进行分析。
目录结构:
int main(int argc, char** argv) {
// 解析传入的参数
ModuleArgument module_args;
module_args.ParseArgument(argc, argv);
auto dag_list = module_args.GetDAGConfList();
std::string dag_info;
for (auto&& i = dag_list.begin(); i != dag_list.end(); i++) {
size_t pos = 0;
for (size_t j = 0; j < (*i).length(); j++) {
pos = ((*i)[j] == '/') ? j: pos;
}
if (i != dag_list.begin()) dag_info += "_";
if (pos == 0) {
dag_info += *i;
} else {
dag_info +=
(pos == (*i).length()-1) ? (*i).substr(pos): (*i).substr(pos+1);
}
}
// 初始化 cyber
apollo::cyber::Init(argv[0], dag_info);
// 启动 module,里面会创建component
ModuleController controller(module_args);
if (!controller.Init()) {
controller.Clear();
AERROR << "module start error.";
return -1;
}
static bool enable_cpu_profile = module_args.GetEnableCpuprofile();
static bool enable_mem_profile = module_args.GetEnableHeapprofile();
std::signal(SIGTERM, [](int sig){
apollo::cyber::OnShutdown(sig);
if (enable_cpu_profile) {
ProfilerStop();
}
if (enable_mem_profile) {
HeapProfilerDump("Befor shutdown");
HeapProfilerStop();
}
});
if (module_args.GetEnableCpuprofile()) {
auto profile_filename = module_args.GetProfileFilename();
ProfilerStart(profile_filename.c_str());
}
if (module_args.GetEnableHeapprofile()) {
auto profile_filename = module_args.GetHeapProfileFilename();
HeapProfilerStart(profile_filename.c_str());
}
// 等待cyber关闭
apollo::cyber::WaitForShutdown();
if (module_args.GetEnableCpuprofile()) {
ProfilerStop();
}
if (module_args.GetEnableHeapprofile()) {
HeapProfilerDump("Befor shutdown");
HeapProfilerStop();
}
// 卸载模块
controller.Clear();
AINFO << "exit mainboard.";
return 0;
}
解析传入的参数
从代码中看到调用的是ModuleArgument的解析接口
void ModuleArgument::ParseArgument(const int argc, char* const argv[]) {
// 模块名称
binary_name_ = std::string(basename(argv[0]));
// 解析参数, 具体想要了解可以看源码,篇幅受限
GetOptions(argc, argv);
// 判断process_group_和sched_name_,没有则赋值为默认值
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";
// 打印dag_conf配置,可以看到dag conf是一个list存储的
for (std::string& dag : dag_conf_list_) {
AINFO << "dag_conf: " << dag;
}
}
启动 module
代码中定义了一个ModuleController的对象,并调用init函数。
inline bool ModuleController::Init() { return LoadAll(); }
LoadAll 函数中解析出模块路径传入LoadModule函数进行加载,LoadModule通过路径解析出对应的dag_config,然后遍历dag_config,在遍历时,调用类加载器class_loader_manager_。
bool ModuleController::LoadModule(const DagConfig& dag_config) {
for (auto module_config : dag_config.module_config()) {
std::string load_path;
if (!common::GetFilePathWithEnv(module_config.module_library(),
"APOLLO_LIB_PATH", &load_path)) {
AERROR << "no module library [" << module_config.module_library()
<< "] found!";
return false;
}
AINFO << "mainboard: use module library " << load_path;
// 通过类加载器加载load_path下的模块
class_loader_manager_.LoadLibrary(load_path);
// 创建component和timer component, 并且调用initialize
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;
}
mainboard中的主要代码已经解释完,后面的流程就是在执行完之后,进行的一系列资源清理等操作。 下面接着上面的步骤讲下ClassLoadManager。
ClassLoadManager
从代码上可以看到,先调用的是LoadLibrary加载动态库。那么这个load_path是什么呢?其实就是dag文件的路径,比如:routing\dag\routing.dag
# Define all coms in DAG streaming.
module_config {
module_library : "modules/routing/librouting_component.so"
components {
class_name : "RoutingComponent"
config {
name : "routing"
config_file_path: "/apollo/modules/routing/conf/routing_config.pb.txt"
flag_file_path: "/apollo/modules/routing/conf/routing.conf"
readers: [
{
channel: "/apollo/raw_routing_request"
qos_profile: {
depth : 10
}
}
]
}
}
}
从配置文件中可以看到加载的是librouting_component,类的名字是RoutingComponent。结合上面类加载的代码,我们就可以对应到实例化模块以及初始化模块的过程。
LoadLibrary内部会创建ClasLoader类再进行加载。
bool ClassLoaderManager::LoadLibrary(const std::string& library_path) {
std::lock_guard<std::mutex> lck(libpath_loader_map_mutex_);
if (!IsLibraryValid(library_path)) {
// lib path和ClassLoader组成的Map
libpath_loader_map_[library_path] =
new class_loader::ClassLoader(library_path);
}
return IsLibraryValid(library_path);
}
ClassLoadManager内部管理了一个libpath_loader_map_,主要是管理类加载器ClassLoader的。
ClassLoader
从LoadModule函数中看出,调用LoadLibrary之后,就会通过config来创建类对象。通过调用 class_loader_manager_.CreateClassObj。 下面的代码中,主要是引用了ClassLoader类的定义:
/**
* for library load,createclass object
*/
class ClassLoader {
public:
explicit ClassLoader(const std::string& library_path);
virtual ~ClassLoader();
// 库是否加载过
bool IsLibraryLoaded();
// 加载库
bool LoadLibrary();
// 卸载库
int UnloadLibrary();
// 获取库路径
const std::string GetLibraryPath() const;
template <typename Base>
std::vector<std::string> GetValidClassNames();
template <typename Base>
// 创建类对象
std::shared_ptr<Base> CreateClassObj(const std::string& class_name);
template <typename Base>
bool IsClassValid(const std::string& class_name);
private:
template <typename Base>
void OnClassObjDeleter(Base* obj);
private:
// 类路径
std::string library_path_;
// 类加载的引用次数
int loadlib_ref_count_;
std::mutex loadlib_ref_count_mutex_;
// 类引用计数
int classobj_ref_count_;
std::mutex classobj_ref_count_mutex_;
};
其中我们看下CreateClassObj函数的实现:
template <typename Base>
std::shared_ptr<Base> ClassLoader::CreateClassObj(
const std::string& class_name) {
if (!IsLibraryLoaded()) {
LoadLibrary();
}
// 调用下层的createClassObj函数
Base* class_object = utility::CreateClassObj<Base>(class_name, this);
if (class_object == nullptr) {
AWARN << "CreateClassObj failed, ensure class has been registered. "
<< "classname: " << class_name << ",lib: " << GetLibraryPath();
return std::shared_ptr<Base>();
}
std::lock_guard<std::mutex> lck(classobj_ref_count_mutex_);
// 增加类对象的引用计数
classobj_ref_count_ = classobj_ref_count_ + 1;
// 绑定对应的析构函数
std::shared_ptr<Base> classObjSharePtr(
class_object, std::bind(&ClassLoader::OnClassObjDeleter<Base>, this,
std::placeholders::_1));
return classObjSharePtr;
}
template <typename Base>
void ClassLoader::OnClassObjDeleter(Base* obj) {
if (nullptr == obj) {
return;
}
delete obj;
std::lock_guard<std::mutex> lck(classobj_ref_count_mutex_);
// 引用计数减一
--classobj_ref_count_;
}
ModuleController::LoadModule 函数在创建完类对象之后就将对象插入component_list_中。
至此,mainboard的主要流程分析就大概理清楚了,下一篇文章我们会更加深入的讲解一下ClassLoader下层的utility是怎样完成类创建、库加载等工作的。