Cyber RT与ROS对照

1、Cyber RT的基本概念与 ROS 对照

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 定义模块拓扑结构的配置文件。

2、常用工具对比

Cyber RT ROS 备注
cyber_launch roslaunch 启动节点
cyber_channel rostopic 察看某个topic的信息
cyber_moniter rqt? 查看诊断消息
cyber_visualizer rviz? 激光点云及摄像头可视化工具,需要安装NVIDIA显卡驱动及CUDA

3、常用命令迁移

具体见Apollo Cyber RT Developer Tools

Cyber RT ROS 备注
cyber_recorder play -f example.record rosbag play example.bag 播放一个包
cyber_recorder info example.record rosbag info example.bag 查看一个包的信息
cyber_recorder record -c /apollo/canbus/chassis \ /apollo/canbus/chassis_detail rosbag record /apollo/canbus/chassis \ /apollo/canbus/chassis_detail 录制多个topic
cyber_recorder split -f input_file.record -o ouput_file.record -k “/apollo/planning” rosbag filter input.bag output.bag ‘topic != “/apollo/planning”’ 滤除一个topic
cyber_recorder split -f input_file.record -o ouput_file.record -k “/apollo/planning” -k “/apollo/relative_map”’ rosbag filter csc.bag csc_no_plannig_and_relativemap.bag ‘topic != “/apollo/planning” and “/apollo/relative_map”’ 滤除多个topic
cyber_channel list rostopic list 列出所有活动的topic
cyber_channel info /apollo/planning rostopic info /apollo/planning 查看 /apollo/planning topic的概要信息
cyber_channel echo /apollo/planning rostopic echo /apollo/planning 查看 /apollo/planning topic的内容
cyber_channel hz /apollo/planning rostopic hz /apollo/planning 查看 /apollo/planning topic的发送频率
cyber_channel bw /apollo/planning rostopic bw /apollo/planning 查看 /apollo/planning topic的带宽
cyber_channel type /apollo/planning rostopic type /apollo/planning 查看 /apollo/planning topic的数据类型

4、像ROS一样使用Cyber RT

有两种方式可将Cyber​​ RT框架用于应用程序:

  • 基于二进制:将应用程序单独编译为二进制文件,通过创建自己的readerwriter与其他网络模块进行通信。
  • 基于组件:将应用程序编译到共享库中。通过继承Component类并编写相应的dag描述文件,Cyber​​ RT框架将动态加载和运行应用程序。也就是上一篇博客介绍的内容。

基于二进制的示例代码如下,与ROS极其相似,更多示例可查看Cyber examplesCyber RT API for Developers。创建一个talker的示例程序如下:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
#include "cyber/cyber.h"
#include "cyber/examples/proto/examples.pb.h"
#include "cyber/time/rate.h"
#include "cyber/time/time.h"

using apollo::cyber::Rate;
using apollo::cyber::Time;
using apollo::cyber::examples::proto::Chatter;

int main(int argc, char *argv[]) {
// init cyber framework
apollo::cyber::Init(argv[0]);
// create talker node
auto talker_node = apollo::cyber::CreateNode("talker");
// 应该是Unique_ptr吧?
//std::shared_ptr<apollo::cyber::Node> talker_node(apollo::cyber::CreateNode("talker"));
// create 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<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;
}

创建一个listener的示例程序如下:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
#include "cyber/cyber.h"
#include "cyber/examples/proto/examples.pb.h"

void MessageCallback(
const std::shared_ptr<apollo::cyber::examples::proto::Chatter>& msg) {
AINFO << "Received message seq-> " << msg->seq();
AINFO << "msgcontent->" << msg->content();
}

int main(int argc, char* argv[]) {
// init cyber framework
apollo::cyber::Init(argv[0]);
// create listener node
auto listener_node = apollo::cyber::CreateNode("listener");
// create listener
auto listener =
listener_node->CreateReader<apollo::cyber::examples::proto::Chatter>(
"channel/chatter", MessageCallback);
apollo::cyber::WaitForShutdown();
return 0;
}

基于组件的方式在Apollo的启动过程3中以Planning模块为例子说明了,这里列出更简单的实现,相对于基于二进制的方式,基于组件的方式有如下的优点:

  • 可以通过启动文件将组件加载到不同的进程中,并且部署非常灵活;
  • 组件可以通过修改dag文件来更改接收到的通道名称,而无需重新编译;
  • 组件支持接收多种类型的数据;
  • 组件支持提供多种融合策略。

头文件:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
#include <memory>

#include "cyber/component/component.h"
#include "cyber/examples/proto/examples.pb.h"

using apollo::cyber::Component;
using apollo::cyber::ComponentBase;
using apollo::cyber::examples::proto::Driver;

class CommonComponentSample : public Component<Driver, Driver> {
public:
bool Init() override;
bool Proc(const std::shared_ptr<Driver>& msg0,
const std::shared_ptr<Driver>& msg1) override;
};
CYBER_REGISTER_COMPONENT(CommonComponentSample)

实现文件:

1
2
3
4
5
6
7
8
9
10
11
12
13
#include "cyber/examples/common_component_example/common_component_example.h"

bool CommonComponentSample::Init() {
AINFO << "Commontest component init";
return true;
}

bool CommonComponentSample::Proc(const std::shared_ptr<Driver>& msg0,
const std::shared_ptr<Driver>& msg1) {
AINFO << "Start common component Proc [" << msg0->msg_id() << "] ["
<< msg1->msg_id() << "]";
return true;
}

对应的dag文件:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
# Define all coms in DAG streaming.
module_config {
module_library : "/apollo/bazel-bin/cyber/examples/common_component_example/libcommon_component_example.so"
components {
class_name : "CommonComponentSample"
config {
name : "common"
readers {
channel: "/apollo/prediction" // proc()中的channel
}
readers {
channel: "/apollo/test"
}
}
}
}

对应的启动文件:

1
2
3
4
5
6
7
<cyber>
<module>
<name>common</name>
<dag_conf>/apollo/cyber/examples/common_component_example/common.dag</dag_conf>
<process_name>common</process_name>
</module>
</cyber>

构建和运行:

Build:

1
bazel build cyber/examples/common_component_smaple/…

Run:

1
mainboard -d cyber/examples/common_component_smaple/timer.dag
听说打赏我的人,最后都找到了真爱。