第一篇日志也是最后一篇
就当作分析Apollo无人车系统的纪念吧。
此博客主要记录我的无人车之路,目前的想法是把Apollo做裁剪与移植,去除自己不需要的东西。并分析每一行代码。与看到的论文作结合深入理解论文在工程中的实现。
adapter功能说明
adapter模块是整个Apollo工程的核心接口模块,所有ros节点都是通过此模块来完成消息交互的。在整个工程中topic的订阅/发布都是在此模块中进行实现,如果需要裁剪Apollo可以直接通过对此模块一些代码的修改,来完成去掉一些驱动的支持。
Apollo的消息传输,也是通过ros进行消息的传输的。但是Apollo团队修改一个ros环境,在传输过程中,并不是通过ros msg进行传输的,而是通过google buffer protocal进行传输。而整个Apollo工程也是通过此协议设定内部的所有数据结构。
Apollo团队基本用到了所有google的开发组建
- gprotoc 用于处理内部所有数据结构
- gflag 用于分析命令行参数
- gtest 用于进行测试
- glog 用于日志输出
- adapter_gflags.h/cc 定义了一些通用的adapter模块的配置项
- adapter_manager.h/cc 定义了一个管理器类,来负责在Apollo中所有topic的订阅与发布。
- adapter.h 定义了adapter最基本的类接口。
- message_adapters.h 所有在Apollo中用到的消息定义。
在adapter.h文件中定义了AdapterBase
基类,这个类实现了所有adapter类的接口函数。由Adapter
类继承实现。从类函数名可以看出,Adapter
实现了返回当前类的topic名称,从接收的topic中取出数据,以及观察队列中是否有数据,它内部定义了两个数据队列,一个data_queue_
用于接收数据,一个observed_queue_
用于用户层面获取数据,在调用Observe
函数后,类内部会将data_queue_
复制给observed_queue_
队列。而填充data_queue_
的数据由外部的回调函数实现。在Adapter
类中的一些功能函数中,使用了std::is_base_of<google::protobuf::Message, D>::value
来判断对象的基类是否是google::protobuf::Message
类型。
在Apollo中的所有要交互的消息都使用此类。在message_adapters.h中定义了全部的消息。
namespace apollo {
namespace common {
namespace adapter {
using ChassisAdapter = Adapter<::apollo::canbus::Chassis>;
using ChassisDetailAdapter = Adapter<::apollo::canbus::ChassisDetail>;
using ControlCommandAdapter = Adapter<control::ControlCommand>;
using GpsAdapter = Adapter<apollo::localization::Gps>;
using ImuAdapter = Adapter<localization::CorrectedImu>;
using RawImuAdapter = Adapter<apollo::drivers::gnss::Imu>;
// 忽略其他 ...
这里定义了,每个要交换的数据,Adapter
是一个模板类,这里所有数据类型都是google buffer protocal。
在adapter_manager.h/cc模块中,定义了一个Adapter
类的管理器,这个管理器的中定义了所有消息的Adapter
类,通过此类统一发送与接收消息,与apollo_app.h/cc模块作结合使用。在adapter_manager.h中定义了一个名为#define REGISTER_ADAPTER(name)
的宏,此宏的参数name
是每个在message_adapters.h中定义的消息名称。在宏内部使用name
来拼接成每个消息独有的函数,例如:
static void Publish##name(const name##Adapter::DataType &data) { \
instance()->InternalPublish##name(data); \
} \
template <typename T> \
static void Fill##name##Header(const std::string &module_name, T *data) { \
static_assert(std::is_same<name##Adapter::DataType, T>::value, \
"Data type must be the same with adapter's type!"); \
instance()->name##_->FillHeader(module_name, data); \
} \
static void Add##name##Callback(name##Adapter::Callback callback) { \
CHECK(instance()->name##_) \
<< "Initialize adapter before setting callback"; \
instance()->name##_->AddCallback(callback); \
}
基本每个函数都是与Adapter
类的函数对应,只是表明生成针对本身消息的函数。在宏内部会按照消息名称name
在宏内部生成对应的消息Adapter
类型的变量,名称是消息名后跟一个'_'
号。而在AdapterManager
类内部,使用宏REGISTER_ADAPTER
宏对每个消息都注册了一遍。
/// The following code registered all the adapters of interest.
REGISTER_ADAPTER(Chassis);
REGISTER_ADAPTER(ChassisDetail);
REGISTER_ADAPTER(ControlCommand);
REGISTER_ADAPTER(Gps);
REGISTER_ADAPTER(Imu);
REGISTER_ADAPTER(RawImu);
REGISTER_ADAPTER(Localization);
REGISTER_ADAPTER(Monitor);
REGISTER_ADAPTER(Pad);
REGISTER_ADAPTER(PerceptionObstacles);
REGISTER_ADAPTER(Planning);
REGISTER_ADAPTER(PlanningPad);
REGISTER_ADAPTER(PointCloud);
REGISTER_ADAPTER(VLP16PointCloud);
// 忽略其他...
这里需要注意的是在宏REGISTER_ADAPTER
中的定义的两个函数:
//
// 两个函数,InternalEnable##name实现了当前注册的消息对主题的订阅,这里可以看到使用了配置数据结构
// config参数,来判断当前的消息对主题的操作,这里实现了对主题的订阅与发布。
//
// 而在InternalPublish##name中实现了发送数据到主题上,这里的DataType都是google buffer protocal的数据
//
void InternalEnable##name(const std::string &topic_name, \
const AdapterConfig &config) { \
name##_.reset( \
new name##Adapter(#name, topic_name, config.message_history_limit())); \
if (config.mode() != AdapterConfig::PUBLISH_ONLY && IsRos()) { \
name##subscriber_ = \
node_handle_->subscribe(topic_name, config.message_history_limit(), \
&name##Adapter::RosCallback, name##_.get()); \
} \
if (config.mode() != AdapterConfig::RECEIVE_ONLY && IsRos()) { \
name##publisher_ = node_handle_->advertise<name##Adapter::DataType>( \
topic_name, config.message_history_limit(), config.latch()); \
} \
\
observers_.push_back([this]() { name##_->Observe(); }); \
name##config_ = config; \
} \
name##Adapter *InternalGet##name() { return name##_.get(); } \
void InternalPublish##name(const name##Adapter::DataType &data) { \
/* Only publish ROS msg if node handle is initialized. */ \
if (IsRos()) { \
if (!name##publisher_.getTopic().empty()) { \
name##publisher_.publish(data); \
} else { \
AERROR << #name << " is not valid."; \
} \
} else { \
/* For non-ROS mode, just triggers the callback. */ \
if (name##_) { \
name##_->OnReceive(data); \
} else { \
AERROR << #name << " is null."; \
} \
} \
name##_->SetLatestPublished(data); \
}
修改思路
从宏REGISTER_ADAPTER
可以看出在Apollo中虽然是使用了ros作为异步消息通讯的框架,但是其修改了消息传输这一部分,按照正常的ros是不支持这以非ros message作为基类的数据结构传输的。而我的需求是让Apollo的回归到基的ros上,但是又不想大规模的破坏当前的代码结构,那么最简单的做法就是,在Apollo内部仍然使用google buffer protocal而仅仅在传输时使用ros message,这就需要在这个宏的这两个部分在进行一个数据结构的转换,将google buffer protocal转换成ros message发送,在接收到ros message时转换成google buffer protocal。
- 收集Apollo的所有gprotoc类的源文件,复制到单独的目录。
- 写一个词语法分析的小工具,将google buffer protocal转换成ros message。
- 此小工具可以自动输出一组h/cc的源文件,其中定义了两个数据结构的转换。
- 在宏
REGISTER_ADAPTER
处使用typeinfo
库,判断数据类型,并调用对应的转换函数。
g2r小工具
花了大概一周多时间,写了一个小工具 https://github.com/gA4ss/g2r.git ,目前可以实现协议的对转。
使用说明
./g2r.out -I ./protocal -o ./message -t ./transorm xxx.proto
- -I 设置include path设置google buffer protocal所在目录,处理
import
类似的语句 - -o 设置rosmsg要输出的目录
- -t 设置辅助转换**C++**源代码所在目录,生成类似代码
#include "g2r_Header.h"
void g2r_hdmap_Header(apollo::hdmap::Header& arg_gprotoc, ros_hdmap::Header::Header& arg_rosmsg) {
arg_rosmsg.version = arg_gprotoc.version();
arg_rosmsg.date = arg_gprotoc.date();
arg_rosmsg.projection = arg_gprotoc.projection();
arg_rosmsg.district = arg_gprotoc.district();
arg_rosmsg.generation = arg_gprotoc.generation();
arg_rosmsg.rev_major = arg_gprotoc.rev_major();
arg_rosmsg.rev_minor = arg_gprotoc.rev_minor();
arg_rosmsg.left = arg_gprotoc.left();
arg_rosmsg.top = arg_gprotoc.top();
arg_rosmsg.right = arg_gprotoc.right();
arg_rosmsg.bottom = arg_gprotoc.bottom();
arg_rosmsg.vendor = arg_gprotoc.vendor();
}
void r2g_hdmap_Header(ros_hdmap::Header::Header& arg_rosmsg, apollo::hdmap::Header& arg_gprotoc) {
arg_gprotoc.set_version(arg_rosmsg.version);
arg_gprotoc.set_date(arg_rosmsg.date);
arg_gprotoc.set_projection(arg_rosmsg.projection);
arg_gprotoc.set_district(arg_rosmsg.district);
arg_gprotoc.set_generation(arg_rosmsg.generation);
arg_gprotoc.set_rev_major(arg_rosmsg.rev_major);
arg_gprotoc.set_rev_minor(arg_rosmsg.rev_minor);
arg_gprotoc.set_left(arg_rosmsg.left);
arg_gprotoc.set_top(arg_rosmsg.top);
arg_gprotoc.set_right(arg_rosmsg.right);
arg_gprotoc.set_bottom(arg_rosmsg.bottom);
arg_gprotoc.set_vendor(arg_rosmsg.vendor);
}
** 目前版本存在文件嵌套的BUG。如果msg内嵌递归的文件则出错。**