第二章:Cyber RT通信机制解析与实践

Cyber RT解析与实践

第二章:Cyber RT通信机制解析与实践



一、Cyber RT 通讯机制简介

1. 话题

在这里插入图片描述
我们想要⼀直获取⻋的速度,该需求不需要向发送⽅返回什么消息,也不需要发送⽅对消息进⾏进⼀步处理。所以我们选择了Listener-Talker通信⽅式实现该功能。
Listener-Talker通信⼀⽅主动送消息,⼀⽅被动接收。如图2-1所示,Listener-Talker通信⾸先创建了两个Node,分别是Talker Node和 Listener Node。每个Node实例化Writer类和Reader类对Channel进⾏消息的读写。Writer和Reader通过Topic连接,对同⼀块共享内存(Channel)进⾏读写处理。在这⾥,Talker Node 为了实现其“诉说”的功能,选择实例化Writer,通过Writer来对Channel进⾏消息写操
作。⽽istener Node为了实现其“聆听”功能,选择实例化reader类,通过Reader来对channel进⾏读操作。在这⾥,通信中⽤的的数据格式的定义car message 定义在car.proto中。该通信⽅式适合于持续性通信的应⽤场景,⽐如雷达信号,摄像头图像信息这类数据的传输。

2. 服务

在这里插入图片描述
我们想要获得⼩⻋的详细信息,⽐如⻋牌这些,但是⼜不需要⼀直获得该信息,想要在需要知道这些信息的时候请求⼀下就好,于是考虑⽤Server- Client通信实现该功能。如图2-1所示,Server-Client通信可以在客户端发出消息请求时,服务端才进⾏请求回应,并将客户端所需的数据返回给客户端。该通信模式适合临时的消息传输,适⽤于不需要持续性发送数据的场景。其传输的数据定义依然在对应的proto⽂件中。

3. 参数

在这里插入图片描述
有⼀些参数⽐如该⻋的最⾼限速,最多乘客以及是否⾃动驾驶等需要被各个模块所使⽤,⽐如是否⾃动驾驶这个参数可能同时影响这很多模块,也可能被很多模块运⾏时所更改。我们希望有⼀个类似于“全局变量”的⽅式来存储这些参数,并定义⼀些⾃定义参数来进⾏使⽤。Cyber中设计了全局参数服务器来实现这个功能,其通信依然基于RTPS协议,如图2-8所示。该通信⽅式服务端和客户端都可以设置参数和更改参数。

二、数据通信基础Protobuf

1. Protobuf 简介

Protobuf是Google公司开发的一种跨语言和平台的序列化数据结构的方式,是一个灵活的、高效的用于序列化数据的协议,与XML和JSON格式相比,Protobuf更小、更快、更便捷。
Protobuf是跨语言的,并且自带一个编译器(protoc),只需要用protoc进行编译,就可以编译成Java、Python、C++、C#、Go等多种语言代码,然后可以直接使用,不需要再写其它代码,自带有解析的代码。只需要将要被序列化的结构化数据定义一次(在.proto文件定义),便可以使用特别生成的源代码(使用protobuf提供的生成工具)轻松的使用不同的数据流完成对结构数据的读写操作。甚至可以更新.proto文件中对数据结构的定义而不会破坏依赖旧格式编译出来的程序。
其优点如下:

  • 性能效率高:序列化后字节占用空间比XML少3-10倍,序列化的时间效率比XML快20-100倍。
  • 使用便捷便捷:将对结构化数据的操作封装成一个类,便于使用。
  • 兼容性高:通信两方使用同一数据协议,当有一方修改了数据结构,不会影响另一方的使用。
  • 跨语言:支持Java,C++,Python、Go、Ruby等多种语言。

2. Protobuf 创建

为了方便讲解,使用cyber/examples/proto/examples.proto文件来讲解,syntax 表示使用Protobuf的版本,目前Protobuf支持proto3,但在Apollo中使用的是proto2;package 表示该文件的路径;每一个message都表示一种数据结构,message后面跟的是数据结构名字,括号里的字段定义格式为:字段规则 数据类型 字段名称 字段编号。
字段规则主要有三种:

  • required:调用时必须提供该字段的值,否则该消息被视为“未初始化”,官方不建议使用,当把字段规则改为其他规则会存在兼容性问题。
  • optional:该字段的值可以设置也可以不设置,会根据数据类型生成一个默认的值。
  • repeated:类似于动态数组,可以存储多个同类型的数据。
# examples.proto
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;
};

3. Protobuf 编译

