概述
什么是Mainboard?
Mainboard 是Apollo Cyber RT框架的核心启动器(Launcher),负责加载和启动所有自动驾驶模块。它是一个通用的模块加载工具,位于 /apollo/cyber/mainboard/。
核心作用
- 统一启动入口: 所有Apollo模块(Planning、Control、Perception等)都通过mainboard启动
 - 动态加载: 运行时动态加载.so共享库文件
 - 配置驱动: 通过DAG配置文件定义要加载的模块和组件
 - 生命周期管理: 管理组件的初始化、运行和关闭流程
 
基本使用方式
mainboard -d /apollo/modules/planning/dag/planning.dag
参数说明:
-d: 指定DAG配置文件路径(可以指定多个)-p: 指定进程组名称(可选)-s: 指定调度策略名称(可选)
核心组件架构
Mainboard由以下几个核心组件构成:
1. 主程序 (mainboard.cc)
源码位置: /apollo/cyber/mainboard/mainboard.cc
int main(int argc, char** argv) {
  // 1. 解析命令行参数
  ModuleArgument module_args;
  module_args.ParseArgument(argc, argv);
  // 2. 初始化Cyber RT框架
  apollo::cyber::Init(argv[0]);
  // 3. 创建模块控制器并初始化
  ModuleController controller(module_args);
  if (!controller.Init()) {
    controller.Clear();
    AERROR << "module start error.";
    return -1;
  }
  // 4. 等待关闭信号
  apollo::cyber::WaitForShutdown();
  // 5. 清理资源
  controller.Clear();
  AINFO << "exit mainboard.";
  return 0;
}
关键流程:
- 解析命令行参数(DAG文件路径等)
 - 初始化Cyber RT框架
 - 加载并初始化所有模块
 - 阻塞等待直到收到关闭信号
 - 清理所有资源并退出
 
2. 模块参数解析器 (ModuleArgument)
源码位置: /apollo/cyber/mainboard/module_argument.h|cc
职责:
- 解析命令行参数
 - 验证参数合法性
 - 存储DAG文件路径列表
 
核心数据成员:
class ModuleArgument {
 private:
  std::list<std::string> dag_conf_list_;  // DAG文件列表
  std::string binary_name_;                // 二进制程序名
  std::string process_group_;              // 进程组名称
  std::string sched_name_;                 // 调度器名称
};
支持的命令行选项:
-h, --help              : 显示帮助信息
-d, --dag_conf=FILE     : 指定DAG配置文件(可多次使用)
-p, --process_group=NAME: 指定进程组(默认: mainboard_default)
-s, --sched_name=NAME   : 指定调度策略(默认: CYBER_DEFAULT)
示例:
mainboard -d planning.dag -d control.dag -p planning_group -s CYBER_DEFAULT
3. 模块控制器 (ModuleController)
源码位置: /apollo/cyber/mainboard/module_controller.h|cc
职责:
- 加载DAG配置文件
 - 动态加载.so库文件
 - 创建和初始化Component实例
 - 管理Component生命周期
 
核心数据成员:
class ModuleController {
 private:
  ModuleArgument args_;                                      // 命令行参数
  class_loader::ClassLoaderManager class_loader_manager_;   // 类加载器管理器
  std::vector<std::shared_ptr<ComponentBase>> component_list_; // 组件列表
  int total_component_nums = 0;                             // 组件总数
  bool has_timer_component = false;                         // 是否有定时组件
};
核心方法:
bool Init();                                    // 初始化(调用LoadAll)
bool LoadAll();                                 // 加载所有DAG文件
bool LoadModule(const std::string& path);       // 加载单个DAG文件
bool LoadModule(const DagConfig& dag_config);   // 加载DAG配置
void Clear();                                   // 清理所有资源
4. 类加载器 (ClassLoader & ClassLoaderManager)
源码位置:
/apollo/cyber/class_loader/class_loader.h|cc/apollo/cyber/class_loader/class_loader_manager.h|cc
ClassLoader职责:
- 封装dlopen/dlsym等底层API
 - 加载.so动态库
 - 创建类实例
 - 管理库的引用计数
 
