baidu apollo(2)—适配器模式

protobuf的原生支持

apollo官方的介绍,
这里写图片描述

在apollo platform源码中,其实也就是ros-indigo,可以看到protobuf相关的修改,
这里写图片描述

通过百度的修改,在ros中不需要使用原有的msg机制来进行数据的序列化和反序列化,而是可以支持直接使用google的protobuf。

适配器模式如何使用

熟悉ros的应该都清楚原生ros中topic、node相关订阅和发布的写法,百度对通讯层利用适配器模式进行了封装(Adapter),下面以modules/routing模块为例子首先介绍如何使用封装后的Adapter,在这里百度还添加了一个AdapterManager,用来对所有的Adapter进行管理。

APOLLO_MAIN(apollo::routing::Routing);
#define APOLLO_MAIN(APP)                                       \
  int main(int argc, char **argv) {                            \
    google::InitGoogleLogging(argv[0]);                        \
    google::ParseCommandLineFlags(&argc, &argv, true);         \
    signal(SIGINT, apollo::common::apollo_app_sigint_handler); \
    APP apollo_app_;                                           \
    ros::init(argc, argv, apollo_app_.Name());                 \
    apollo_app_.Spin();                                        \
    return 0;                                                  \
  }

routing模块本身启动后是一个进程,ros中的Node,从上面代码可以看到百度使用了很多google的工具,log,参数解析等。

int ApolloApp::Spin() {
  auto status = Init();
  .....
}

ApolloApp::Spin()中首先会执行Init函数,即apollo::routing::Routing类的Init()函数,

apollo::common::Status Routing::Init() {
  const auto routing_map_file = apollo::hdmap::RoutingMapFile();
  AINFO << "Use routing topology graph path: " << routing_map_file;
  navigator_ptr_.reset(new Navigator(routing_map_file));
  CHECK(common::util::GetProtoFromFile(FLAGS_routing_conf_file, &routing_conf_))
      << "Unable to load routing conf file: " + FLAGS_routing_conf_file;

  AINFO << "Conf file: " << FLAGS_routing_conf_file << " is loaded.";

  hdmap_ = apollo::hdmap::HDMapUtil::BaseMapPtr();
  CHECK(hdmap_) << "Failed to load map file:" << apollo::hdmap::BaseMapFile();
  //①调取AdapterManager的Init函数,static,参数是routing模块下的adapter_conf
  AdapterManager::Init(FLAGS_routing_adapter_config_filename);
  //②添加routing模块的回调函数
  AdapterManager::AddRoutingRequestCallback(&Routing::OnRoutingRequest, this);
  return apollo::common::Status::OK();
}

在上述过程中,主要分为两步:
①调取AdapterManagerInit函数,参数为routing模块下的adapter_conf,如下所示,其实就是创建ros Publisher 和Subscriber对象需要的配置参数,如是pub还是sub,message queue的大小,最后一条是是否为ros,目前都是ros,表明该进程Node为ros节点,通过ros的底层通讯机制进行通讯,例如TCPROS/UDPROS,不过msg类型不是ros原生的msg类型,而是都是protobuf中的proto。

config {
  type: ROUTING_REQUEST
  mode: RECEIVE_ONLY
  message_history_limit: 10
}
config {
  type: ROUTING_RESPONSE
  mode: PUBLISH_ONLY
  latch: true
}
config {
  type: MONITOR
  mode: DUPLEX
  message_history_limit: 1
}
is_ros: true

进入到AdapterManager::Init中,

void AdapterManager::Init(const std::string &adapter_config_filename) {
  // Parse config file
  AdapterManagerConfig configs;
  Init(configs);
}

void AdapterManager::Init(const AdapterManagerConfig &configs) {
  if (Initialized()) {
    return;
  }

  instance()->initialized_ = true;
  ①如果是ros节点,则创建ros::NodeHandle对象
  if (configs.is_ros()) {
    instance()->node_handle_.reset(new ros::NodeHandle());
  }
 for (const auto &config : configs.config()) {
    switch (config.type()) {
      case AdapterConfig::POINT_CLOUD:
        EnablePointCloud(FLAGS_pointcloud_topic, config);
        break;
      ②调用EnableRoutingRequest()函数,完成了创建Publisher 和Subscriber对象
      case AdapterConfig::ROUTING_REQUEST:
        EnableRoutingRequest(FLAGS_routing_request_topic, config);
        break;

上述代码主要完成了两个工作:
创建ros::NodeHandle对象;
调用EnableRoutingRequest()函数,完成了创建Publisher 和Subscriber对象,该函数的具体是如何实现的后续再描述。在Subscriber创建的时候,肯定需要制定回调函数,这里百度封装了一个统一的函数RoutingRequestAdapter::RosCallback

②添加routing模块的回调函数,上述不是描述过已经给Subscriber添加了一个RoutingRequestAdapter::RosCallback函数,怎么还需要AdapterManager::AddRoutingRequestCallback(&Routing::OnRoutingRequest, this);去添加回调函数,其实主要是封装,具体的回调函数实现是在Routing::OnRoutingRequest中,如下代码所示,当该进程(Node)的topic收到数据时,会调用下面的回调函数进行处理。

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;
}

适配器模式的原理

适配器Adapter的设计

接下来具体分析百度是如何通过适配器模式进行设计封装的,首先是适配器Adapter的设计。

//modules/common/adapters/message_adapters.h中定义了
using RoutingRequestAdapter = Adapter<routing::RoutingRequest>;

其中模板类Adapter的类型routing::RoutingRequest为proto,

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];
}