Protobuf的编译要分为两个步骤,首先要根据.proto文件生成proto库,然后再根据生产的proto库生成C++相关的源文件。这个源文件是C++语言自动编写的,可以被C++程序自动识别。每一个message会被解析生一个类,里面的字段就相当于这个类的属性。在源文件中也会根据属性生成额外的成员,如获取和设置属性的函数。

package(default_visibility = ["//visibility:public"])
#1、生成proto库
proto_library(
    name = "examples_proto",
    srcs = ["examples.proto"],
)
#2、生成源文件
cc_proto_library(
    name = "examples_cc_proto",
    deps = [
        ":examples_proto",
    ],
)

4. Protobuf 案例实战

目的:使用Protobuf来定义数据格式,在main程序中设置数据值并输出。
流程:1、创建目录并编写相关文件;2、编译执行。
内容如下:

1. 创建test功能包结构:

test
|-- test_proto
    |-- BUILD
    |-- car.cc
|-- proto
    |-- BUILD
    |-- car_msg.proto

各个结构内容如下:

2. test_proto/BUILD

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 = "car",
    srcs = ["car.cc"],
    deps = ["//test/proto:car_msg_cc_proto"], 
)

install(
    name = "install",
    runtime_dest = "test/bin",
    targets = [
        ":car"
    ],
)

install_src_files(
    name = "install_src",
    src_dir = ["."],
    dest = "test/src/cyberatest",
    filter = "*",
)

代码解析:
此文件为Bazel构建文件,它描述了如何构建一个名为"car"的二进制可执行文件。

  • 首先,代码中使用了几个load语句来加载Bazel的内置规则和自定义规则。这些规则包含在不同的Bazel文件中,并通过文件路径进行引用。本代码中,加载了cc_binary、cc_library、install和install_src_files等规则。
  • 接下来,使用了package语句来设置默认的可见性(visibility)。这里将软件包的可见性设置为public,意味着该软件包中的所有目标(targets)都可以被其他软件包访问到。
  • 然后,使用了cc_binary规则来定义一个名为"car"的二进制可执行文件。该可执行文件的源代码文件是"car.cc",依赖的库是//test/proto:car_msg_cc_proto,这意味着需要先构建并链接该库才能构建该可执行文件。
  • 接下来,使用了install规则来定义一个名为"install"的安装目标,用于将构建好的文件安装到指定的运行时目录下。这里将目标设置为":car",表示安装构建好的"car"目标。安装位置是"test/bin"。
  • 最后,使用了install_src_files规则来定义一个名为"install_src"的安装源码文件目标。这个目标的作用是将当前目录下的源代码文件安装到指定的目录下。这里将源码文件目录设置为当前目录,安装目标路径设置为"test/src/cyberatest",并通过filter参数指定只安装匹配通配符"*"的文件。
    总的来说,本构建文件描述了如何构建和安装一个名为"car"的二进制可执行文件,并将其安装到指定的目录中,同时也将源代码文件安装到指定目录中。

3. test_proto/car.cc

#include "test/proto/car_msg.pb.h"
using namespace std;

int main()
{
    
    
    apollo::cyber::test::proto::CarMsg car;

    car.set_owner("apollo");
    car.set_license_plate("京A88888");
    car.set_max_passenger(6);
    car.add_car_info("SUV"); //车型
    car.add_car_info("Red"); //车身颜色
    car.add_car_info("electric"); //电动

    string owner = car.owner();
    string license_plate = car.license_plate();
    uint64_t max_passenger = car.max_passenger();
    
    cout << "owner:" << owner << endl;
    cout << "license_plate:" << license_plate << endl;
    cout << "max_passenger:" << max_passenger << endl;

    for (int i = 0; i < car.car_info_size(); ++i){
    
    
        string info = car.car_info(i);
        cout << info << " ";
    }
    cout << endl;
    return 0;
}

4. proto/BUILD

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"])

proto_library(
    name = "car_msg_proto",
    srcs = ["car_msg.proto"],
)

cc_proto_library(
    name = "car_msg_cc_proto",
    deps = [":car_msg_proto"],
)

5. proto/car_msg.proto

syntax = "proto2";

package apollo.cyber.test.proto;

message CarMsg {
    
    
    required string owner = 1;
    optional string license_plate = 2;
    optional uint64 max_passenger = 3;
    repeated string car_info = 4;
}