ClassLoaderManager职责:
- 管理多个ClassLoader实例
 - 提供统一的类创建接口
 - 避免重复加载同一个库
 
核心接口:
class ClassLoaderManager {
 public:
  // 加载动态库
  bool LoadLibrary(const std::string& library_path);
  // 创建类实例(根据类名)
  template <typename Base>
  std::shared_ptr<Base> CreateClassObj(const std::string& class_name);
  // 卸载所有库
  void UnloadAllLibrary();
};
启动流程详解
完整启动流程图
用户执行命令
    ↓
mainboard启动
    ↓
1. ModuleArgument::ParseArgument()  ← 解析命令行参数
    ↓
2. apollo::cyber::Init()             ← 初始化Cyber RT
    ├─ InitLogger()                  ← 初始化日志系统
    ├─ SysMo::Instance()             ← 初始化系统监控
    ├─ 注册SIGINT信号处理器
    └─ SetState(STATE_INITIALIZED)
    ↓
3. ModuleController::Init()          ← 初始化模块控制器
    ↓
4. ModuleController::LoadAll()       ← 加载所有模块
    ├─ 解析DAG文件路径(支持相对/绝对路径)
    ├─ 统计Component数量
    └─ 遍历每个DAG文件
        ↓
5. ModuleController::LoadModule(path)
    ├─ 解析DAG配置(Protobuf)
    └─ 对每个module_config:
        ├─ ClassLoaderManager::LoadLibrary()  ← 加载.so文件
        └─ 对每个component:
            ├─ CreateClassObj<ComponentBase>()  ← 创建实例
            └─ component->Initialize(config)     ← 初始化组件
                ├─ 创建Node
                ├─ 加载配置文件
                ├─ 调用Component::Init()        ← 用户实现
                ├─ 创建Reader订阅消息
                └─ 注册到Scheduler调度器
    ↓
6. apollo::cyber::WaitForShutdown()  ← 阻塞等待关闭信号
    ↓
7. ModuleController::Clear()         ← 清理资源
    ├─ 调用所有component->Shutdown()
    └─ ClassLoaderManager::UnloadAllLibrary()
详细步骤说明
步骤1: 参数解析
void ModuleArgument::ParseArgument(const int argc, char* const argv[]) {
  binary_name_ = std::string(basename(argv[0]));
  GetOptions(argc, argv);  // 解析 -d, -p, -s 等参数
  // 设置默认值
  if (process_group_.empty()) {
    process_group_ = DEFAULT_process_group_;  // "mainboard_default"
  }
  if (sched_name_.empty()) {
    sched_name_ = DEFAULT_sched_name_;        // "CYBER_DEFAULT"
  }
  // 保存到全局数据
  GlobalData::Instance()->SetProcessGroup(process_group_);
  GlobalData::Instance()->SetSchedName(sched_name_);
}
步骤2: Cyber RT初始化
bool Init(const char* binary_name) {
  // 1. 初始化日志系统
  InitLogger(binary_name);
  // 2. 初始化系统监控
  SysMo::Instance();
  // 3. 注册信号处理器(响应Ctrl+C)
  std::signal(SIGINT, OnShutdown);
  // 4. 注册退出处理器
  std::atexit(ExitHandle);
  // 5. 设置状态为已初始化
  SetState(STATE_INITIALIZED);
  return true;
}
关键初始化:
- 日志系统: glog + 异步日志
 - 调度器: Scheduler单例
 - 拓扑管理: TopologyManager(服务发现)
 - 传输层: Transport(通信基础设施)
 
