先来看一个例子,方便我们更直观地理解注册器模式,摘自apollo2.5的modules/perception/lib/base/registerer.h文件:
下面以SharedData类为例来具体分析一下,SharedData类的定义如下:
class SharedData {
public:
SharedData() {}
virtual ~SharedData() {}
virtual bool Init() = 0;
// this api should clear all the memory used,
// and would be called by SharedDataManager when reset DAGStreaming.
virtual void Reset() { CHECK(false) << "reset() not implemented."; }
virtual void RemoveStaleData() {
CHECK(false) << "remove_stale_data() not implemented.";
}
virtual std::string name() const = 0;
private:
DISALLOW_COPY_AND_ASSIGN(SharedData);
};
REGISTER_REGISTERER(SharedData);
#define REGISTER_SHAREDDATA(name) REGISTER_CLASS(SharedData, name)
SharedData类是一个抽象基类,定义了SharedData类对外的通用接口。可以看到,在完成SharedData类的定义之后使用宏REGISTER_REGISTERER完成SharedDataRegisterer类的定义,也就是SharedData类的注册:
REGISTER_REGISTERER(SharedData);
class SharedDataRegisterer {
typedef perception::Any Any;
typedef perception::FactoryMap FactoryMap;
public:
static SharedData *GetInstanceByName(const ::std::string &name) {
FactoryMap &map = perception::GlobalFactoryMap()["SharedData"];
FactoryMap::iterator iter = map.find(name);
if (iter == map.end()) {
for (auto c : map) {
AERROR << "Instance:" << c.first;
}
AERROR << "Get instance " << name << " failed.";
return nullptr;
}
Any object = iter->second->NewInstance();
return *(object.AnyCast());
}
static std::vector GetAllInstances() {
std::vector instances;
FactoryMap &map = perception::GlobalFactoryMap()["SharedData"];
instances.reserve(map.size());
for (auto item : map) {
Any object = item.second->NewInstance();
instances.push_back(*(object.AnyCast()));
}
return instances;
}
static const ::std::string GetUniqInstanceName() {
FactoryMap &map = perception::GlobalFactoryMap()["SharedData"];
CHECK_EQ(map.size(), 1) << map.size();
return map.begin()->first;
}
static SharedData *GetUniqInstance() {
FactoryMap &map = perception::GlobalFactoryMap()["SharedData"];
CHECK_EQ(map.size(), 1) << map.size();
Any object = map.begin()->second->NewInstance();
return *(object.AnyCast());
}
static bool IsValid(const ::std::string &name) {
FactoryMap &map = perception::GlobalFactoryMap()["SharedData"];
return map.find(name) != map.end();
}
};
SharedDataRegisterer类有5个静态公有成员函数,分别完成如下功能:
GetInstanceByName函数用来根据输入名称创建对应的子类的对象,返回类型为SharedData *
GetAllInstances函数用来创建在SharedDataRegisterer类中注册的所有子类的对象,返回类型为std::vector
GetUniqInstanceName函数获取在SharedDataRegisterer类中注册的唯一子类的名称,如果在SharedDataRegisterer类中注册了多个子类,则此方法将导致CHECK失败
GetUniqInstance函数用来创建在SharedDataRegisterer类中注册的唯一子类的对象,如果在SharedDataRegisterer类中注册了多个子类,则此方法将导致CHECK失败
IsValid函数用来判断输入名称对应的子类是否在SharedDataRegisterer类中注册,返回类型为bool
这里要说明一下FactoryMap和BaseClassMap,一个FactoryMap对象存储的是派生类名称与一个指向该派生类对象的指针的关联,而一个BaseClassMap对象存储的是基类名称与一个FactoryMap对象的关联:
typedef std::unordered_map FactoryMap;
typedef std::unordered_map BaseClassMap;
接下来看看CommonSharedData类,继承自SharedData类,并且这是一个模板类,类型参数为M,具有如下成员变量:
typedef std::unordered_map> SharedDataMap;
typedef std::pair> SharedDataPair;
typedef std::unordered_map
DataAddedTimeMap; // precision in second
typedef std::pair DataKeyTimestampPair;
SharedDataMap data_map_;
Mutex mutex_;
CommonSharedDataStat stat_;
DataAddedTimeMap data_added_time_map_;
double latest_timestamp_ = std::numeric_limits::min();
data_map_存储的是shared data的key和shared data本身,data_added_time_map_存储的是shared data的key和shared data添加到data_map_中的时间,stat_存储的是一个具体类型的SharedData对象的状态,主要包括对该对象执行的Add、Get和Remove操作的次数。
关于CommonSharedData类的成员函数,主要说下Reset()和RemoveStaleData():
void Reset() override;
void RemoveStaleData() override;
Reset()用来重置一个具体类型的SharedData对象,包括清空data_map_和data_added_time_map_,复位latest_timestamp_
RemoveStaleData()用来从一个具体类型的SharedData对象中移除添加到data_map_中的时间在系统当前时间之前超过shared_data_stale_time阈值的shared data
CameraSharedData、FusionSharedData、LaneSharedData、TLPreprocessingData类以及通过宏OBJECT_SHARED_DATA定义的ObjectData类都继承自CommonSharedData类的模板实例。下面以CameraSharedData类为例解释一下:
struct CameraItem {
cv::Mat image_src_mat;
SeqId seq_num = 0u;
double timestamp = 0.0;
};
class CameraSharedData : public CommonSharedData {
public:
CameraSharedData() = default;
virtual ~CameraSharedData() = default;
std::string name() const override {
return "CameraSharedData";
}
private:
DISALLOW_COPY_AND_ASSIGN(CameraSharedData);
};
REGISTER_SHAREDDATA(CameraSharedData);
可以看到,在完成CameraSharedData类的定义之后使用宏REGISTER_SHAREDDATA完成ObjectFactoryCameraSharedData类和RegisterFactoryCameraSharedData()函数的定义,ObjectFactoryCameraSharedData类继承自ObjectFactory类,ObjectFactoryCameraSharedData类和RegisterFactoryCameraSharedData()函数一起完成CameraSharedData类在SharedData类对应的FactoryMap对象中的注册:
REGISTER_SHAREDDATA(CameraSharedData);
REGISTER_CLASS(SharedData, CameraSharedData);
class ObjectFactoryCameraSharedData : public apollo::perception::ObjectFactory {
public:
virtual ~ObjectFactoryCameraSharedData() {}
virtual perception::Any NewInstance() {
return perception::Any(new CameraSharedData());
}
};
inline void RegisterFactoryCameraSharedData() {
perception::FactoryMap &map = perception::GlobalFactoryMap()["SharedData"];
if (map.find("CameraSharedData") == map.end()) map["CameraSharedData"] = new ObjectFactoryCameraSharedData();
}
通过宏OBJECT_SHARED_DATA完成LidarObjectData、RadarObjectData、CameraObjectData和CIPVObjectData类的定义,并且通过宏REGISTER_SHAREDDATA完成类在SharedData注册器中的注册,这里与CameraSharedData类是一样的:
#define OBJECT_SHARED_DATA(data_name) \
class data_name : public CommonSharedData { \
public: \
data_name() : CommonSharedData() {} \
virtual ~data_name() {} \
std::string name() const override { \
return #data_name; \
} \
\
private: \
DISALLOW_COPY_AND_ASSIGN(data_name); \
}
OBJECT_SHARED_DATA(LidarObjectData);
OBJECT_SHARED_DATA(RadarObjectData);
OBJECT_SHARED_DATA(CameraObjectData);
OBJECT_SHARED_DATA(CIPVObjectData);
REGISTER_SHAREDDATA(LidarObjectData);
REGISTER_SHAREDDATA(RadarObjectData);
REGISTER_SHAREDDATA(CameraObjectData);
REGISTER_SHAREDDATA(CIPVObjectData);
以LidarObjectData类为例,宏OBJECT_SHARED_DATA展开后的代码如下:
OBJECT_SHARED_DATA(LidarObjectData);
class LidarObjectData : public CommonSharedData {
public:
LidarObjectData() : CommonSharedData() {}
virtual ~LidarObjectData() {}
std::string name() const override {
return "LidarObjectData";
}
private:
DISALLOW_COPY_AND_ASSIGN(LidarObjectData);
}
总结一下:REGISTER_REGISTERER宏的功能是完成基类注册器的定义,亦即基类的注册,REGISTER_SHAREDDATA宏的功能是完成派生类在基类注册器中的注册,亦即派生类与基类的关联。
最后再来分析一下SharedDataManager类,该类是整个SharedData这一层与外层交互的接口,具体定义如下:
class SharedDataManager {
public:
SharedDataManager() = default;
~SharedDataManager() = default;
bool Init(const DAGConfig::SharedDataConfig &data_config);
// thread-safe.
SharedData *GetSharedData(const std::string &name) const;
void Reset();
void RemoveStaleData();
private:
std::unordered_map> shared_data_map_;
bool inited_ = false;
DISALLOW_COPY_AND_ASSIGN(SharedDataManager);
};
成员变量shared_data_map_存储的是具体类型的SharedData类的名称如CameraSharedData、LidarObjectData等,和指向某个该类型SharedData对象的指针。成员函数都是通过调用相应的基类接口(在SharedData类中定义)来实现所需的功能,例如初始化是通过Init函数读取DAGConfig消息的data_config域(在onboard/proto/dag_config.proto文件中定义),并在内部调用对应类型的SharedData的Init()函数来实现的,一个DAGConfig消息实例(参见conf/dag_streaming.config文件)的data_config片段如下:
data_config {
datas {
id: 1
name: "LidarObjectData"
}
datas {
id: 2
name: "RadarObjectData"
}
datas {
id: 3
name: "TLPreprocessingData"
}
}
在分析Subnode类之前,我们先来看看EventManager类,该类用来管理event,这里的event是指shared data从一个subnode流向另一个subnode,亦即DAG中的edge。需要注意的成员变量主要有event_queue_map_和event_meta_map_,分别用来存储EventID与EventQueue的关联以及EventID与EventMeta的关联:
using EventQueue = FixedSizeConQueue;
using EventQueueMap = std::unordered_map>;
using EventMetaMap = std::unordered_map;
EventQueueMap event_queue_map_;
EventMetaMap event_meta_map_;
bool inited_ = false;
先来看看Init函数,通过读取DAGConfig消息的edge_config域(在onboard/proto/dag_config.proto文件中定义),根据edge_config域的参数初始化成员变量event_queue_map_和event_meta_map_:
bool EventManager::Init(const DAGConfig::EdgeConfig &edge_config) {
if (inited_) {
AWARN << "EventManager Init twice.";
return true;
}
for (const DAGConfig::Edge &edge : edge_config.edges()) {
for (const DAGConfig::Event event_pb : edge.events()) {
if (event_queue_map_.find(event_pb.id()) != event_queue_map_.end()) {
AERROR << "duplicate event id in config. id: " << event_pb.id();
return false;
}
event_queue_map_[event_pb.id()].reset(
new EventQueue(FLAGS_max_event_queue_size));
EventMeta event_meta;
event_meta.event_id = event_pb.id();
event_meta.name = event_pb.name();
event_meta.from_node = edge.from_node();
event_meta.to_node = edge.to_node();
event_meta_map_.emplace(event_pb.id(), event_meta);
AINFO << "load EventMeta: " << event_meta.to_string();
}
}
AINFO << "load " << event_queue_map_.size() << " events in DAGSreaming.";
inited_ = true;
return true;
}
一个DAGConfig消息实例(参见conf/dag_streaming.config文件)的edge_config片段如下:
# Define all edges linked nodes.
edge_config {
# 64-Lidar LidarProcessSubnode -> FusionSubnode
edges {
id: 101
from_node: 1
to_node: 31
events {
id: 1001
name: "lidar_fusion"
}
}
# Radar RadarProcessSubnode -> FusionSubnode
edges {
id: 102
from_node: 2
to_node: 31
events {
id: 1002
name: "radar_fusion"
}
}
# TLPreprocessorSubnode -> TLProcSubnode
edges {
id: 201
from_node: 41
to_node: 42
events {
id: 1003
name: "traffic_light"
}
}
}
再来看看Publish函数,作用是将输入的Event添加到event_queue_map_里与该Event的EventID关联的EventQueue中去:
bool EventManager::Publish(const Event &event) {
EventQueue *queue = GetEventQueue(event.event_id);
if (queue == nullptr) {
AERROR << "Fail to get event with id: " << event.event_id;
return false;
}
if (!queue->try_push(event)) {
// Critical errors: queue is full.
AERROR << "EventQueue is FULL. id: " << event.event_id;
// Clear all blocked data.
AERROR << "clear EventQueue. id: " << event.event_id
<< " size: " << queue->size();
queue->clear();
// try second time.
queue->try_push(event);
}
return true;
}
最后来看看Subscribe函数,作用是将event_id属性与输入的EventID相同的Event从event_queue_map_里对应的EventQueue中删除,同时会将该Event赋值给输入的Event指针指向的内容:
bool EventManager::Subscribe(EventID event_id, Event *event, bool nonblocking) {
EventQueue *queue = GetEventQueue(event_id);
if (queue == nullptr) {
AERROR << "Fail to get event with id: " << event_id;
return false;
}
if (nonblocking) {
return queue->try_pop(event);
}
ADEBUG << "EVENT_ID: " << event_id << "QUEUE LENGTH:" << queue->size();
queue->pop(event);
return true;
}
bool EventManager::Subscribe(EventID event_id, Event *event) {
return Subscribe(event_id, event, false);
}
顺便说一下,GetEventQueue函数的作用是从event_queue_map_中取出与输入的EventID关联的EventQueue,GetEventMeta函数的作用是从event_meta_map_中取出与输入的EventID关联的EventMeta。
总结一下:from_node发布event,to_node订阅event,每一条edge都包含一个from_node、一个to_node和一个event。
Subnode和SharedData的设计模式是完全一样的,在设计层次上,Subnode对应SharedData,CommonSubnode对应CommonSharedData。唯一不同的是,各个具体类型的Subnode类如LidarProcessSubnode、CIPVSubnode等都直接继承自Subnode类,而各个具体类型的SharedData类如CameraSharedData、CIPVObjectData等都继承自CommonSharedData类的模板实例。下面先来看一下Subnode类的成员变量:
protected:
// following variable can be accessed by Derived Class.
SubnodeID id_ = 0;
std::string name_;
std::string reserve_;
DAGConfig::SubnodeType type_ = DAGConfig::SUBNODE_NORMAL;
EventManager *event_manager_ = nullptr;
SharedDataManager *shared_data_manager_ = nullptr;
std::vector sub_meta_events_;
std::vector pub_meta_events_;
private:
volatile bool stop_ = false;
bool inited_ = false;
int total_count_ = 0;
int failed_count_ = 0;
先来看看Init函数,通过读取DAGConfig消息的subnode_config域(在onboard/proto/dag_config.proto文件中定义),根据subnode_config域的参数以及输入的参数初始化成员变量:
bool Subnode::Init(const DAGConfig::Subnode &subnode_config,
const vector &sub_events,
const vector &pub_events,
EventManager *event_manager,
SharedDataManager *shared_data_manager) {
name_ = subnode_config.name();
id_ = subnode_config.id();
reserve_ = subnode_config.reserve();
if (subnode_config.has_type()) {
type_ = subnode_config.type();
}
CHECK(event_manager != nullptr) << "event_manager == nullptr";
event_manager_ = event_manager;
CHECK(shared_data_manager != nullptr) << "shared_data_manager == nullptr";
shared_data_manager_ = shared_data_manager;
// fill sub and pub meta events.
if (!event_manager_->GetEventMeta(sub_events, &sub_meta_events_)) {
AERROR << "failed to get Sub EventMeta. node: <" << name_ << ", " << id_
<< ">";
return false;
}
if (!event_manager_->GetEventMeta(pub_events, &pub_meta_events_)) {
AERROR << "failed to get Pub EventMeta. node: <" << id_ << ", " << name_
<< ">";
return false;
}
if (!InitInternal()) {
AERROR << "failed to Init inner members.";
return false;
}
inited_ = true;
return true;
}
成员变量sub_meta_events_和pub_meta_events_是通过调用event_manager_的GetEventMeta函数实现的初始化,也就是将event_manager_的成员变量event_meta_map_中对应EventID的EventMeta分别添加到sub_meta_events_和pub_meta_events_中。
一个DAGConfig消息实例(参见conf/dag_streaming.config文件)的subnode_config片段如下:
# Define all nodes in DAG streaming.
subnode_config {
# 64-Lidar Input nodes.
subnodes {
id: 1
name: "LidarProcessSubnode"
reserve: "device_id:velodyne64;"
type: SUBNODE_IN
}
# Front radar Input nodes.
subnodes {
id: 2
name: "RadarProcessSubnode"
reserve: "device_id:radar;"
type: SUBNODE_IN
}
# Fusion node.
subnodes {
id: 31
name: "FusionSubnode"
reserve: "pub_driven_event_id:1001;lidar_event_id:1001;radar_event_id:1002;"
type: SUBNODE_OUT
}
# TrafficLight Preprocess node.
subnodes {
id: 41
name: "TLPreprocessorSubnode"
type: SUBNODE_IN
}
# TrafficLight process node.
subnodes {
id: 42
name: "TLProcSubnode"
type: SUBNODE_OUT
}
}
接着来看看ProcEvents()函数,该函数是Subnode处理event的通用接口,必须被派生类重写:
// @brief Subnode process interface, should be implemented in derived class.
// @return Status.
virtual apollo::common::Status ProcEvents() = 0;
再来看看Run()函数,对于类型不是SUBNODE_IN的子节点,会在while循环中一直调用ProcEvents()函数:
void Subnode::Run() {
if (!inited_) {
AERROR << "Subnode not inited, run failed. node: <" << id_ << ", " << name_
<< ">";
return;
}
if (type_ == DAGConfig::SUBNODE_IN) {
AINFO << "Subnode == SUBNODE_IN, EXIT THREAD. subnode:" << DebugString();
return;
}
while (!stop_) {
Status status = ProcEvents();
++total_count_;
if (status.code() == ErrorCode::PERCEPTION_ERROR) {
++failed_count_;
AWARN << "Subnode: " << name_ << " proc event failed. "
<< " total_count: " << total_count_
<< " failed_count: " << failed_count_;
continue;
}
// FATAL error, so exit thread.
if (status.code() == ErrorCode::PERCEPTION_FATAL) {
AERROR << "Subnode: " << name_ << " proc event FATAL error, EXIT. "
<< " total_count: " << total_count_
<< " failed_count: " << failed_count_;
break;
}
}
}
注意,类型是SUBNODE_IN的子节点包括CameraProcessSubnode、LidarProcessSubnode、RadarProcessSubnode、MotionService和TLPreprocessorSubnode,这些类中的ProcEvents()函数的实现非常简单:
apollo::common::Status ProcEvents() override {
return apollo::common::Status::OK();
}
首先来看看DAGStreaming类,主要的成员变量如下:
EventManager event_manager_;
SharedDataManager shared_data_manager_;
bool inited_ = false;
std::unique_ptr monitor_;
// NOTE(Yangguang Li): Guarantee Sunode should be firstly called destructor.
// Subnode depends the EventManager and SharedDataManager.
static SubnodeMap subnode_map_;
// subnode has order, IDs define the initilization order
static std::map subnode_name_map_;
Init函数读取conf/dag_streaming.config文件,根据文件中的内容来初始化相关的成员变量,在Init函数内部会调用InitSharedData和InitSubnodes函数:
bool DAGStreaming::Init(const string& dag_config_path) {
if (inited_) {
AWARN << "DAGStreaming Init twice.";
return true;
}
DAGConfig dag_config;
string content;
if (!apollo::common::util::GetContent(dag_config_path, &content)) {
AERROR << "failed to laod DAGConfig file: " << dag_config_path;
return false;
}
if (!TextFormat::ParseFromString(content, &dag_config)) {
AERROR << "failed to Parse DAGConfig proto: " << dag_config_path;
return false;
}
if (!event_manager_.Init(dag_config.edge_config())) {
AERROR << "failed to Init EventManager. file: " << dag_config_path;
return false;
}
if (!InitSharedData(dag_config.data_config()) || !InitSubnodes(dag_config)) {
return false;
}
inited_ = true;
AINFO << "DAGStreaming Init success.";
return true;
}
Run()函数内部调用的是Schedule()函数,Schedule()函数的内部实现调用了Thread类的接口,具体代码如下:
void DAGStreaming::Run() { Schedule(); }
void DAGStreaming::Schedule() {
monitor_->Start();
// start all subnodes.
for (auto& pair : subnode_map_) {
pair.second->Start();
}
AINFO << "DAGStreaming start to schedule...";
for (auto& pair : subnode_map_) {
pair.second->Join();
}
monitor_->Join();
AINFO << "DAGStreaming schedule exit.";
}
Stop()函数的内部实现使用的都是Thread类的接口,具体代码如下:
void DAGStreaming::Stop() {
monitor_->Stop();
// stop all subnodes.
for (auto& pair : subnode_map_) {
pair.second->Stop();
}
// sleep 100 ms
usleep(100000);
// kill thread which is blocked
for (auto& pair : subnode_map_) {
if (pair.second->IsAlive()) {
AINFO << "pthread_cancel to thread " << pair.second->Tid();
pthread_cancel(pair.second->Tid());
}
}
AINFO << "DAGStreaming is stoped.";
}
最后来看下GetSubnodeByName函数,这是一个静态函数,用来获取指定名称Subnode的对象的指针:
Subnode* DAGStreaming::GetSubnodeByName(std::string name) {
std::map::iterator iter =
subnode_name_map_.find(name);
if (iter != subnode_name_map_.end()) {
return subnode_map_[iter->second].get();
}
return nullptr;
}
感知模块在Init()函数中会调用RegistAllOnboardClass()函数,注册一系列类以完成模块启动后的各项工作,相关代码如下:
void Perception::RegistAllOnboardClass() {
/// regist sharedata
RegisterFactoryLidarObjectData();
RegisterFactoryRadarObjectData();
RegisterFactoryCameraObjectData();
RegisterFactoryCameraSharedData();
RegisterFactoryCIPVObjectData();
RegisterFactoryLaneSharedData();
RegisterFactoryFusionSharedData();
traffic_light::RegisterFactoryTLPreprocessingData();
/// regist subnode
RegisterFactoryLidarProcessSubnode();
RegisterFactoryRadarProcessSubnode();
RegisterFactoryCameraProcessSubnode();
RegisterFactoryCIPVSubnode();
RegisterFactoryLanePostProcessingSubnode();
RegisterFactoryAsyncFusionSubnode();
RegisterFactoryFusionSubnode();
RegisterFactoryMotionService();
lowcostvisualizer::RegisterFactoryVisualizationSubnode();
traffic_light::RegisterFactoryTLPreprocessorSubnode();
traffic_light::RegisterFactoryTLProcSubnode();
}
我们可以以此为入口了解各个子模块的工作逻辑,下面以RegisterFactoryLidarProcessSubnode为例进行说明。代码中其实并不存在RegisterFactoryLidarProcessSubnode()这个函数,该函数的定义其实是由宏完成的,相关代码如下:
/// modules/perception/onboard/subnode.h
#define REGISTER_SUBNODE(name) REGISTER_CLASS(Subnode, name)
/// modules/perception/lib/base/registerer.h
#define REGISTER_CLASS(clazz, name) \
class ObjectFactory##name : public apollo::perception::ObjectFactory { \
public: \
virtual ~ObjectFactory##name() {} \
virtual perception::Any NewInstance() { \
return perception::Any(new name()); \
} \
}; \
inline void RegisterFactory##name() { \
perception::FactoryMap &map = perception::GlobalFactoryMap()[#clazz]; \
if (map.find(#name) == map.end()) map[#name] = new ObjectFactory##name(); \
}
而在obstacle/onboard/lidar_process_subnode.h文件中使用了上面这个宏:
REGISTER_SUBNODE(LidarProcessSubnode);
于是就会生成一个名称为ObjectFactoryLidarProcessSubnode的类,该类继承自apollo::perception::ObjectFactory,并且还生成了RegisterFactoryLidarProcessSubnode()函数,宏展开之后的代码如下:
//REGISTER_SUBNODE(LidarProcessSubnode);
//REGISTER_CLASS(Subnode, LidarProcessSubnode);
class ObjectFactoryLidarProcessSubnode : public apollo::perception::ObjectFactory {
public:
virtual ~ObjectFactoryLidarProcessSubnode() {}
virtual perception::Any NewInstance() {
return perception::Any(new LidarProcessSubnode());
}
};
inline void RegisterFactoryLidarProcessSubnode() {
perception::FactoryMap &map = perception::GlobalFactoryMap()["Subnode"];
if (map.find("LidarProcessSubnode") == map.end()) map["LidarProcessSubnode"] = new ObjectFactoryname();
}
ObjectFactoryLidarProcessSubnode类和RegisterFactoryLidarProcessSubnode()函数一起就可以完成LidarProcessSubnode类在
Subnode类对应的FactoryMap对象中的注册。
最后再来复习一下,一个FactoryMap对象存储的是派生类名称与一个指向该派生类对象的指针的关联,而一个BaseClassMap对象存储的是基类名称与一个FactoryMap对象的关联:
typedef std::unordered_map FactoryMap;
typedef std::unordered_map BaseClassMap;
BaseClassMap &GlobalFactoryMap();