代码解析:

  • 在这个消息定义中,1、2、3、4是字段的标识符(field identifier)。它们用于唯一标识每个字段,并在序列化和反序列化过程中进行匹配。
  • 对于每个字段,标识符的前缀用于表示字段的类型(required、optional、repeated),后面的数字用于标识该字段在消息中的位置。在这里,"owner"字段的标识符是1,"license_plate"字段的标识符是2,"max_passenger"字段的标识符是3,"car_info"字段的标识符是4。
  • 这些标识符是为了确保消息在序列化和反序列化过程中的一致性,并且它们在消息协议中是唯一的。

6. 数据包的BUILD

代码解析:

  • 这是一个BUILD文件中的一部分,其中使用了Bazel构建系统的install和install_src_files规则。
  • 首先,通过load函数加载了"//tools/install:install.bzl"文件中的install和install_src_files规则。
  • 然后,通过install规则定义了一个名为"install"的安装规则。它指定了要安装的文件列表,其中包括"test.BUILD"和"cyberfile.xml"。它还指定了依赖关系,其中包括"//test/test_proto:install"规则。
  • 接下来,通过install_src_files规则定义了一个名为"install_src"的源文件安装规则。它指定了源文件的目录(src_dir),这里是当前目录(“.”)。它还指定了安装的目标目录(dest),这里是"test/src"。filter参数指定了要安装的源文件的通配符过滤条件,这里是"*“表示所有文件。它还指定了依赖关系,其中包括”//test/test_proto:install_src"规则。

7. cyberfile.xml

代码解析:
这段XML代码看起来像是一个描述软件包的清单文件,其中包含了各种关于软件包的信息。

  • 前面部分包含了:包类型,源码路径,许可证 ,作者等基础信息;
  • 第一个标签,它的类型是"binary",源代码路径是"//cyber",仓库名称是"cyber",依赖的软件包名称是"cyber-dev"。
  • 第二个标签没有指定类型,只指定了依赖的软件包名称"bazel-extend-tools-dev"。
  • 第三个标签没有指定类型,但通过lib_names属性指定了依赖的库名称是"protobuf",仓库名称是"com_google_protobuf",依赖的软件包名称是"3rd-protobuf-dev"。
  • : 标签用于指定构建软件包时使用的构建工具,这里是"bazel"。

6. 编译运行

代码到这里就可以进行编译运行:

// 编译
cd /apollo_workspace
buildtool build -p test

// 执行
cd /apollo_workspace/bazel-bin/test/test_proto
./car

运行结果如下图所示:
在这里插入图片描述
所有者:apollo
车牌号:京A88888
最大乘客人数:6
SUV红色电动


三、Cyber RT 话题通信实践案例

1. Listener 和 Talker通讯原理

在第一章中,我们已经说明了Node、Channel等Cyber的基础概念,本章我们基于这些基础概念,进一步介绍cyber中的三种通信方式,也即发送接收信息的三种方式。
为了更好的说明这三种通信机制的用法,该章我们通过实现一个案例来说明该部分内容。
案例如下,假设我们拥有了一辆自己的“无人车“,apollo号,现在我们想通过通信,获得该车辆的“实时”速度、车的详细信息以及车的通用参数。那么现在会有几个问题:

  • 车本身有的变量有哪些,应该在哪里定义?
  • 实现“实时”车速的获取和实现车的详细信息等应该用什么通信方式?在哪里实现?
  • 实现的代码应该如何运行起来?
    不要着急,接来下我们就开始用Cyber实现这个小demo,并一一解答以上疑问。
    该案例我们创建在/apollo/workspace/test文件下,命名为communication整体目录结构如下:

目录结构:

/apollo_workspace/
  |--test
  |   |--communication
  |   |  |--BUILD //cyber_test编译文件
      |  |--talker.cc //talker-listener通信实现
      |  |--listener.cc
      |  |--server.cc //server-client通信实现
      |  |--client.cc
      |  |--param_server.cc //parameter server-client通信实现
      |  |--param_client.cc 
      |--proto 
         |--BUILD //car.proto 编译文件
         |--car.proto  //小车数据定义的文件

通过第一节内容,我们知道了proto文件的使用方法,那么该章我们来自己编写一个proto文件,来实现我们“车”的变量定义,在该章的三种通信方式的案例中都是用这一数据定义。对car.proto文件进行编写,其内容如下:

2. 通信实现流程讲解

3. 编写C++话题通信实现

1. proto文件编写

首先我们要通过第一节内容,编写一个自己的proto文件,来实现我们“车”的变量定义,在本节中的三种通信方式的案例中都是用这一数据定义。对car.proto文件进行编写,其内容如下:

car.proto

// 定义proto使用的版本
syntax = "proto2";

//定义包名,在cc文件中调用
package apollo.cyber.test.proto;

//定义一个车的消息,车的型号,车主,车的车牌号,已跑公里数,车速
message Car{
    
    
    optional string plate = 1; 
    optional string type = 2;
    optional string owner = 3;
    optional uint64 kilometers = 4;
    optional uint64 speed = 5;
};

2. talker.cc 文件编写

我们来编写一个talker.cc来实现主动对话

talker.cc

//头文件引用
#include "test/proto/car.pb.h"
#include "cyber/cyber.h"
#include "cyber/time/rate.h"

//car数据定义的引用,可以看出其定义来源于一个proto
using apollo::cyber::examples::cyber_test_proto::Car;

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>("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<Car>();
        msg->set_speed(speed);
        //假设车速持续增加
        speed += 5;
        talker->Write(msg);
        sleep(1);
    }
    return 0;
}

3. listener.cc 文件编写

编写一个listener来实现对talker发送过来的内容进行接收。

listener.cc

#include "test/proto/car.pb.h"
#include "cyber/cyber.h"

using apollo::cyber::examples::cyber_test_proto::Car;

//接收到消息后的响应函数
void message_callback(
        const std::shared_ptr<Car>& 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>(
            "car_speed", message_callback);
    apollo::cyber::WaitForShutdown();
    return 0;
}

4. 运行与测试

1. 编写bazel编译文件

编写在cyber/examples/cyber_test/BUILD中。

talker 和 listener 编译文件。

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 = "talker",
    srcs = ["talker.cc"],
    deps = [
        "//cyber",
        "//test/proto:car_cc_proto",
    ],
    linkstatic = True,
)

cc_binary(
    name = "listener",
    srcs = ["listener.cc"],
    deps = [
        "//cyber",
        "//test/proto:car_cc_proto",
    ],
    linkstatic = True,
)

2. 编译:

aem start //启动docker环境
aem enter //进入docker环境

使用apollo 包管理开发方式提供的

buildtool build -p test/communication/

编译成功显示:
在这里插入图片描述

3. 运行:

首先,先将输出方法改为控制台输出。

export GLOG_alsologtostderr=1

打开两个终端,都进入Apollo的docker环境,一个终端运行talker,另一个运行listener,会发现listener运行后开始接收talker发送的小车速度的消息。

运行talker

./bazel-bin/test/communication/talker

终端显示:
在这里插入图片描述

运行listener

./bazel-bin/test/communication/listener

结果显示:
在这里插入图片描述
恭喜你,完成Apollo Cyber RT 的C++ 的话题通信实验喽!!!

5. 编写Python话题通信实现(小练习)

小测试!!!

6. 运行与测试

期待结果!!!


四、Cyber RT 本地部署之话题通信实践案例

1.安装部署:

https://apollo.baidu.com/community/Apollo-Homepage-Document/Apollo_Doc_CN_8_0?doc=%2F%25E5%25AE%2589%25E8%25A3%2585%25E8%25AF%25B4%25E6%2598%258E%2F%25E8%25BD%25AF%25E4%25BB%25B6%25E5%258C%2585%25E5%25AE%2589%25E8%25A3%2585%2F%25E8%25BD%25AF%25E4%25BB%25B6%25E5%258C%2585%25E5%25AE%2589%25E8%25A3%2585%2F

2. 创建和进入 Apollo 环境容器

1. 创建工作空间

创建并进入目录

mkdir application-demo
cd application-demo

2. 启动 apollo 环境容器

aem start

如果一切正常,将会见到类似下图的提示:
在这里插入图片描述

3. 进入 apollo 环境容器

aem enter

脚本执行成功后,将显示以下信息,您将进入 Apollo 的运行容器:
在这里插入图片描述

user_name@in-dev-docker:/apollo_workspace# 

工作空间文件夹将被挂载到容器的 /apollo_workspace 中。

4. 初始化工作空间

aem init

在这里插入图片描述
至此 Apollo 环境管理工具及容器已经安装完成。

3. Protobuf、talker-listener实践案例演示

1. Protobuf

在这里插入图片描述

2. talker-listener

在这里插入图片描述
在这里插入图片描述


总结

以上就是今天要讲的内容,本文仅仅简单介绍了apollo talker and listener 的使用,而apollo 提供了大量能使我们快速便捷地学习自动驾驶的案例和方法。

猜你喜欢

转载自blog.csdn.net/yechen1/article/details/131707570