Adapter继承自AdapterBaseAdapterBase是个抽象类,就是一堆接口,这些接口在Adapter中实现,

/**
 * @class AdapterBase
 * @brief Base interface of all concrete adapters.
 */
class AdapterBase {
 public:
  virtual ~AdapterBase() = default;

  /**
   * @brief returns the topic name that this adapter listens to.
   */
  virtual const std::string& topic_name() const = 0;

  /**
   * @brief Create a view of data up to the call time for the user.
   */
  virtual void Observe() = 0;

  /**
   * @brief returns TRUE if the observing queue is empty.
   */
  virtual bool Empty() const = 0;

  /**
   * @brief returns TRUE if the adapter has received any message.
   */
  virtual bool HasReceived() const = 0;

  /**
   * @brief Gets message delay.
   */
  virtual double GetDelaySec() const = 0;

  /**
   * @brief Clear the data received so far.
   */
  virtual void ClearData() = 0;

  /**
   * @brief Dumps the latest received data to file.
   */
  virtual bool DumpLatestMessage() = 0;
};
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_ptr<D const> DataPtr;

  typedef typename std::list<DataPtr>::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")
      : topic_name_(topic_name),
        message_num_(message_num),
        enable_dump_(FLAGS_enable_adapter_dump),
        dump_path_(dump_dir + "/" + adapter_name) {
    if (HasSequenceNumber<D>()) {
      if (!apollo::common::util::EnsureDirectory(dump_path_)) {
        AERROR << "Cannot enable dumping for '" << adapter_name
               << "' adapter because the path " << dump_path_
               << " cannot be created or is not a directory.";
        enable_dump_ = false;
      } else if (!apollo::common::util::RemoveAllFiles(dump_path_)) {
        AERROR << "Cannot enable dumping for '" << adapter_name
               << "' adapter because the path " << dump_path_
               << " contains files that cannot be removed.";
        enable_dump_ = false;
      }
    } else {
      enable_dump_ = false;
    }
  }
   //这里主要看一下如何添加callback函数,
   void AddCallback(Callback callback) {
    receive_callbacks_.push_back(callback);
  }
  ........
  /// User defined function when receiving a message
  std::vector<Callback> receive_callbacks_;

看完上面的分析,并没有看到适配器有什么用,Adapter的使用主要需要结合AdapterManager

AdapterManager的设计
class AdapterManager {
   //static函数
  static void Init(const std::string &adapter_config_filename);
  //很关键的宏
  REGISTER_ADAPTER(RoutingRequest);
  //单例模式,这里不分析了,很简单
  DECLARE_SINGLETON(AdapterManager);

上一节看到对Init函数的调用,但是Init的调用中,很多函数的实现是通过DECLARE_SINGLETON宏来实现的。

/// Macro to prepare all the necessary adapter functions when adding a
/// new input/output. For example when you want to listen to
/// car_status message for your module, you can do
/// REGISTER_ADAPTER(CarStatus) write an adapter class called
/// CarStatusAdapter, and call EnableCarStatus(`car_status_topic`,
/// true, `callback`(if there's one)) in AdapterManager.
#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<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);                                \
  }                                                                            \
  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<name##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<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(RoutingRequest);

  public:
  //定义了EnableRoutingRequest函数                                                                       
  static void EnableRoutingRequest(const std::string &topic_name,                      
                           const AdapterConfig &config) 
 {                      
    CHECK(config.message_history_limit() > 0)                                  
        << "Message history limit must be greater than 0";
    //单例模式,返回AdapterManager对象                     
    instance()->InternalEnableRoutingRequest(topic_name, config);                      
 }



  static void PublishRoutingRequest(const RoutingRequestAdapter::DataType &data) {             
    instance()->InternalPublishRoutingRequest(data);                                   
  }


  static void AddRoutingRequestCallback(RoutingRequestAdapter::Callback callback) {          
    CHECK(instance()->RoutingRequest_)                                                 
        << "Initialize adapter before setting callback";                       
    instance()->RoutingRequest_->AddCallback(callback);                                
  }