步骤3-5: 加载模块
bool ModuleController::LoadAll() {
  const std::string work_root = common::WorkRoot();  // /apollo
  std::vector<std::string> paths;
  // 解析每个DAG文件的完整路径
  for (auto& dag_conf : args_.GetDAGConfList()) {
    std::string module_path = "";
    if (dag_conf == common::GetFileName(dag_conf)) {
      // 情况1: 纯文件名 -> 到 /apollo/dag 下查找
      module_path = common::GetAbsolutePath(dag_root_path, dag_conf);
    } else if (dag_conf[0] == '/') {
      // 情况2: 绝对路径
      module_path = dag_conf;
    } else {
      // 情况3: 相对路径 -> 相对于当前目录或work_root
      module_path = common::GetAbsolutePath(current_path, dag_conf);
      if (!common::PathExists(module_path)) {
        module_path = common::GetAbsolutePath(work_root, dag_conf);
      }
    }
    paths.emplace_back(std::move(module_path));
  }
  // 加载每个模块
  for (auto module_path : paths) {
    if (!LoadModule(module_path)) {
      AERROR << "Failed to load module: " << module_path;
      return false;
    }
  }
  return true;
}
LoadModule详细过程:
bool ModuleController::LoadModule(const std::string& path) {
  // 1. 解析DAG文件(Protobuf格式)
  DagConfig dag_config;
  if (!common::GetProtoFromFile(path, &dag_config)) {
    return false;
  }
  // 2. 遍历每个module_config
  for (auto module_config : dag_config.module_config()) {
    // 3. 加载动态库
    std::string load_path = module_config.module_library();
    class_loader_manager_.LoadLibrary(load_path);
    // 4. 创建普通Component
    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);
      // 初始化Component
      if (base == nullptr || !base->Initialize(component.config())) {
        return false;
      }
      // 保存到列表
      component_list_.emplace_back(std::move(base));
    }
    // 5. 创建定时Component
    for (auto& component : module_config.timer_components()) {
      // 类似处理...
    }
  }
  return true;
}
步骤6: 等待关闭
inline void WaitForShutdown() {
  while (!IsShutdown()) {
    std::this_thread::sleep_for(std::chrono::milliseconds(200));
  }
}
主线程在此阻塞,等待以下事件之一:
- 收到SIGINT信号(Ctrl+C)
 - 其他线程调用
SetState(STATE_SHUTTING_DOWN) 
步骤7: 清理资源
void ModuleController::Clear() {
  // 1. 关闭所有Component
  for (auto& component : component_list_) {
    component->Shutdown();  // 停止Reader、清理资源
  }
  // 2. 清空Component列表
  component_list_.clear();
  // 3. 卸载所有动态库
  class_loader_manager_.UnloadAllLibrary();
}
动态库加载机制
ClassLoader工作原理
ClassLoader封装了Linux的动态链接库加载机制(dlopen/dlsym)。
1. 库加载流程
bool ClassLoader::LoadLibrary() {
  // 使用dlopen打开.so文件
  void* handle = dlopen(library_path_.c_str(), RTLD_LAZY | RTLD_LOCAL);
  if (!handle) {
    AERROR << "Failed to load library: " << dlerror();
    return false;
  }
  loadlib_ref_count_++;
  return true;
}
2. 类创建机制
Component类需要通过宏注册到全局注册表:
// 在Component实现文件中
CYBER_REGISTER_COMPONENT(PlanningComponent)
// 宏展开后实际上是:
CLASS_LOADER_REGISTER_CLASS(PlanningComponent, apollo::cyber::ComponentBase)
这个宏的作用:
- 在动态库加载时,向全局注册表添加类的创建函数
 - 类名 → 工厂函数的映射关系
 
