本文是对Cyber RT的学习记录,文章可能存在不严谨、不完善、有缺漏的部分,还请大家多多指出。
课程地址: https://apollo.baidu.com/community/course/outline/329?activeId=10200
更多还请参考:
[1] Apollo星火计划学习笔记——第三讲(Apollo Cyber RT 模块详解与实战)https://blog.csdn.net/sinat_52032317/article/details/126924375
[2] 【Apollo星火计划】—— Cyber基础概念|通信机制
https://blog.csdn.net/sinat_52032317/article/details/131878429?spm=1001.2014.3001.5501
[3] 第一章:Cyber RT基础入门与实践https://apollo.baidu.com/community/article/1093
[4] 第二章:Cyber RT通信机制解析与实践https://apollo.baidu.com/community/article/1094
[5] 第三章:Component组件认知与实践https://apollo.baidu.com/community/article/1103
说明
本文1-4节以此文中的example-component例子为基础;
TEST1.Component案例和TEST2.TimerComponent案例基于星火计划中的例子
这部分内容详见第三章:Component组件认知与实践https://apollo.baidu.com/community/article/1103
Apollo 的 Cyber RT 框架是基于组件(component)概念来构建的。每个组件都是 Cyber RT 框架的一个特定的算法模块, 处理一组输入并产生其输出数椐,配合Component对应的DAG文件,Cyber RT可实现对该模块的动态加载。
Component可分为两类:
以消息驱动的Component,即只有消息到来时,才会调用proc
定时调用的TimerComponent,定时调度模块没有绑定消息收发,需要用户自己创建reader来读取消息,如果需要读取多个消息,则可以创建多个reader
注意:
Component提供消息融合机制,最多可以支持4路消息,当从多个channel读取数据的时候,以第一个Channel为主Channel,当主Channel有消息到达,Cyber RT会调用Component的Proc()进行一次数据处理。
TimerComponent不提供消息融合,与Component不同的是TimerComponent的Proc()函数不是基于主Channel触发执行,而是由系统定时调用,开发者可以在配置文件中确定调用的时间间隔。
(1)包含头文件(具体见2.1)
(2)定义一个类,并继承Component或者timer Component,根据component功能需要,选择继承Component或者继承TimerComponent
(3)重写Init()和Proc()函数,init函数在Component被加载的时候执行,用来对Component进行初始化,如Node的创建,Node Reader创建,Node Writer创建等;Proc函数是实现该Component功能的核心函数,其中实现了该Component的核心逻辑功能。
(4)在Cyber Rt中注册该Component,只有在Cyber RT中注册了该Component,Cyber RT才能对其进行动态的加载,否则,报错
在Cyber RT中,所有的Component都会被编译成独立的.so文件,Cyber Rt会根据开发者提供的配置文件,按照需要加载对应的Component。所以,开发者需要为.so文件编写好配置文件:.dag文件和.launch文件,以供Cyber RT正确的加载执行Component。
Cyber RT提供两种加载启动Component的方式:
使用cyber_launch工具启动Component对应的launch文件
使用mainboard启动component对应的dag文件
cyber_launch工具可以启动dag文件和二进制文件,而mainboard执行启动dag文件
优点:
可以通过配置launch文件加载到不同进程中,可以弹性部署
可以通过配置DAG文件来修改其中的参数配置,调度策略,Channel名称
可以接收多个种类的消息,并有多种消息融合策略
接口简单,并且可以被Cyber框架动态的加载
要创建并启动一个算法组件,需要通过以下4个步骤:
初始化组件的目录结构
实现组件类
设置配置文件
启动组件
├── BUILD
├── cyberfile.xml
├── example-components.BUILD
├── example.dag
├── example.launch
├── proto
│ ├── BUILD
│ └── examples.proto
└── src
├── BUILD
├── common_component_example.cc
├── common_component_example.h
├── timer_common_component_example.cc
└── timer_common_component_example.h
C++头文件: common_component_example.h
C++源文件: common_component_example.cc
Bazel 构建文件: BUILD
DAG 文件: examples.dag
Launch 文件: examples.launch
实现common_component_example.h有以下步骤:
包含头文件
基于模板类Component派生出组件类ComponentSample
在派生类中定义自己的Init和proc函数。Proc函数需要指定输入的数据类型
使用CYBER_REGISTER_COMPONENT宏定义把组件类注册成全局可用
实例如下所示:
#pragma once
#include
#include "cyber/component/component.h"
#include "example_components/proto/examples.pb.h"
// CommonComponentSample类不能被继承
class CommonComponentSample : public apollo::cyber::Component<example::proto::Driver, example::proto::Driver> {
//有几个数据就有几个example::proto::Driver
public:
bool Init() override;
bool Proc(const std::shared_ptr<example::proto::Driver>& msg0,
const std::shared_ptr<example::proto::Driver>& msg1) override;
};
CYBER_REGISTER_COMPONENT(CommonComponentSample)
模板类Component的定义在cyber/component/component.h中,如下所示:
template <typename M0 = NullType, typename M1 = NullType,
typename M2 = NullType, typename M3 = NullType>
class Component : public ComponentBase {
public:
Component() {}
~Component() override {}
/**
* @brief init the component by protobuf object.
*
* @param config which is defined in 'cyber/proto/component_conf.proto'
*
* @return returns true if successful, otherwise returns false
*/
bool Initialize(const ComponentConfig& config) override;
bool Process(const std::shared_ptr<M0>& msg0, const std::shared_ptr<M1>& msg1,
const std::shared_ptr<M2>& msg2,
const std::shared_ptr<M3>& msg3);
private:
/**
* @brief The process logical of yours.
*
* @param msg0 the first channel message.
* @param msg1 the second channel message.
* @param msg2 the third channel message.
* @param msg3 the fourth channel message.
*
* @return returns true if successful, otherwise returns false
*/
virtual bool Proc(const std::shared_ptr<M0>& msg0,
const std::shared_ptr<M1>& msg1,
const std::shared_ptr<M2>& msg2,
const std::shared_ptr<M3>& msg3) = 0;
};
由代码可见,Component类最多可以接收4个模板参数,每个模板参数均表示一种输入的消息类型,这些消息在Proc函数中被周期性的调用和处理
对于源文件commoncomponent_example.cc,Init和Proc这两个函数需要实现。
#include "example_components/src/common_component_example.h"
bool CommonComponentSample::Init() {
AINFO << "Commontest component init";
return true;
}
bool CommonComponentSample::Proc(const std::shared_ptr<example::proto::Driver>& msg0,
const std::shared_ptr<example::proto::Driver>& msg1) {
AINFO << "Start common component Proc [" << msg0->msg_id() << "] ["
<< msg1->msg_id() << "]";
return true;
}
可见基于common_component_example_lib库最终生成了一个共享库文件libcommon_component_example.so,而该共享库通过Cyber RT调度程序mainboard动态加载运行。
load("//tools:cpplint.bzl", "cpplint")
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
package(default_visibility = ["//visibility:public"])
cc_binary(
name = "libcomponent_examples.so",
linkshared = True,
linkstatic = True,
deps = [
":timer_common_component_example_lib",
":common_component_example_lib"
],
)
cc_library(
name = "timer_common_component_example_lib",
srcs = ["timer_common_component_example.cc"],
hdrs = ["timer_common_component_example.h"],
visibility = ["//visibility:private"],
alwayslink = True,
deps = [
"//cyber",
"//example_components/proto:examples_cc_proto",
],
)
cc_library(
name = "common_component_example_lib",
srcs = ["common_component_example.cc"],
hdrs = ["common_component_example.h"],
visibility = ["//visibility:private"],
alwayslink = True,
deps = [
"//cyber",
"//example_components/proto:examples_cc_proto",
],
)
cpplint()
DAG配置文件是Cyber RT调度程序mainboard动态加载模块的最终配置文件。在DAG依赖配置文件(例如example.dag)中配置如下项目:
Channel names: 输入 Channel 的名称
Library path: 该组件生成的共享库路径
Class name: 此组件类的名称
配置实例如下所示:
# Define all coms in DAG streaming.
module_config {
# 共享库文件路径
module_library : "/opt/apollo/neo/packages/example-components-dev/latest/lib/libcomponent_examples.so"
timer_components {
class_name : "TimerCommonComponentSample"
config {
name : "CommonComponent"
# 消息频率:10ms
interval : 10
}
}
components {
# 组件类名称,一定不能写错,否则mainboard无法动态创建CommonComponentSample组件对象
class_name : "CommonComponentSample"
config {
# 模块名
name : "example"
readers {
channel: "/apollo/channel_example/driver_test"
}
readers {
channel: "/apollo/channel_example/driver_test2"
}
}
}
}
在launch启动文件中(example.launch),配置下面的选项:
name :组件的名字
dag_conf :上一步配置的 DAG 文件路径
process_name :运行组件时的进程名
配置实例:
<cyber>
<component>
<name>common</name>
<dag_conf>/apollo/cyber/examples/common_component_example/common.dag</dag_conf>
<process_name>common</process_name>
</component>
</cyber>
通过下面的命令来编译组件:
buildtool build --packages example_components
运行组件的命令:
(1)通过launch文件启动
cyber_launch start example_components/example.launch
(2)通过.dag文件启动
mainboard -d example_components/example.dag
同时在另一个终端开启Cyber_monitor
cyber_monitor
本节实现一个简单的Component实例,实现两路channel消息融合,并将两路channel消息编号依次打印到屏幕终端。
apollo_workspace
|--test
|--common_component_example
| |--BUILD // bazel编译文件
| |--driver_writer.cc // 向driver channel中写消息的writer
| |--chatter_writer.cc // 向chatter channel中写消息的writer
| |--common_component_example.cc // component 源文件
| |--common_component_example.h // component 头文件
| |--common.dag // component 配置文件
| |--common.launch // component launch文件
|--proto
|--BUILD // protobuf的编译文件
|--examples.proto // protobuf
|--BUILD
|--test.BUILD
|--cyberfile.xml
syntax = "proto2"; // proto版本
package apollo.cyber.test.proto; // proto命名空间
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;
};
load("@rules_proto//proto:defs.bzl", "proto_library")
load("@rules_cc//cc:defs.bzl", "cc_proto_library")
load("//tools:python_rules.bzl", "py_proto_library")
package(default_visibility = ["//visibility:public"])
cc_proto_library(
name = "examples_cc_proto",
deps = [
":examples_proto",
],
)
proto_library(
name = "examples_proto",
srcs = ["examples.proto"],
)
load("@rules_proto//proto:defs.bzl", "proto_library") proto相关编译规则
load("@rules_cc//cc:defs.bzl", "cc_proto_library") c++相关编译规则
load("//tools:python_rules.bzl", "py_proto_library") python相关编译规则,apollo中自定义的
#include "cyber/cyber.h"
#include "test/common_component_example/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::test::proto::Chatter; //命名空间
int main(int argc, char *argv[]) {
apollo::cyber::Init(argv[0]);
auto talker_node = apollo::cyber::CreateNode("chatter_writer");
// 创建writer,写Chatter类型消息
auto talker = talker_node->CreateWriter<Chatter>("/apollo/chatter");
// 创建计时器
Rate rate(3.0);
std::string content("apollo_prediction");
while (apollo::cyber::OK()) {
static uint64_t seq = 0;
auto msg = std::make_shared<Chatter>(); // Chatter的智能指针
msg->set_timestamp(Time::Now().ToNanosecond()); // 时间戳
msg->set_lidar_timestamp(Time::Now().ToNanosecond());
msg->set_seq(seq++);
msg->set_content(content + std::to_string(seq - 1));
talker->Write(msg); // 将数据写入channel
AINFO << "/apollo/chatter sent message, seq=" << (seq - 1) << ";";
// 每秒3次
rate.Sleep();
}
return 0;
}
#include "cyber/cyber.h"
#include "test/common_component_example/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::test::proto::Driver;
int main(int argc, char *argv[]) {
// 初始化cyber
apollo::cyber::Init(argv[0]);
// 创建node
auto talker_node = apollo::cyber::CreateNode("driver_writer");
// 创建writer,写Driver类型消息
auto talker = talker_node->CreateWriter<Driver>("/apollo/driver");
// 新建计时器
Rate rate(2.0);
std::string content("apollo_test");
while (apollo::cyber::OK()) {
static uint64_t seq = 0;
auto msg = std::make_shared<Driver>();
// 创建一个Driver类型的消息并填入数据
msg->set_timestamp(Time::Now().ToNanosecond());
msg->set_msg_id(seq++);
msg->set_content(content + std::to_string(seq - 1));
talker->Write(msg);
AINFO << "/apollo/driver sent message, seq=" << (seq - 1) << ";";
// 每秒2次
rate.Sleep();
}
return 0;
}
#pragma once
#include
#include "cyber/component/component.h"
#include "test/common_component_example/proto/examples.pb.h"
using apollo::cyber::Component;
using apollo::cyber::ComponentBase;
using apollo::cyber::test::proto::Driver;
using apollo::cyber::test::proto::Chatter;
// 有两个消息源,继承以Driver和Chatter为参数的Component模版类
class CommonComponentSample : public Component<Driver, Chatter> {
public:
bool Init() override;
// Proc() 函数的两个参数表示两个channel中的最新的信息
bool Proc(const std::shared_ptr<Driver>& msg0,
const std::shared_ptr<Chatter>& msg1) override;
};
// 将CommonComopnentSample注册在cyber中
CYBER_REGISTER_COMPONENT(CommonComponentSample)
可以看到,此处继承了Component
#include "test/common_component_example/com_component_test/common_component_example.h"
// 在加载component时调用
bool CommonComponentSample::Init() {
AINFO << "Commontest component init";
return true;
}
// 在主channel,也就是Driver有消息到达时调用
bool CommonComponentSample::Proc(const std::shared_ptr<Driver>& msg0,
const std::shared_ptr<Chatter>& msg1) {
// 将两个消息的序号格式化输出
AINFO << "Start common component Proc [" << msg0->msg_id() << "] ["
<< msg1->seq() << "]";
return true;
}
module_config {
module_library : "/opt/apollo/neo/packages/test-dev/latest/lib/libcommon_component_example.so"
components {
class_name : "CommonComponentSample"
config {
name : "common"
readers {
channel: "/apollo/driver"
}
readers {
channel: "/apollo/chatter"
}
}
}
}
module_library:指向 Component 编译后得到的.so文件的存放目录。
components:表示 Component 的类型,除了components外,还有一种是timer_component,将会在下个例子中讲解。
class_name:表示被加载的 Component 的类名,在这个例子中是 CommonComponentSample。
name:表示被加载的类在 Cyber 中的标识名。
readers:表示 Component 所读取的 Channel ,与其继承的基类读取的类型一一对应。
<cyber>
<module>
<name>common</name>
<dag_conf>/apollo_workspace/test/common_component_example/com_component_test/common.dag</dag_conf>
<process_name>common</process_name>
</module>
</cyber>
:表示加载的 Component 在 Cyber 中的标识名,与 dag 文件中的name字段对应。
:表示 dag 配置文件路径。
:表示启动后的线程名,与线程名相同的component 会在此线程中运行。
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
load("//tools/install:install.bzl", "install", "install_src_files")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_binary(
name = "libcommon_component_example.so",
linkshared = True,
linkstatic = True,
deps = [":common_component_example_lib"],
)
cc_library(
name = "common_component_example_lib",
srcs = ["common_component_example.cc"],
hdrs = ["common_component_example.h"],
visibility = ["//visibility:private"],
deps = [
"//cyber",
"//test/common_component_example/proto:examples_cc_proto", // 路径按自己的改
],
alwayslink = True,
)
cc_binary(
name = "driver_writer",
srcs = ["driver_writer.cc"],
linkstatic = True,
deps = [
"//cyber",
"//test/common_component_example/proto:examples_cc_proto",
],
)
cc_binary(
name = "chatter_writer",
srcs = ["chatter_writer.cc"],
linkstatic = True,
deps = [
"//cyber",
"//test/common_component_example/proto:examples_cc_proto",
],
)
filegroup(
name = "conf",
srcs = [
":common.dag",
":common.launch",
],
)
install(
name = "install",
data = [
":conf",
],
runtime_dest = "test/bin",
library_dest = "test/lib",
data_dest = "test/common_component_example/conf",
targets = [
":chatter_writer",
":driver_writer",
"libcommon_component_example.so",
],
)
install_src_files(
name = "install_src",
src_dir = ["."],
dest = "test/src/common_component_example",
filter = "*",
)
cpplint()
buildtool build -p test/
注意:
install关键字:
runtime_dest 可执行文件位置
library_dest 库文件位置
data_dest.dag/.launch 文件的位置
记得修改包管理BUILD文件中的deps
完成编译后,我们就可以运行 Cyber 并加载 Component了,如上文所说,Cyber 会根据配置文件来加载 Component。Cyber 提供了两种加载 Component 的方法:
方法一、使用mainboard启动:mainboard -d
mainboard -d test/common_component_example/common.dag
方法二、使用cyber_launch启动:cyber_launch start
cyber_launch start test/common_component/common.launch
启动三个终端
#第一个
export GLOG_alsologtostderr=1
./bazel-bin/test/common_component_example/driver_writer
#第二个
export GLOG_alsologtostderr=1
./bazel-bin/test/common_component_example/chatter_writer
#第三个
export GLOG_alsologtostderr=1
cyber_launch start test/common_component_example/common.launch
cyber_monitor可以查看channel信息
CommonComponentSample每接受到一次主channel信息,执行一次Proc()函数,Proc()函数执行消息融合逻辑依次打印出两路消息的编号到屏幕上。
可以看到CommonComponentSample打印到屏幕上的信息,其中主channel信息(Driver信息)编号是依次递增的,而非主channel信息(Chatter信息)编号会出现缺失或者重复,这是因为component的Proc()函数只有主channel消息到达时才会触发执行,Proc()函数执行时会读取所有融合channel最新消息。
在本节中,我们会实现两个TimerComponent,分别是TimerDriverSample和TimerChatterSample,用来替换掉上一个案例中的两个 Writer。
apollo_workspace
|--test
|--timer_component_example
|--BUILD
|--timer_chatter.h // TimerChatterSample 头文件
|--timer_chatter.cc // TimerChatterSample 源文件
|--timer_driver.h // TimerDriverSample 头文件
|--timer_driver.cc // TimerDriverSample 源文件
|--driver.dag // TimerDriverSample 配置文件
|--driver.launch // TimerDriverSample launch文件
|--chatter.dag // TimerChatterSample 配置文件
|--chatter.launch // TimerChatterSample launch文件
沿用TEST1中的文件
#include
#include "cyber/class_loader/class_loader.h"
#include "cyber/component/component.h"
#include "cyber/component/timer_component.h"
#include "test/common_component_example/proto/examples.pb.h"
using apollo::cyber::Component;
using apollo::cyber::ComponentBase;
using apollo::cyber::TimerComponent;
using apollo::cyber::Writer;
using apollo::cyber::test::proto::Chatter;
class TimerChatterSample : public TimerComponent {
public:
bool Init() override;
bool Proc() override;
private:
std::shared_ptr<Writer<Chatter>> chatter_writer_ = nullptr;
};
CYBER_REGISTER_COMPONENT(TimerChatterSample)
可以看到,TimeChatterComponent 需要继承 TimerComponent基类,代码结构与普通的 Component 几乎相同。
不同的是因为没有数据源,所以没有模版参数。
#include "test/timer_component_example/timer_chatter.h"
#include "cyber/class_loader/class_loader.h"
#include "cyber/component/component.h"
#include "test/common_component_example/proto/examples.pb.h"
bool TimerChatterSample::Init() {
chatter_writer_ = node_->CreateWriter<Chatter>("/apollo/chatter");
return true;
}
bool TimerChatterSample::Proc() {
static int i = 0;
auto out_msg = std::make_shared<Chatter>();
out_msg->set_seq(i++);
chatter_writer_->Write(out_msg);
AINFO << "timer_chatter: Write chattermsg->"
<< out_msg->ShortDebugString();
return true;
}
TimerChatter 在 Init()中初始化了 Writer,并在 Proc()中向 Channel 中写信息。
#include
#include "cyber/class_loader/class_loader.h"
#include "cyber/component/component.h"
#include "cyber/component/timer_component.h"
#include "test/common_component_example/proto/examples.pb.h"
using apollo::cyber::Component;
using apollo::cyber::ComponentBase;
using apollo::cyber::TimerComponent;
using apollo::cyber::Writer;
using apollo::cyber::test::proto::Driver;
class TimerDriverSample : public TimerComponent {
public:
bool Init() override;
bool Proc() override;
private:
std::shared_ptr<Writer<Driver>> driver_writer_ = nullptr;
};
CYBER_REGISTER_COMPONENT(TimerDriverSample)
#include "test/timer_component_example/timer_driver.h"
#include "cyber/class_loader/class_loader.h"
#include "cyber/component/component.h"
#include "test/common_component_example/proto/examples.pb.h"
bool TimerDriverSample::Init() {
driver_writer_ = node_->CreateWriter<Driver>("/apollo/driver");
return true;
}
bool TimerDriverSample::Proc() {
static int i = 0;
auto out_msg = std::make_shared<Driver>();
out_msg->set_msg_id(i++);
driver_writer_->Write(out_msg);
AINFO << "timer_driver: Write drivermsg->"
<< out_msg->ShortDebugString();
return true;
}
module_config {
module_library : "/opt/apollo/neo/packages/test-dev/latest/lib/libtimer_chatter.so"
timer_components {
class_name : "TimerChatterSample"
config {
name : "timer_chatter"
interval : 400
}
}
}
interval:表示 TimerComponent 执行 Proc()的间隔,此配置中为 400 ms 执行一次。
因为没有数据融合,所以没有readers字段
其余配置和普通 Component 相同
<cyber>
<module>
<name>timer_chatter</name>
<dag_conf>/opt/apollo/neo/packages/test-dev/latest/timer_component_example/conf/chatter.dag</dag_conf>
<process_name>timer_chatter</process_name>
</module>
</cyber>
module_config {
module_library : "/opt/apollo/neo/packages/test-dev/latest/lib/libtimer_driver.so"
timer_components {
class_name : "TimerDriverSample"
config {
name : "timer_driver"
interval : 200
}
}
}
<cyber>
<module>
<name>timer_driver</name>
<dag_conf>/opt/apollo/neo/packages/test-dev/latest/timer_component_example/conf/driver.dag</dag_conf>
<process_name>timer_driver</process_name>
</module>
</cyber>
load("@rules_cc//cc:defs.bzl", "cc_binary", "cc_library")
load("//tools/install:install.bzl", "install", "install_src_files")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_binary(
name = "libcommon_component_example.so",
linkshared = True,
linkstatic = True,
deps = [":common_component_example_lib"],
)
cc_library(
name = "common_component_example_lib",
srcs = ["common_component_example.cc"],
hdrs = ["common_component_example.h"],
visibility = ["//visibility:private"],
deps = [
"//cyber",
"//test/common_component_example/proto:examples_cc_proto",
],
alwayslink = True,
)
cc_binary(
name = "driver_writer",
srcs = ["driver_writer.cc"],
linkstatic = True,
deps = [
"//cyber",
"//test/common_component_example/proto:examples_cc_proto",
],
)
cc_binary(
name = "chatter_writer",
srcs = ["chatter_writer.cc"],
linkstatic = True,
deps = [
"//cyber",
"//test/common_component_example/proto:examples_cc_proto",
],
)
filegroup(
name = "conf",
srcs = [
":common.dag",
":common.launch",
],
)
install(
name = "install",
data = [
":conf",
],
runtime_dest = "test/bin",
library_dest = "test/lib",
data_dest = "test/common_component_example/conf",
targets = [
":chatter_writer",
":driver_writer",
"libcommon_component_example.so",
],
)
install_src_files(
name = "install_src",
src_dir = ["."],
dest = "test/src/cyberatest",
filter = "*",
)
cpplint()
记得修改包管理BUILD文件中的deps.
同上
我们实现的两个 TimerComponent 可以用来替代上一个案例中的两个定时写消息的 Writer,启动方法也与上一案例类似,不同的是 TimerComponent 可以通过配置文件配置。
同样开启三个终端
# 第一个
export GLOG_alsologtostderr=1
cyber_launch start test/common_component_example/common.launch
# 第二个
export GLOG_alsologtostderr=1
cyber_launch start test/timer_component_example/driver.launch
# 第三个
export GLOG_alsologtostderr=1
cyber_launch start test/timer_component_example/chatter.launch
CommonComponentSample每接受到一次主channel信息,执行一次Proc()函数,Proc()函数执行消息融合逻辑依次打印出两路消息的编号到屏幕上。
TimerChatterSample每隔400ms/200ms,由系统定时器调用Proc()函数,Proc()函数每执行一次就发出一条消息。并打印该条消息的编号到屏幕上。