private:                                                                      
  std::unique_ptr<RoutingRequestAdapter> RoutingRequest_;                                      
  ros::Publisher RoutingRequestpublisher_;                                             
  ros::Subscriber RoutingRequestsubscriber_;                                           
  AdapterConfig RoutingRequestconfig_;

  //新建RoutingRequestAdapter
  void InternalEnableRoutingRequest(const std::string &topic_name,                     
                            const AdapterConfig &config) {                     
    RoutingRequest_.reset(                                                             
        new RoutingRequestAdapter("RoutingRequest", topic_name, config.message_history_limit())); 
    //订阅
    if (config.mode() != AdapterConfig::PUBLISH_ONLY && IsRos()) {             
      RoutingRequestsubscriber_ =                                                      
          node_handle_->subscribe(topic_name, config.message_history_limit(),  
                                  &RoutingRequestAdapter::RosCallback, RoutingRequest_.get()); 
    }
    //发布                                                                          
    if (config.mode() != AdapterConfig::RECEIVE_ONLY && IsRos()) {             
      RoutingRequestpublisher_ = node_handle_->advertise<RoutingRequestAdapter::DataType>(     
          topic_name, config.message_history_limit(), config.latch());         
    }                                                                          
    //c++ 11 lambda表达式                                                                           
    observers_.push_back([this]() { RoutingRequest_->Observe(); });                    
    RoutingRequestconfig_ = config;                                                    
  }

  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);                                         
  }  

REGISTER_ADAPTER宏创建了适配所有Adapter的函数,主要是将AdapterAdapterManager 联系起来。而前面提到的AddRoutingRequestCallback()函数,

  std::unique_ptr<RoutingRequestAdapter> RoutingRequest_;   
  static void AddRoutingRequestCallback(RoutingRequestAdapter::Callback callback) {                              
    instance()->RoutingRequest_->AddCallback(callback);                                
  }

最终调用的是RoutingRequestAdapterAddCallback(),其实调用的是Adapter模板类中的,

  void AddCallback(Callback callback) {
    receive_callbacks_.push_back(callback);
  }

只是将callback函数放到receive_callbacks_这个vector中。

当有ros消息到来时,在REGISTER_ADAPTER宏里定义的Subscriber,其 回调函数为RoutingRequestAdapter::RosCallback

RoutingRequestsubscriber_ =                                                      
          node_handle_->subscribe(topic_name, config.message_history_limit(),  
                                  &RoutingRequestAdapter::RosCallback, RoutingRequest_.get()); 
  void RosCallback(const DataPtr& message) {
    last_receive_time_ = apollo::common::time::Clock::NowInSeconds();
    EnqueueData(message);
    FireCallbacks(*message);
  }
  void FireCallbacks(const D& data) {
    //在receive_callbacks_这个vector中取出所有的回调函数,并调用。
    for (const auto& callback : receive_callbacks_) {
      callback(data);
    }
  }

总结

所以,通过百度的封装,使用方法可以总结为:
①定义msg格式,这里就是proto,例如routing::RoutingRequest,然后定义相应的模板类RoutingRequestAdapter
using RoutingRequestAdapter = Adapter<routing::RoutingRequest>;
②在AdapterManager::Init()函数中,添加

  case AdapterConfig::ROUTING_REQUEST:
        EnableRoutingRequest(FLAGS_routing_request_topic, config);

③在自己的模块,例如routing,首先定义一个adapter.conf,如下所示,

config {
  type: ROUTING_REQUEST
  mode: RECEIVE_ONLY
  message_history_limit: 10
}
config {
  type: ROUTING_RESPONSE
  mode: PUBLISH_ONLY
  latch: true
}
config {
  type: MONITOR
  mode: DUPLEX
  message_history_limit: 1
}
is_ros: true

然后在自己的模块的Init()函数中,调用AdapterManager::Init(),输入参数为上述adapter.conf

AdapterManager::Init(FLAGS_routing_adapter_config_filename);

④在自己的模块中添加回调函数,该回调函数是整个数据处理的关键,需要手动编写。

AdapterManager::AddRoutingRequestCallback(&Routing::OnRoutingRequest, this);

上述的总结是Subscriber,而Publisher的过程与之类似。

  • 2
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值