3. 实例创建
template <typename Base>
std::shared_ptr<Base> ClassLoader::CreateClassObj(
    const std::string& class_name) {
  // 从全局注册表中查找类名对应的工厂函数
  Base* class_object = utility::CreateClassObj<Base>(class_name, this);
  if (class_object == nullptr) {
    return std::shared_ptr<Base>();
  }
  // 使用自定义删除器管理引用计数
  std::shared_ptr<Base> classObjSharePtr(
      class_object,
      std::bind(&ClassLoader::OnClassObjDeleter<Base>, this, std::placeholders::_1)
  );
  return classObjSharePtr;
}
ClassLoaderManager管理机制
class ClassLoaderManager {
 private:
  // 库路径 → ClassLoader的映射
  std::map<std::string, ClassLoader*> libpath_loader_map_;
};
bool ClassLoaderManager::LoadLibrary(const std::string& library_path) {
  // 检查是否已加载
  if (libpath_loader_map_.find(library_path) != libpath_loader_map_.end()) {
    return true;  // 避免重复加载
  }
  // 创建新的ClassLoader并加载库
  ClassLoader* loader = new ClassLoader(library_path);
  loader->LoadLibrary();
  libpath_loader_map_[library_path] = loader;
  return true;
}
好处:
- 避免同一个库被加载多次
 - 统一管理所有ClassLoader
 - 支持按需卸载
 
Component生命周期管理
Component类层次结构
ComponentBase (抽象基类)
    ↑
    ├─ Component<M0, M1, M2, M3>  (消息驱动组件)
    └─ TimerComponent              (定时触发组件)
生命周期阶段
1. 创建阶段
// mainboard通过ClassLoader创建实例
std::shared_ptr<ComponentBase> base =
    class_loader_manager_.CreateClassObj<ComponentBase>("PlanningComponent");
2. 初始化阶段
bool Component<M0>::Initialize(const ComponentConfig& config) {
  // 1. 创建Node(通信节点)
  node_.reset(new Node(config.name()));
  // 2. 加载配置文件和Flag文件
  LoadConfigFiles(config);
  // 3. 调用用户实现的Init()方法
  if (!Init()) {
    AERROR << "Component Init() failed.";
    return false;
  }
  // 4. 创建Reader订阅消息
  ReaderConfig reader_cfg;
  reader_cfg.channel_name = config.readers(0).channel();
  reader_cfg.qos_profile.CopyFrom(config.readers(0).qos_profile());
  auto func = [self](const std::shared_ptr<M0>& msg) {
    auto ptr = self.lock();
    if (ptr) {
      ptr->Process(msg);  // 收到消息时调用Proc
    }
  };
  auto reader = node_->CreateReader<M0>(reader_cfg, func);
  readers_.emplace_back(std::move(reader));
  // 5. 注册到调度器
  auto sched = scheduler::Instance();
  return sched->CreateTask(factory, node_->Name());
}
关键步骤:
- 创建Cyber Node(通信节点)
 - 加载配置文件(pb.txt)和Flag文件(.conf)
 - 调用用户的Init()方法进行自定义初始化
 - 创建Reader并注册消息回调
 - 将Component作为Task注册到Scheduler
 
3. 运行阶段
消息驱动模式 (Component):
// 当订阅的channel有新消息时
Reader回调 → Component::Process() → Component::Proc() (用户实现)
定时触发模式 (TimerComponent):
// 按固定时间间隔触发
Timer触发 → TimerComponent::Process() → TimerComponent::Proc() (用户实现)
4. 关闭阶段
virtual void Shutdown() {
  if (is_shutdown_.exchange(true)) {
    return;  // 避免重复关闭
  }
  // 1. 调用用户的清理方法
  Clear();
  // 2. 关闭所有Reader
  for (auto& reader : readers_) {
    reader->Shutdown();
  }
  // 3. 从调度器中移除Task
  scheduler::Instance()->RemoveTask(node_->Name());
}
Component示例
以Planning模块为例:
// planning_component.h
class PlanningComponent final
    : public cyber::Component<prediction::PredictionObstacles,
                              canbus::Chassis,
                              localization::LocalizationEstimate> {
 public:
  bool Init() override;
  bool Proc(const std::shared_ptr<prediction::PredictionObstacles>& pred,
            const std::shared_ptr<canbus::Chassis>& chassis,
            const std::shared_ptr<localization::LocalizationEstimate>& loc) override;
};
// 注册到类加载器
CYBER_REGISTER_COMPONENT(PlanningComponent)
信号处理与优雅关闭
信号处理机制
1. 注册信号处理器
在Cyber RT初始化时注册:
bool Init(const char* binary_name) {
  // 注册SIGINT处理器(Ctrl+C)
  std::signal(SIGINT, OnShutdown);
  // 注册退出处理器
  std::atexit(ExitHandle);
  return true;
}
2. 信号处理函数
void OnShutdown(int sig) {
  (void)sig;
  if (GetState() != STATE_SHUTDOWN) {
    SetState(STATE_SHUTTING_DOWN);  // 修改全局状态
  }
}
3. 退出处理函数
void ExitHandle() {
  Clear();  // 清理Cyber RT资源
}
关闭流程
用户按Ctrl+C
    ↓
