Cyber RT组件注册以及动态创建过程 1、mainboard函数分析 mainboard
是Cyber RT启动组件的主程序,程序的名称是由cyber/BUILD
文件指定的,cyber_launch不过是调用了此函数,其入口函数main()
位于cyber/mainboard/mainboard.cc
中:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 int main (int argc, char ** argv) { google::SetUsageMessage("we use this program to load dag and run user apps." ); ModuleArgument module_args; module_args.ParseArgument(argc, argv); apollo::cyber::Init(argv[0 ]); 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 ; }
此函数首先解析命令行参数,初始化Cyber环境,接下来创建一个ModuleController
类对象controller
,之后调用controller.Init()
启动相关功能模块。最后,一直等待cyber::WaitForShutdown()
返回,清理资源并退出main
函数。ModuleArgument
类解析命令行参数,了解此类有助于使用mainboard
命令启动功能模块:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 class ModuleArgument { private : std ::list <std ::string > dag_conf_list_; std ::string binary_name_; std ::string process_group_; std ::string sched_name_; }; 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; } }
ModuleController::Init()
函数十分简单,内部调用了ModuleControll::LoadAll()
函数:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 class ModuleController { private : ModuleArgument args_; class_loader::ClassLoaderManager class_loader_manager_; std ::vector <std ::shared_ptr <ComponentBase>> component_list_; }; 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)) { module_path = common::GetAbsolutePath(dag_root_path, dag_conf); } else if (dag_conf[0 ] == '/' ) { module_path = dag_conf; } else { 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 ; }
上述函数读取命令行中的所有dag_conf,并且逐一调用bool ModuleController::LoadModule(const std::string& path)
函数加载功能模块:
1 2 3 4 5 6 7 8 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); }
此函数从配置文件.dag
读取配置信息,并且调用bool ModuleController::LoadModule(const DagConfig& dag_config)
函数加载功能模块:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 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 ; }
上述代码的核心是调用class_loader_manager_.LoadLobrary(Loadpath)
加载库,调用class_loader_manager_.CreateClassObj()
创建并且初始化(base->Initialize()
,此继承体系的基类中有一个纯虚函数Init()
,Initialize()调用了它
)组件(component
)类对象,并将该模块加入到Cyber RT的组件列表统一调度管理。
2、组件注册过程(预编译阶段完成) Cyber RT
的代码采用工厂模式方法设计,理解这个模式有助于掌握Cyber RT
的组织结构。工厂方法模式就是有两个总的抽象类,一个工厂基类(Factory),一个产品基类(Product)。对每个不同的产品(ProductA/B)都需要给它实现一个工厂(FactoryA/B)。当我们需要产品的实例时,我们就可以调用相应的工厂类返回该产品实例(return new ProductA/B
)。
#### 2.1、Cyber RT工厂模式的对应
Product: ComponentBse
,Cyber RT基于这个基类又分为两个子类Component, TimerComponent
,这两个子类可以视为Product。(代码位于cyber/component);
ProductA/B:modules
里不同功能下的各种组件比如CameraComponent
,它们都继承自Component
或TimerComponent
。(代码位于modules/内各个功能下的xxx_component.h/cc);
Factory:AbstractClassFactoryBase
,它的子类AbstractClassFactory
可以视为Factory。(代码位于cyber/class_loader/utility/class_factory.h)
FactoryA/B:ClassFactory
。代码位于(cyber/class_loader/utility/class_factory.h);
Cyber RT这里有个非常非常tricky的地方,那就是ClassLoader
这个类,它是类加载器用来加载动态库和实例化Product,它虽然没有继承ClassFactory
,但它里面大部分函数都最终调用了ClassFactory
的方法,所以我们暂时可以把ClassLoader
视作工厂。
2.2、Apollo功能模块的结构
apollo/modules
内有很多文件夹,一般每个文件夹对应某个功能,比如drivers
对应驱动,planning
对应规划等等。对于比较单一的功能比如control
,可以看到里面没有像drivers
那样再细分为camera
, radar
,而是直接作为一个功能,这个功能基本就可以理解为模块(module
),所以cyber/modules
里的某一个子文件夹可能对应着多个module
,我们一般要加载的模块也就是要把这个module
对应的所有Component/TimerComponent
(组件)给实例化出来。
一个动态库(dag文件里的module_library
字段指定)对应一个或多个module
(模块)。在实例化Component/TimerComponent
的时候包含这些组件的动态库必须已经被加载进来了。
在诸如modules/control
, modules/drivers/camera
这样的模块下,一定会有一个dag文件夹,这里面就包含了每个模块对应的dag
文件。一个dag文件对应一个module(模块),而每个module有着一个或多个Component/TimerComponent。
2.3、以Planning模块为例 Planning
模块结构比较简单,内部只含有一个module
。modules/planning/planing_component.h
的组件类PlanningComponent
继承自cyber::Component<prediction::PredictionObstacles, canbus::Chassis,
localization::LocalizationEstimate>
。类中管理PlanningBase
类对象指针(Apollo 3.5基于场景概念进行规划,目前从PlanningBase类派生出三个规划类:StdPlanning(高精地图模式)、NaviPlanning(实时相对地图模式)、OpenSpacePlanning(自由空间模式),可通过目录modules/planning/dag下的配置文件指定选用何种场景)。
同时,使用宏CYBER_REGISTER_COMPONENT(PlanningComponent)
将规划组件PlanningComponent
注册到Cyber
的组件类管理器。查看cyber/component/component.h
源代码可知:
1 2 #define CYBER_REGISTER_COMPONENT(name) \ CLASS_LOADER_REGISTER_CLASS(name, apollo::cyber::ComponentBase)
后者的定义在cyber/class_loader/class_loader_register_macro.h
中:
1 2 #define CLASS_LOADER_REGISTER_CLASS(Derived, Base) \ CLASS_LOADER_REGISTER_CLASS_INTERNAL_1(Derived, Base, __COUNTER__)
继续展开:
1 2 #define CLASS_LOADER_REGISTER_CLASS_INTERNAL_1(Derived, Base, UniqueID) \ CLASS_LOADER_REGISTER_CLASS_INTERNAL(Derived, Base, UniqueID)
进一步展开:
1 2 3 4 5 6 7 8 9 10 #define CLASS_LOADER_REGISTER_CLASS_INTERNAL(Derived, Base, UniqueID) \ namespace { \ struct ProxyType ##UniqueID { \ ProxyType##UniqueID() { \ apollo::cyber::class_loader::utility::RegisterClass<Derived, Base>( \ #Derived, #Base); \ } \ }; \ static ProxyType##UniqueID g_register_class_##UniqueID; \ }
将PlanningComponent
代入上述宏,最终得到:
1 2 3 4 5 6 7 8 9 namespace { struct ProxyType__COUNTER__ { ProxyType__COUNTER__() { apollo::cyber::class_loader::utility::RegisterClass<PlanningComponent, apollo::cyber::ComponentBase>( "PlanningComponent" , "apollo::cyber::ComponentBase" ); } }; static ProxyType__COUNTER__ g_register_class___COUNTER__; }
上述代码首先定义了结构体ProxyType__COUNTER__
,该结构体包含一个构造函数在其内部调用apollo::cyber::class_loader::utility::RegisterClass<PlanningComponent,apollo::cyber::ComponentBase>("PlanningComponent", "apollo::cyber::ComponentBase");
注册apollo::cyber::ComponentBase
类的派生类PlanningComponent
。apollo::cyber::class_loader::utility::RegisterClass
函数如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 template <typename Derived, typename Base>void RegisterClass (const std ::string & class_name, const std ::string & base_class_name) { AINFO << "registerclass:" << class_name << "," << base_class_name << "," << GetCurLoadingLibraryName(); utility::AbstractClassFactory<Base>* new_class_factrory_obj = new utility::ClassFactory<Derived, Base>(class_name, base_class_name); new_class_factrory_obj->AddOwnedClassLoader(GetCurActiveClassLoader()); new_class_factrory_obj->SetRelativeLibraryPath(GetCurLoadingLibraryName()); GetClassFactoryMapMapMutex().lock(); ClassClassFactoryMap& factory_map = GetClassFactoryMapByBaseClass(typeid (Base).name()); factory_map[class_name] = new_class_factrory_obj; GetClassFactoryMapMapMutex().unlock(); }
由此可见Cyber RT使用工厂方法模式完成产品对象的创建。Cyber RT在预编译阶段完成了工厂类的注册,将XXX_component
对应的工厂类存入static类型的字典ClassClassFactoryMap
中统一管理,这样便可以根据产品类的类名称由工厂类实例化出产品类。
3、动态创建过程 根据上一部分的内容,功能模块类PlanningComponent
对象在bool ModuleController::LoadModule(const DagConfig& dag_config)函数内部创建:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 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; 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)); } } return true ; }
已经知道,PlanningComponent
对象是通过class_loader_manager_.CreateClassObj<ComponentBase>(class_name)
创建出来的,而class_loader_manager_
是一个class_loader::ClassLoaderManager
类对象。现在的问题是:class_loader::ClassLoaderManager
与工厂类utility::AbstractClassFactory<Base>
如何联系起来的?
先看ClassLoaderManager::CreateClassObj
函数(位于文件cyber/class_loader/class_loader_manager.h
中):
1 2 3 4 5 6 7 8 9 10 11 12 template <typename Base>std ::shared_ptr <Base> ClassLoaderManager::CreateClassObj ( const std ::string & class_name) { std ::vector <ClassLoader*> class_loaders = GetAllValidClassLoaders(); for (auto class_loader : class_loaders) { if (class_loader->IsClassValid<Base>(class_name)) { return (class_loader->CreateClassObj<Base>(class_name)); } } AERROR << "Invalid class name: " << class_name; return std ::shared_ptr <Base>(); }
上述函数中,从所有的class_loaders
中找出一个正确的class_loader
,并调用
class_loader->CreateClassObj(class_name)
(位于文件cyber/class_loader/class_loader.h
中)创建功能模块组件类对象:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 template <typename Base>std ::shared_ptr <Base> ClassLoader::CreateClassObj ( const std ::string & class_name) { if (!IsLibraryLoaded()) { LoadLibrary(); } 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; }
上述函数继续调用utility::CreateClassObj(class_name, this)
(位于文件cyber/class_loader/utility/class_loader_utility.h
中)创建功能模块组件类对象:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 template <typename Base>Base* CreateClassObj (const std ::string & class_name, ClassLoader* loader) { GetClassFactoryMapMapMutex().lock(); ClassClassFactoryMap& factoryMap = GetClassFactoryMapByBaseClass(typeid (Base).name()); AbstractClassFactory<Base>* factory = nullptr ; if (factoryMap.find (class_name) != factoryMap.end ()) { factory = dynamic_cast <utility::AbstractClassFactory<Base>*>( factoryMap[class_name]); } GetClassFactoryMapMapMutex().unlock(); Base* classobj = nullptr ; if (factory && factory->IsOwnedBy(loader)) { classobj = factory->CreateObj(); } return classobj; }
上述函数使用factory = dynamic_cast<utility::AbstractClassFactory<Base>*>( factoryMap[class_name])
;获取对应的工厂对象指针,至此将class_loader::ClassLoaderManager
与工厂类utility::AbstractClassFactory<Base>
联系起来了。工厂对象指针找到后,使用classobj = factory->CreateObj()
;就顺理成章地将功能模块类对象创建出来了。