apollo 在3.5版本之前采用ros的框架,因此,CyberRT 中同样有大量的ROS的影子。Writer、Reader就是最典型的例子。下面我将会采用从node(节点)、Writer(发布者)、Reader(订阅者)三个方面,和ROS逐一比较分析说明两者间的异同。
在CyberRT框架下,node是最基础的单元。在创建writer,reader等均需要连接到一个node上。
在cyberRT中创建方法如下:
std::unique_ptr<Node> apollo::cyber::CreateNode(const std::string& node_name, const std::string& name_space = "");
参数:
在
cyber::Init()
还未执行前,系统还处于未初始化状态,没法创建node,会直接返回nullptr
writer 是CyberRT中,用来发布消息最基本的方法。每个writer对应一个特定消息类型的channel
。writer可以通过Node类中的 CreateWriter
接口创建。具体如下:
template <typename MessageT>
auto CreateWriter(const std::string& channel_name)
-> std::shared_ptr<Writer<MessageT>>;
template <typename MessageT>
auto CreateWriter(const proto::RoleAttributes& role_attr)
-> std::shared_ptr<Writer<MessageT>>;
参数:
std::shared_ptr>
reader是接收消息最基础的方法。reader必须绑定一个回调函数。当channel中的消息到达后,回调会被调用。
reader 可以通过Node类中 CreateReader
接口创建。具体如下:
template <typename MessageT>
auto CreateReader(const std::string& channel_name, const std::function<void(const std::shared_ptr<MessageT>&)>& reader_func)
-> std::shared_ptr<Reader<MessageT>>;
template <typename MessageT>
auto CreateReader(const ReaderConfig& config,
const CallbackFunc<MessageT>& reader_func = nullptr)
-> std::shared_ptr<cyber::Reader<MessageT>>;
template <typename MessageT>
auto CreateReader(const proto::RoleAttributes& role_attr,
const CallbackFunc<MessageT>& reader_func = nullptr)
-> std::shared_ptr<cyber::Reader<MessageT>>;
参数:
std::shared_ptr>
syntax = "proto2";
package apollo.cyber.examples.proto;
message SamplesTest1 {
optional string class_name = 1;
optional string case_name = 2;
};
message Chatter {
optional uint64 timestamp = 1;
optional uint64 lidar_timestamp = 2;
optional uint64 seq = 3;
optional bytes content = 4;
};
message Driver {
optional string content = 1;
optional uint64 msg_id = 2;
optional uint64 timestamp = 3;
};
#include "cyber/cyber.h"
#include "cyber/proto/chatter.pb.h"
#include "cyber/time/rate.h"
#include "cyber/time/time.h"
using apollo::cyber::Rate;
using apollo::cyber::Time;
using apollo::cyber::proto::Chatter;
int main(int argc, char *argv[]) {
// cyber初始化
apollo::cyber::Init(argv[0]);
// 创建 node
std::shared_ptr<apollo::cyber::Node> talker_node(apollo::cyber::CreateNode("talker"));
// 创建发布者
auto talker = talker_node->CreateWriter<Chatter>("channel/chatter");
// 发布频率
Rate rate(1.0);
while (apollo::cyber::OK()) {
static uint64_t seq = 0;
//构造消息
auto msg = std::make_shared<apollo::cyber::proto::Chatter>();
msg->set_timestamp(Time::Now().ToNanosecond());
msg->set_lidar_timestamp(Time::Now().ToNanosecond());
msg->set_seq(seq++);
msg->set_content("Hello, apollo!");
//发布消息
talker->Write(msg);
AINFO << "talker sent a message!";
//延时等待
rate.Sleep();
}
return 0;
}
#include "cyber/cyber.h"
#include "cyber/proto/chatter.pb.h"
//回调函数
void MessageCallback(
const std::shared_ptr<apollo::cyber::proto::Chatter>& msg) {
AINFO << "Received message seq-> " << msg->seq();
AINFO << "msgcontent->" << msg->content();
}
int main(int argc, char *argv[]) {
// 初始化cyber
apollo::cyber::Init(argv[0]);
// 创建node
auto listener_node = apollo::cyber::CreateNode("listener");
// 创建 listener
auto listener =listener_node->CreateReader<apollo::cyber::proto::Chatter>("channel/chatter", MessageCallback);
//阻塞
apollo::cyber::WaitForShutdown();
return 0;
}
# 编译生成bin文件
cc_binary(
name = "talker",
srcs = [ "talker.cc", ],
deps = [
"//cyber",
"//cyber/examples/proto:examples_cc_proto",
],
)
cc_binary(
name = "listener",
srcs = [ "listener.cc", ],
deps = [
"//cyber",
"//cyber/examples/proto:examples_cc_proto",
],
)
编译会生成二进制的可执行文件
package(default_visibility = ["//visibility:public"])
cc_proto_library(
name = "examples_cc_proto",
deps = [
":examples_proto",
],
)
proto_library(
name = "examples_proto",
srcs = [
"examples.proto",
],
)
消息类型也必须编译生成c++可用的库文件,上式中均调用了该库
未完待续
以上分析只是从使用的角度来分析CyberRT架构,后续在时间允许的情况下,计划用10篇左右的篇幅详解一下通信机制,apollo主要采用了fastrtps,这是个非常复杂的话题,先立个flag吧。