SIGINT信号触发
    ↓
OnShutdown() → SetState(STATE_SHUTTING_DOWN)
    ↓
WaitForShutdown()检测到状态变化,退出循环
    ↓
mainboard主函数继续执行
    ↓
ModuleController::Clear()
    ├─ 遍历所有Component
    │   └─ component->Shutdown()
    │       ├─ 停止Reader接收消息
    │       ├─ 从Scheduler移除Task
    │       └─ 调用用户Clear()方法
    ↓
ClassLoaderManager::UnloadAllLibrary()
    └─ 卸载所有.so动态库
    ↓
程序退出时触发atexit
    ↓
ExitHandle() → cyber::Clear()
    ├─ TaskManager::CleanUp()
    ├─ TimingWheel::CleanUp()
    ├─ Scheduler::CleanUp()
    └─ TopologyManager::CleanUp()
优雅关闭的保证
- 状态同步: 使用原子变量
is_shutdown_防止重复关闭 - 资源顺序释放: 先停止业务逻辑,再清理通信资源
 - 异常安全: 即使某个Component关闭失败,也继续清理其他资源
 
完整调用链路
启动链路总览
main()
  └─ ModuleArgument::ParseArgument()
  └─ cyber::Init()
      ├─ InitLogger()
      ├─ SysMo::Instance()
      ├─ signal(SIGINT, OnShutdown)
      └─ atexit(ExitHandle)
  └─ ModuleController::Init()
      └─ LoadAll()
          └─ LoadModule(path)
              └─ GetProtoFromFile(path, &dag_config)
              └─ for each module_config:
                  ├─ ClassLoaderManager::LoadLibrary(lib_path)
                  │   └─ ClassLoader::LoadLibrary()
                  │       └─ dlopen(lib_path)
                  └─ for each component:
                      ├─ CreateClassObj<ComponentBase>(class_name)
                      │   └─ utility::CreateClassObj() [查找注册表]
                      └─ component->Initialize(config)
                          ├─ Node::Node(name)
                          ├─ LoadConfigFiles()
                          ├─ Init() [用户实现]
                          ├─ CreateReader<M0>(config, callback)
                          └─ Scheduler::CreateTask()
  └─ WaitForShutdown()
  └─ ModuleController::Clear()
      ├─ component->Shutdown()
      └─ UnloadAllLibrary()
消息处理链路
外部消息发布到Channel
    ↓
Transport层接收
    ↓
DataDispatcher分发给订阅者
    ↓
Reader收到消息
    ↓
Scheduler调度Task执行
    ↓
Component::Process(msg)
    ↓
Component::Proc(msg) [用户实现]
    └─ 执行业务逻辑
    └─ 通过Writer发布结果
