严正声明:本文系作者davidhopper原创,未经许可,不得转载。
Apollo项目在处理消息循环时应用了C++设计模式之适配器模式(Adapter Pattern)。适配器其实很好理解,网上经常提到的一个例子:中国电压标准是220V,美国电压标准是110V,中国电器要在美国使用,必须借助一个变压器,这个变压器就是适配器。另外一个例子:中国插座标准是扁孔,欧洲插座标准是圆孔,中国的电源插头到欧洲使用,必须借助一个插孔转接器,这个转接器也是适配器。
具体到Apollo项目中,各模块内部的消息传递使用Google Protocol Buffer格式,各模块之间的底层消息传递目前使用ROS机制,今后可能会替换为百度自研机制。不管Apollo项目各模块之间的底层消息传递机制如何改变,我们必须确保各模块内部的消息格式不变,即使用Google Protocol Buffer格式,否则会因为底层消息传递机制的修改,导致各模块内部涉及消息处理的代码被迫修改,这既严重破坏各模块代码的独立性和正确性,也严重影响项目开发效率。
Apollo项目的解决方案比较优雅,具体方案如下。
Adapter
定义Apollo项目在modules/common/adapters/adapter.h
中定义了一个适配器模板类Adapter,代码罗列如下(省略私有成员函数、私有成员变量及公有函数实现代码):
namespace apollo {
namespace common {
namespace adapter {
// ...
template <typename D>
class Adapter : public AdapterBase {
public:
/// The user can use Adapter::DataType to get the type of the
/// underlying data.
typedef D DataType;
typedef boost::shared_ptrconst> DataPtr;
typedef typename std::list ::const_iterator Iterator;
typedef typename std::function<void(const D&)> Callback;
/**
* @brief Construct the \class Adapter object.
* @param adapter_name the name of the adapter. It is used to log
* error messages when something bad happens, to help people get an
* idea which adapter goes wrong.
* @param topic_name the topic that the adapter listens to.
* @param message_num the number of historical messages that the
* adapter stores. Older messages will be removed upon calls to
* Adapter::RosCallback().
*/
Adapter(const std::string& adapter_name, const std::string& topic_name,
size_t message_num, const std::string& dump_dir = "/tmp");
/**
* @brief returns the topic name that this adapter listens to.
*/
const std::string& topic_name() const override;
/**
* @brief reads the proto message from the file, and push it into
* the adapter's data queue.
* @param message_file the path to the file that contains a (usually
* proto) message of DataType.
*/
template <class T = D>
bool FeedFile(const std::string& message_file);
/**
* @brief push (a copy of) the input data into the data queue of
* the adapter.
* @param data the input data.
*/
void FeedData(const D& data);
/**
* @brief Data callback when receiving a message. Under the hood it calls
* the callback ROS would invoke, useful when trying to emulate the callback
* behavior when there's not a ROS.
* @param data the input data.
*/
void OnReceive(const D& message);
/**
* @brief copy the data_queue_ into the observing queue to create a
* view of data up to the call time for the user.
*/
void Observe() override;
/**
* @brief returns TRUE if the observing queue is empty.
*/
bool Empty() const override;
/**
* @brief returns TRUE if the adapter has received any message.
*/
bool HasReceived() const override;
/**
* @brief returns the most recent message in the observing queue.
*
* /note
* Please call Empty() to make sure that there is data in the
* queue before calling GetOldestObserved().
*/
const D& GetLatestObserved();
/**
* @brief returns the most recent message pointer in the observing queue.
*
* /note
* Please call Empty() to make sure that there is data in the
* queue before calling GetLatestObservedPtr().
*/
DataPtr GetLatestObservedPtr();
/**
* @brief returns the oldest message in the observing queue.
*
* /note
* Please call Empty() to make sure that there is data in the
* queue before calling GetOldestObserved().
*/
const D& GetOldestObserved() const;
/**
* @brief returns an iterator representing the head of the observing
* queue. The caller can use it to iterate over the observed data
* from the head. The API also supports range based for loop.
*/
Iterator begin() const;
/**
* @brief returns an iterator representing the tail of the observing
* queue. The caller can use it to iterate over the observed data
* from the head. The API also supports range based for loop.
*/
Iterator end() const;
/**
* @brief registers the provided callback function to the adapter,
* so that the callback function will be called once right after the
* message hits the adapter.
* @param callback the callback with signature void(const D &).
*/
void AddCallback(Callback callback);
/**
* @brief Pops out the latest added callback.
* @return false if there's no callback to pop out, true otherwise.
*/
bool PopCallback();
/**
* @brief fills the fields module_name, current timestamp and
* sequence_num in the header.
*/
void FillHeader(const std::string& module_name, D* data);
uint32_t GetSeqNum() const;
void SetLatestPublished(const D& data);
const D* GetLatestPublished();
/**
* @brief Gets message delay.
*/
double GetDelaySec();
/**
* @brief Clear the data received so far.
*/
void ClearData() override;
/**
* @brief Dumps the latest received data to file.
*/
bool DumpLatestMessage() override;
private:
// ...
};
} // namespace adapter
} // namespace common
} // namespace apollo
里面的代码大多涉及消息格式转换,根本不必理会,我们最需关心的是这个回调函数添加函数:void AddCallback(Callback callback)
,其中的Callback
定义如下:
typedef typename std::function<void(const D&)> Callback;
说白了,这就是一个消息处理函数(或函数对象),该函数接收一个数据类型为D
(模板参数)的参数,返回值为void
。当我们使用Adapter
函数将一个具体的消息处理函数(假定命名为message_handler)加入到Adapter
后,Adapter
就会经过一系列的内部操作,让message_handler顺利处理数据类型为D
的消息。
基于Adapter
模板,Apollo项目在modules/common/adapters/message_adapters.h
文件中为我们预先定义了很多消息处理适配器,包括车辆底盘、定位、导航、感知、规划、控制、监控等多种消息:
namespace apollo {
namespace common {
namespace adapter {
using ChassisAdapter = Adapter<::apollo::canbus::Chassis>;
using ChassisDetailAdapter = Adapter<::apollo::canbus::ChassisDetail>;
using ControlCommandAdapter = Adapter;
using GpsAdapter = Adapter;
using ImuAdapter = Adapter;
using RawImuAdapter = Adapter;
using LocalizationAdapter = Adapter;
using MonitorAdapter = Adapter;
using PadAdapter = Adapter;
using PerceptionObstaclesAdapter = Adapter;
using PlanningAdapter = Adapter;
using PointCloudAdapter = Adapter<::sensor_msgs::PointCloud2>;
using ImageShortAdapter = Adapter<::sensor_msgs::Image>;
using ImageLongAdapter = Adapter<::sensor_msgs::Image>;
using PredictionAdapter = Adapter;
using DriveEventAdapter = Adapter;
using TrafficLightDetectionAdapter = Adapter;
using RoutingRequestAdapter = Adapter;
using RoutingResponseAdapter = Adapter;
using RelativeOdometryAdapter =
Adapter;
using InsStatAdapter = Adapter;
using InsStatusAdapter = Adapter;
using GnssStatusAdapter = Adapter;
using SystemStatusAdapter = Adapter;
using StaticInfoAdapter = Adapter;
using MobileyeAdapter = Adapter;
using DelphiESRAdapter = Adapter;
using ContiRadarAdapter = Adapter;
using CompressedImageAdapter = Adapter;
using GnssRtkObsAdapter = Adapter;
using GnssRtkEphAdapter = Adapter;
using GnssBestPoseAdapter = Adapter;
using LocalizationMsfGnssAdapter =
Adapter;
using LocalizationMsfLidarAdapter =
Adapter;
using LocalizationMsfSinsPvaAdapter =
Adapter;
using LocalizationMsfStatusAdapter =
Adapter;
using RelativeMapAdapter = Adapter;
using NavigationAdapter = Adapter;
} // namespace adapter
} // namespace common
} // namespace apollo
AdapterManager
对适配器的调用我们可以基于各个具体的Adapter
实现消息的接收、发布,但仍然需要我们撰写代码少量与底层消息传递机制打交道的代码,显然不符合通用性要求。Apollo的解决方案是定义一个适配器管理者对象AdapterManager
,并在该类内部使用宏REGISTER_ADAPTER
来添加各种消息适配器,同时实现对应消息的接收和发布功能,该宏的定义为:
#define REGISTER_ADAPTER(name) \
public: \
static void Enable##name(const std::string &topic_name, \
const AdapterConfig &config) { \
CHECK(config.message_history_limit() > 0) \
<< "Message history limit must be greater than 0"; \
instance()->InternalEnable##name(topic_name, config); \
} \
static name##Adapter *Get##name() { \
return instance()->InternalGet##name(); \
} \
static AdapterConfig &Get##name##Config() { \
return instance()->name##config_; \
} \
static void Feed##name##Data(const name##Adapter::DataType &data) { \
if (!instance()->name##_) { \
AERROR << "Initialize adapter before feeding protobuf"; \
return; \
} \
Get##name()->FeedData(data); \
} \
static bool Feed##name##File(const std::string &proto_file) { \
if (!instance()->name##_) { \
AERROR << "Initialize adapter before feeding protobuf"; \
return false; \
} \
return Get##name()->FeedFile(proto_file); \
} \
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##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); \
} \
template <class T> \
static void Add##name##Callback( \
void (T::*fp)(const name##Adapter::DataType &data), T *obj) { \
Add##name##Callback(std::bind(fp, obj, std::placeholders::_1)); \
} \
template <class T> \
static void Add##name##Callback( \
void (T::*fp)(const name##Adapter::DataType &data)) { \
Add##name##Callback(fp); \
} \
/* Returns false if there's no callback to pop out, true otherwise. */ \
static bool Pop##name##Callback() { \
return instance()->name##_->PopCallback(); \
} \
\
private: \
std::unique_ptr##Adapter> name##_; \
ros::Publisher name##publisher_; \
ros::Subscriber name##subscriber_; \
AdapterConfig name##config_; \
\
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( \
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); \
}
宏定义似乎有些难看,我们以RoutingRequest
消息为例 ,来看一个实际例子。RoutingRequest
消息的ProtoBuf格式如下:
message RoutingRequest {
optional apollo.common.Header header = 1;
// at least two points. The first is start point, the end is final point.
// The routing must go through each point in waypoint.
repeated LaneWaypoint waypoint = 2;
repeated LaneSegment blacklisted_lane = 3;
repeated string blacklisted_road = 4;
optional bool broadcast = 5 [default = true];
}
REGISTER_ADAPTER(RoutingRequest)
展开后的代码如下所示,大家是不是看到了RoutingRequest
消息响应回调函数的添加函数:static void AddRoutingRequestCallback(RoutingRequestAdapter::Callback callback)
,以及RoutingRequest
消息发布函数:static void PublishRoutingRequest(const RoutingRequestAdapter::DataType &data)
?
public:
static void EnableRoutingRequest(const std::string &topic_Namest,
const AdapterConfig &config) {
CHECK(config.message_history_limit() > 0)
<< "Message history limit must be greater than 0";
instance()->InternalEnableRoutingRequest(topic_Namest, config);
}
static RoutingRequestAdapter *GetRoutingRequest() {
return instance()->InternalGetRoutingRequest();
}
static AdapterConfig &GetRoutingRequestConfig() {
return instance()->RoutingRequestconfig_;
}
static bool FeedRoutingRequestFile(const std::string &proto_file) {
if (!instance()->RoutingRequest_) {
AERROR << "Initialize adapter before feeding protobuf";
return false;
}
return GetRoutingRequest()->FeedFile(proto_file);
}
static void PublishRoutingRequest(const RoutingRequestAdapter::DataType &data) {
instance()->InternalPublishRoutingRequest(data);
}
template
static void FillRoutingRequestHeader(const std::string &module_RoutingRequest, T *data) {
static_assert(std::is_same::value,
"Data type must be the same with adapter's type!");
instance()->RoutingRequest_->FillHeader(module_RoutingRequest, data);
}
static void AddRoutingRequestCallback(RoutingRequestAdapter::Callback callback) {
CHECK(instance()->RoutingRequest_)
<< "Initialize adapter before setting callback";
instance()->RoutingRequest_->AddCallback(callback);
}
template <class T>
static void AddRoutingRequestCallback(
void (T::*fp)(const RoutingRequestAdapter::DataType &data), T *obj) {
AddRoutingRequestCallback(std::bind(fp, obj, std::placeholders::_1));
}
template <class T>
static void AddRoutingRequestCallback(
void (T::*fp)(const RoutingRequestAdapter::DataType &data)) {
AddRoutingRequestCallback(fp);
}
/* Returns false if there's no callback to pop out, true otherwise. */
static bool PopRoutingRequestCallback() {
return instance()->RoutingRequest_->PopCallback();
}
private:
std::unique_ptr RoutingRequest_;
ros::Publisher RoutingRequestpublisher_;
ros::Subscriber RoutingRequestsubscriber_;
AdapterConfig RoutingRequestconfig_;
void InternalEnableRoutingRequest(const std::string &topic_Namest,
const AdapterConfig &config) {
RoutingRequest_.reset(
new RoutingRequestAdapter(“RoutingRequest”, topic_Namest, config.message_history_limit()));
if (config.mode() != AdapterConfig::PUBLISH_ONLY && IsRos()) {
RoutingRequestsubscriber_ =
node_handle_->subscribe(topic_Namest, config.message_history_limit(),
&RoutingRequestAdapter::OnReceive, RoutingRequest_.get());
}
if (config.mode() != AdapterConfig::RECEIVE_ONLY && IsRos()) {
RoutingRequestpublisher_ = node_handle_->advertise(
topic_Namest, config.message_history_limit(), config.latch());
}
observers_.push_back([this]() { RoutingRequest_->Observe(); });
RoutingRequestconfig_ = config;
}
RoutingRequestAdapter *InternalGetRoutingRequest() { return RoutingRequest_.get(); }
void InternalPublishRoutingRequest(const RoutingRequestAdapter::DataType &data) {
/* Only publish ROS msg if node handle is initialized. */
if (IsRos()) {
if (!RoutingRequestpublisher_.getTopic().empty()) {
RoutingRequestpublisher_.publish(data);
} else {
AERROR << #RoutingRequest << " is not valid.";
}
} else {
/* For non-ROS mode, just triggers the callback. */
if (RoutingRequest_) {
RoutingRequest_->OnReceive(data);
} else {
AERROR << #RoutingRequest << " is null.";
}
}
RoutingRequest_->SetLatestPublished(data);
}
目前已基本将Apollo项目的消息适配器及消息回调函数阐述完毕,剩下的问题是如何使用?下面还是以RoutingRequest
消息为例进行阐述。
AdapterManager
在Routing
类的初始化函数Routing::Init()
中添加如下代码,完成AdapterManager
的初始化:
AdapterManager::Init(FLAGS_routing_adapter_config_filename);
RoutingRequest
消息响应函数在Routing
类中撰写RoutingRequest
消息响应函数:void Routing::OnRoutingRequest(
:
const RoutingRequest &routing_request)
void Routing::OnRoutingRequest(
const RoutingRequest &routing_request) {
AINFO << "Get new routing request:" << routing_request.DebugString();
RoutingResponse routing_response;
apollo::common::monitor::MonitorLogBuffer buffer(&monitor_logger_);
const auto& fixed_request = FillLaneInfoIfMissing(routing_request);
if (!navigator_ptr_->SearchRoute(fixed_request, &routing_response)) {
AERROR << "Failed to search route with navigator.";
buffer.WARN("Routing failed! " + routing_response.status().msg());
return;
}
buffer.INFO("Routing success!");
AdapterManager::PublishRoutingResponse(routing_response);
return;
}
RoutingRequest
注册到适配器管理器在Routing
类的初始化函数Routing::Init()
中添加如下代码,完成消息响应函数RoutingRequest
到适配器管理器的注册。注意适配器管理器AdapterManager
中消息响应函数的注册函数名称格式为Add+MessageName+Callback,如下所示:
AdapterManager::AddRoutingRequestCallback(&Routing::OnRoutingRequest, this);
RoutingRequest
消息目前已经完成RoutingRequest
消息的响应函数注册,但还没有消息发布函数。Apollo 2.0版本中,除测试模块外,另有两处发布该消息,一处是在dreamview模块,一处在planning模块。dreamview模块是在SimulationWorldUpdater
类的构造函数内中调用AdapterManager::PublishRoutingRequest(routing_request)
发布RoutingRequest
消息:
SimulationWorldUpdater::SimulationWorldUpdater(WebSocketHandler *websocket, SimControl *sim_control, const MapService *map_service, bool routing_from_file)
: sim_world_service_(map_service, routing_from_file),
map_service_(map_service),
websocket_(websocket),
sim_control_(sim_control) {
// ..
websocket_->RegisterMessageHandler(
"SendRoutingRequest",
[this](const Json &json, WebSocketHandler::Connection *conn) {
RoutingRequest routing_request;
bool succeed = ConstructRoutingRequest(json, &routing_request);
if (succeed) {
AdapterManager::FillRoutingRequestHeader(
FLAGS_dreamview_module_name, &routing_request);
AdapterManager::PublishRoutingRequest(routing_request);
}
// …
Planning模块是在Frame::Rerouting
函数内调用AdapterManager::PublishRoutingRequest(request)
发布RoutingRequest
消息:
bool Frame::Rerouting() {
// ...
AdapterManager::PublishRoutingRequest(request);
return true;
}