目录
1.Cyber RT 诞生的背景
1.1 开发者们希望系统可以在实时操作系统上运行:
1.2 Cyber RT 在Apollo中的位置
Cyber RT的优势
1.3 Real Time OS 与 CyberRT的比较
1.4 Cyber的通讯方式(No Broker——不同于ROS)
1.5 实时性由QoS和实时线程保证
本章小结
2.Cyber RT 与 ROS的对比
Cyber RT 和 ROS 之间基本概念的对照
3.Cyber RT在Apollo框架中的作用
本章小结
4.Cyber RT 组件、通讯机制概要
4.1通过Component添加数据订阅/发布
4.2Reader / Writer 通过Transport来通信:
4.3 Datavisitor
本章小结
5.Cyber RT的实践案例
5.1 Listener 和 Talker通讯原理
5.2 实验流程
5.3 编写Car Message(protoc)
5.4 创建Talker/Listener
talker.cc
listener.cc
5.5 编译并创建cc应用
5.6 运行
5.7 Python实验
声明
1.1 开发者们希望系统可以在实时操作系统上运行:
- 静态分配(static allocation)
- 非阻塞调用
- 进程内通信 -——代替网络协议栈通信
开发者们希望能够不通过OS Kernel对键盘、鼠标以及Apollo的外挂设备(摄像头、激光雷达等)进行交互。Apollo 3.5版本以前构建在通用分时多户操作系统(Time-Sharing OS)Linux上,基于ROS1的通信模型。linux目前的调度是Completely Fair Scheduling(CFS) 算法,因为开发者们在实时性方面具有一定的要求,所以需要改为实时的调度算法。为了解决调度、通信和任务管理实时响应要求,Cyber RT应运而生。
ROS1是集中式的消息管理系统,其核心节点为master(roscore),各节点之间的通讯需要借助核心节点进行,若核心节点下线,整个系统就会出故障。Cyber RT更类似于一种点对点式的系统,各节点之间点对点通讯,不必通过核心节点,任何一个节点的下线并不会导致系统的崩溃。但同样的,它也缺乏了集中式管理的一种好处——可以管理各个节点。(关于Cyber RT的详细解释强力推荐王方浩知乎系列文章)
Cyber RT 被称为自动驾驶的中间件,在Apollo中处于承上启下的位置。
Cyber RT有以下几点优势值得我们注意:
1.满足自动驾驶的任务需求和实时性
· 任务调度(DAG)基于有向无环图的任务调度
· 协程和内存管理(RTOS/TSOS扩展)
· 数据融合(Multi-in,Multi-out)2.在ROS的基础上继承Fast RTPS (eProsima Fast RTPS)∶
· 去中心化通讯RTPS 通讯∶QoS,Participant/Node/Reader/Writer/Service/Client
· 同主机通讯(进程内/间)∶传输层利用共享内存SHM,传递消息指针,实现符合RTPS 模型
· 设备间通讯媒介∶Protobuf
左图是普通Linux系统里的kernel,会处理文件、网络请求,通过Schedule里的函数,与Hardware(我们的硬件设备)相连接。在实时操作系统中,会有个独立在kernel外的调度队列,其会运行Real Time Task(实时线程),这个线程将会被赋予高优先级,保证其优先执行。实时线程在执行之后会和硬件连接。
可以看到,ROS1中的通讯方式容易出现单点故障,导致系统崩溃。
- 希望Reader和Writer不通过中间人,以databus的方式直接进行消息沟通
- Cyber 引入Transport 来完成这个工作极大的提升了系统稳定性
由图中可以看到,Cyber通过Writer这个节点,借助Transport这个中间节点,生成对应的通道,送入Reciever中,最后再给到Reader。不同的通道会根据实际情况进行适时调整。例如,在进程内(intraListener),通过指针进行传递;在进程间(shmSegment),通过申请一块内存,进行数据共享,再把数据通过指针的方式进行传输;如果是跨域或是不同主机(rtps Protobuf Message),则通过网络UDP的方式进行传送。
在自动驾驶中,前两种方式用的比较多。
1.5 实时性由QoS和实时线程保证
- 更快的通讯∶进程内点对点回调(IntraTransimitter),进程间用ShmMemory
- 灵活出让CPU时间∶协程(用户态线程)
- 7.0版本∶更大覆盖的无锁队列实现
CyberRT是为了解决时时任务而诞生的软件系统
- 建立了高效的去中心的数据通信通道
- 通过QoS,实时线程,以及用户态化保证实时性CyberRT针对自动驾驶任务特点进行了计算架构的优化
- 基于有向无环的任务调度
- 数据融合
CyberRT在Apollo扮演承上启下的角色,是整个数据流通的关键
ROS 应用于自动驾驶领域的不足:
- 调度的不确定性:各节点以独立进程运行,节点运行顺序无法确定,因而业务逻辑的调度顺序无法保证;
- 运行效率:ROS 为分布式系统,存在通信开销。
Cyber RT的特色:
- 高性能:无锁对象,协程(coroutine),自适应通信机制;
- 确定性:可配置的任务以及任务调度,通过协程将调度从内核空间转移到用户空间;
- 模块化:在框架内实现组件以及节点,即可完成系统任务;
- 便利性:创建和使用任务。
Cyber RT | ROS | 备注 |
---|---|---|
Component | 无 | 组件之间通过Cyber channel通信 |
Channel | Topic | channel用于管理数据通信,用户可以通过publish/subscribe相同的channel来通信。 |
Node | Node | 每一个模块包含Node并通过Node来通信。一个模块通过定义read/write和/或service/client使用不同的通信模式 |
Reader/Writer | Publish/Subscribe | 订阅者模式。往channel读写消息的类。通常作为Node的主要消息传输接口。 |
Service/Client | Service/Client | 请求/相应模式,支持节点之间双向通信。 |
Message | Message | Cyber RT中用于模块间通信的数据单元,其实现基于protobuf。 |
Parameter | Parameter | Parameter服务提供全局参数访问的接口,该服务基于service/client模式。 |
Record file | Bag file | 用于记录从channel发送或者接收的消息,回放record file可以重现之前的操作行为。 |
Launch file | Launch file | 提供一种启动模块的便利途径。通过在launch file中定义一个或者多个dag文件,可以同时启动多个modules。 |
Task | 无 | 异步计算任务。 |
CRoutine | 无 | 协程,优化线程使用与系统资源分配。 |
Scheduler | 无 | 任务调度器,用户空间。 |
Dag file | 无 | 定义模块拓扑结构的配置文件。 |
更多内容详见此处Cyber RT与ROS对照 | GWH Blog
底层操作系统可以是实时操作系统也可以是分时操作系统。用户通过Driver将各个数据通过数据流传到DataVisitor,最后再到proc(Apollo各个业务算法)。
Cyber RT的主程序放在Mainboard之中。Mainboard通过ConfigManager读取DAG文件(Proto/Yaml定义的一个有向无环图)。读取之后,通过ClassLoder来实例化一个Component对象,在创建一个Reader。Reader被Scheduler以协程的方式进行封装,变成一个协程函数。协程函数最终会被分配到一个线程之中。最后任务添加到本地队列之中,进行初始化,等待所有Component的启动,进行“收发”的启动。
4.1通过Component添加数据订阅/发布
- · 默认会创建Reader,并定义QoS
- · Writer由用户创建
- 消息通过Datavisitor来同步,实现数据融合
- · 注册服务
1.同进程内部,通过回调机制(数据消息裸指针)
2.同主机,进程间,通过Sharememory (ShmMemory),并通过事件完成数据块共享(数据消息共享内存块指针)
3.跨主机/域,采用UDP/TCP(fast-RTPS)进行消息传递,适合跨域,如V2X.
Datavisitor
- 定义了数据buffer_m_i,和缓存,超过频控要求,即丢弃;
- 可以融合多路消息,对多路输入节点,只有当同一时刻附近,数据都Ready时,才会触发用户回调,实现数据融合
- Cyber 通过 mainboard 读取 dag文件创建Copomonent 中的Writer 和 Reader对象,分别进行数据发布和订阅,然后并将两者加入到通信拓扑图中,无中心节点依赖
- 数据通过Tansmitter从Writer流通到Reader,缓存在在Datavisitor进行数据融合,最终传递给业务函数(Proc)接口,在RT-Thread上运行,实现数据流通和处理
Listener-Talker通信一方主动送消息,一方被动接收。Listener-Talker通信首先创建了两个Node,分别是Talker Node和 Listener Node。每个Node实例化Writer类和Reader类对Channel进行消息的读写。Writer和Reader通过Topic连接,对同一块共享内存(Channel)进行读写处理。在这里,Talker Node 为了实现其“诉说”的功能,选择实例化Writer,通过Writer来对Channel进行消息写操作。而Listener Node为了实现其“聆听”功能,选择实例化reader类,通过Reader来对channel进行读操作。该通信方式适合于持续性通信的应用场景,比如雷达信号,摄像头图像信息这类数据的传输。
首先在创建一个car1.proto 文件。其路径为apollo_workspace/examples/proto/car1.proto
vim /apollo_workspace/examples/proto/car1.proto
在car1.proto中定义车身信息
syntax = "proto2";
//定义包名,在cc文件中调用
package apollo.cyber.examples.proto; //package相当于namespace
//定义一个车的消息,车的型号,车主,车的车牌号,已跑公里数,车速
message Car1{
optional string plate = 1; //optional表示可缺省
optional string type = 2;
optional string owner = 3;
optional uint64 kilometers = 4;
optional uint64 speed = 5;
};
Cyber RT基于bazel编译,会有一个BUILD文件(相当于CmakeList)
vim /apollo_workspace/examples/proto/BUILD
在BUILD文件里添加car1.proto的信息
proto_library(
name = "car1_proto",
srcs = ["car1.proto"],
)
cc_proto_library(
name = "car1_cc_proto",
deps = [
":car1_proto",
],
)
在/apollo_workspace/examples/communication这个路径下创建talker1.cc文件。
vim /apollo_workspace/examples/communication/talker1.cc
//头文件引用
#include "examples/proto/car1.pb.h"
#include "cyber/cyber.h"
#include "cyber/time/rate.h"
//car数据定义的引用,可以看出其定义来源于一个proto
using apollo::cyber::examples::proto::Car1;
int main(int argc, char *argv[]) {
// 初始化一个cyber框架
apollo::cyber::Init(argv[0]);
// 创建talker节点
auto talker_node = apollo::cyber::CreateNode("talker");
// 从节点创建一个Topic,来实现对车速的查看
auto talker = talker_node->CreateWriter("car_speed");
AINFO << "I'll start telling you the current speed of the car.";
//设置初始速度为0,然后速度每秒增加5km/h
uint64_t speed = 0;
while (apollo::cyber::OK()) {
auto msg = std::make_shared();
msg->set_speed(speed);
//假设车速持续增加
speed += 5;
talker->Write(msg);
sleep(1);
}
return 0;
}
在/apollo_workspace//examples/communication路径下创建listener1.cc
#include "examples/proto/car1.pb.h"
#include "cyber/cyber.h"
using apollo::cyber::examples::proto::Car1;
//接收到消息后的响应函数
void message_callback(
const std::shared_ptr& msg) {
AINFO << "now speed is: " << msg->speed();
}
int main(int argc, char* argv[]) {
//初始化cyber框架
apollo::cyber::Init(argv[0]);
//创建监听节点
auto listener_node = apollo::cyber::CreateNode("listener");
//创建监听响应进行消息读取
auto listener = listener_node->CreateReader(
"car_speed", message_callback);
apollo::cyber::WaitForShutdown();
return 0;
}
回到BULID,补充相应信息
vim /apollo_workspace/examples/communication/BUILD
在BULID文件里补充以下信息
//添加两个cc_binary
cc_binary(
name = "talker1",
srcs = ["talker1.cc"],
deps = [
"//cyber",
"//examples/proto:car1_cc_proto",
],
linkstatic = True,
)
cc_binary(
name = "listener1",
srcs = ["listener1.cc"],
deps = [
"//cyber",
"//examples/proto:car1_cc_proto",
],
linkstatic = True,
)
//在install中将自己创建的talker1和listener1程序加入进去
install(
name = "install",
runtime_dest = "examples/bin",
targets = [
":talker",
":listener",
":server",
":client",
":param_client",
":param_server",
":talker1", //添加
":listener1" //添加
],
)
需要在工作空间里进行编译,所有回到 /apollo_workspace目录下编译
//回到 /apollo_workspace目录下编译
cd /apollo_workspace
bash scripts/apollo_neo.sh build --packages examples/communication
整体的编译过程大致需要1-2分钟,编译完成后如下图所示
重开一个终端,执行talker
//设置将输出结果到控制台
export GLOG_alsologtostderr=1
//编译产生的可执行文件在 /opt/apollo/neo/packages/examples-dev/local/bin
cd /opt/apollo/neo/packages/examples-dev/local/bin
//执行talker1
./talker1
执行成功后
同样再开一个终端,执行listener
//设置将输出结果到控制台
export GLOG_alsologtostderr=1
//编译产生的可执行文件在 /opt/apollo/neo/packages/examples-dev/local/bin
cd /opt/apollo/neo/packages/examples-dev/local/bin
//执行listener1
./listener1
执行成功后,可以看到发出的消息中,汽车的速度逐渐增加(+5)
实验流程图
Multi Data Distribution Control (MDDC)实验
实验地址: https://github.com/yiakwy-mapping-team/cybertron
- zlib need to updated mannually (rules..proto)
- need use anaconda to downgrade Python 3.10 to Python 3.6 (**)
- move GCC so to anaconda python
本人所有文章仅作为自己的学习记录,若有侵权,联系立删。