实际使用示例
示例1: 启动Planning模块
DAG配置文件 (planning.dag)
module_config {
  module_library : "/apollo/bazel-bin/modules/planning/libplanning_component.so"
  components {
    class_name : "PlanningComponent"
    config {
      name: "planning"
      config_file_path: "/apollo/modules/planning/conf/planning_config.pb.txt"
      flag_file_path: "/apollo/modules/planning/conf/planning.conf"
      readers: [
        {
          channel: "/apollo/prediction"
        },
        {
          channel: "/apollo/canbus/chassis"
          qos_profile: {
            depth : 15
          }
        },
        {
          channel: "/apollo/localization/pose"
        }
      ]
    }
  }
}
启动命令
mainboard -d /apollo/modules/planning/dag/planning.dag
启动流程
- Mainboard启动,解析DAG文件
 - 加载
libplanning_component.so - 创建
PlanningComponent实例 - 初始化Component:
- 创建名为"planning"的Node
 - 加载planning_config.pb.txt和planning.conf
 - 调用PlanningComponent::Init()
 - 订阅3个channel的消息
 
 - 等待消息到达,触发规划计算
 
示例2: 同时启动多个模块
mainboard -d /apollo/modules/planning/dag/planning.dag \
          -d /apollo/modules/control/dag/control.dag \
          -d /apollo/modules/prediction/dag/prediction.dag \
          -p autonomous_driving \
          -s CYBER_DEFAULT
所有模块在同一个进程中运行,共享:
- 同一个Scheduler
 - 同一个Transport层
 - 同一个进程组
 
示例3: 创建自定义Component
步骤1: 定义Component类
// my_component.h
#include "cyber/component/component.h"
#include "cyber/examples/proto/examples.pb.h"
class MyComponent : public apollo::cyber::Component<Driver> {
 public:
  bool Init() override;
  bool Proc(const std::shared_ptr<Driver>& msg) override;
};
CYBER_REGISTER_COMPONENT(MyComponent)
步骤2: 实现Component
// my_component.cc
#include "my_component.h"
bool MyComponent::Init() {
  AINFO << "MyComponent Init";
  // 自定义初始化逻辑
  return true;
}
bool MyComponent::Proc(const std::shared_ptr<Driver>& msg) {
  AINFO << "Received message: " << msg->msg_id();
  // 处理消息
  return true;
}
步骤3: 编译为动态库
# BUILD
cc_binary(
    name = "libmy_component.so",
    linkshared = True,
    linkstatic = False,
    srcs = ["my_component.cc", "my_component.h"],
    deps = [
        "//cyber",
    ],
)
步骤4: 创建DAG配置
# my.dag
module_config {
  module_library : "/apollo/bazel-bin/mymodule/libmy_component.so"
  components {
    class_name : "MyComponent"
    config {
      name: "my_component"
      readers {
        channel: "/apollo/test_channel"
      }
    }
  }
}
步骤5: 启动
mainboard -d my.dag
总结
Mainboard核心特点
- 通用性: 一个工具启动所有模块
 - 灵活性: 通过DAG配置文件定义加载内容
 - 动态性: 运行时加载动态库,无需重新编译
 - 解耦合: 业务逻辑与启动框架分离
 
关键设计模式
- 工厂模式: ClassLoader使用工厂创建Component实例
 - 注册模式: CYBER_REGISTER_COMPONENT宏注册类到全局表
 - 单例模式: Scheduler、TopologyManager等核心服务
 - 观察者模式: Reader/Writer的发布订阅机制
 
最佳实践
- 一个模块一个DAG: 便于管理和复用
 - 合理使用进程组: 隔离不同优先级的任务
 - 优雅关闭: 在Component::Clear()中清理资源
 - 错误处理: Init()和Proc()返回false时正确处理
 
参考文件
- 
源码文件:
/apollo/cyber/mainboard/mainboard.cc:27-48/apollo/cyber/mainboard/module_controller.cc:29-141/apollo/cyber/mainboard/module_argument.cc:28-135/apollo/cyber/class_loader/class_loader_manager.h:32-103/apollo/cyber/init.cc:98-152/apollo/cyber/component/component_base.h:41-121
 - 
配置示例:
/apollo/modules/planning/dag/planning.dag:1-31/apollo/modules/control/dag/control.dag:1-12
 
