0. 前言

Github 仓库链接Hikvision Camera ROS2 package

0.1 问题背景

上一篇博客](https://www.guyuehome.com/blog/detail/id/12240))介绍了我开源的海康相机 ROS2 功能包,在本地机器上可以实时订阅和发布图像消息,但是在通过局域网进行多机通信的测试时,PC 端收不到边缘端发布的图像消息,不过可以通过 ros2 topic list 查看到图像话题是存在的。

经过查询资料,这主要是由于 DDS 的不同实现的实时性和可靠性存在不同。

0.2 ROS2 下的 DDS 的不同实现

以下是一个简单的表格,介绍ROS 2中四种不同的DDS实现:Fast DDS、OpenSplice DDS、Connext DDS和Eclipse Cyclone DDS。

DDS实现 介绍 优点 缺点
Fast DDS - 前身为Fast RTPS,是ROS 2中默认的DDS实现。 - 高性能和可靠性。
- 支持大规模的分布式系统。
- 配置灵活,易于集成。
- 开源免费。
- 部分功能可能仍在演进中。
- 可能需要一些时间来适应配置和优化。
- 社区相对较小。
OpenSplice DDS - 另一个受欢迎的DDS实现,已与ROS 2集成。 - 成熟稳定,可靠性较高。
- 支持多种平台。
- 支持实时性和安全性。
- 良好的工具和支持。
- 闭源商业软件,可能需要购买许可证。
- 社区支持相对较少。
- 文档可能不如其他实现全面。
Connext DDS - 来自RTI的商业DDS实现,广泛应用于实时系统。 - 高度可靠,性能优秀。
- 支持广泛的平台和编程语言。
- 强调实时性和安全性。
- 良好的支持和文档。
- 商业软件,需要购买许可证。
- 可能对资源占用较高。
- 开源版本功能有限。
Eclipse Cyclone DDS - 开源且高效的DDS实现,可用作Fast DDS的替代方案。 - 开源免费,社区活跃。
- 性能良好,轻量级实现。
- 支持多种平台和语言。
- 可能缺乏一些高级功能和工具。
- 文档相对较少。
- 社区支持较其他实现略少。

0.3 如何挖掘 DDS 的性能

在这里我选择的是 Eclipse Cyclone DDS 这个 DDS 实现,但想要实现我想要的效果,还需要对其进行调优,参数设置得不好的话,最终效果会很差。下面具体介绍一下为什么要对 DDS 进行调优。

DDS需要调优的主要原因是确保它能够满足应用程序的性能和可靠性要求。由于不同的应用场景和硬件平台有着不同的特点和约束,因此需要进行调优以使DDS能够最大程度地发挥优势。

以下是为什么DDS需要调优的几个主要原因:

  1. 性能优化: DDS的性能对实时应用至关重要。通过调优,可以降低通信延迟,提高数据传输速率,增加系统的吞吐量,以满足实时系统对数据传输的实时性要求。

  2. 资源利用: 在分布式系统中,资源(如带宽、CPU、内存)是有限的。DDS调优可以帮助合理利用这些资源,减少资源浪费,提高系统的效率和稳定性。

  3. QoS配置: DDS提供了丰富的Quality of Service(QoS)选项,用于控制数据传输的各个方面,如数据可靠性、优先级、历史数据存储等。通过正确配置QoS参数,可以满足应用对数据传输的不同需求。

  4. 网络适应性: 在跨越不同网络环境的分布式系统中,DDS需要适应各种网络条件,如高延迟、不稳定连接等。调优可以帮助DDS在不同网络环境下保持稳定的通信,并减少数据丢失的可能性。

  5. 安全性: 对于一些安全性要求较高的应用,DDS需要配置加密和认证机制,以保护数据的机密性和完整性。

  6. 调试和故障排除: 调优也有助于发现和解决DDS在系统中可能出现的问题,提高系统的稳定性和可靠性。

综上所述,DDS调优是为了使DDS能够更好地适应特定的应用场景和硬件平台,提高系统的性能、实时性和可靠性,确保分布式系统能够顺利地进行数据通信和协作。

1. 具体操作

1.1 Cyclone DDS 调优参数设置

下面内容需要同时在边缘端和 PC 端进行设置。

首先,安装并配置环境变量:

sudo apt install ros-foxy-rmw-cyclone-cpp
echo 'export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp' >> ~/.bashrc

接着,在终端中直接设置下面三个参数:

sudo sysctl net.ipv4.ipfrag_time=3
sudo sysctl -w net.core.rmem_max=2147483648
sudo sysctl net.ipv4.ipfrag_high_thresh=2147483648

然后,创建一个 config.xml 文件,内容如下:

<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain id="any">
<Internal>
<MinimumSocketReceiveBufferSize>1024MB</MinimumSocketReceiveBufferSize>
</Internal>
</Domain>
</CycloneDDS>

最后,在终端中临时加载上面参数文件:

CYCLONEDDS_URI=/path/to/config.xml

1.2 局域网配置

确保边缘计算设备和 PC 通过 Wi-Fi 或有线连接到同一个局域网,如果设备很多,都是通过同一个局域网,且想对设备进行分组进行分布式通信,可以设置下面参数,设置了相同编号的设备之间就可以进行通信了,不设置的话就是所有设备之间都可以进行通信:

echo 'export ROS_DOMAIN_ID=5' >> ~/.bashrc

1.3 测试

克隆 Github 上的功能包代码,怎么创建工作空间和编译这里就不再赘述了,ROS2 新手移步上一篇博客学习。

将海康相机连接在边缘设备上,执行测试程序:

# 边缘端执行发布
ros2 run hk_camera hk_camera_compressed_pub_test_reliable
# PC 端执行订阅
ros2 run hk_camera hk_camera_compressed_sub_test_reliable

PC 端订阅图像效果如下,虽然相机最高帧率可达到 40Hz,但是这里我的边缘设备最高发布速率只能达到 20 fps,在 PC 端可以实现实时接收图像:

边缘端图像发布大概 8MiB/s:

PC 端接收的速率也大概是 8MiB/s:

2. 解析

2.1 关于图像话题类型

为了进一步提高通信的效率,这里我选择使用 ROS2 的压缩图像消息进行传输,这个类型的消息在 ROS2 Foxy 中是不支持可视化的,不过不必担心,我在代码库中给出了 OpenCV 窗口可视化的程序,同时实时显示帧率。

虽然是压缩图像消息,但分辨率也是 1920x1200 的,与原图相同,只是使用了不同的压缩算法(如JPEG、PNG等)对图像进行压缩,以减少传输所需的带宽和存储空间。这里大家根据自己的需求和带宽进行选择。

2.2 DDS 调优中的几个参数

下面的表格介绍 Cyclone DDS 中的四个调优参数,前两个是 Cyclone DDS 专属的调优参数,后面两个对各种 DDS 实现都是有效的:

调优参数 参数名称 介绍 取值范围与建议设置
系统接收缓冲区的最大大小 (Max System Receive Buffer Size) net.core.rmem_max 控制 Cyclone DDS 在系统级别上接收数据包的缓冲区的最大大小。 根据系统的硬件资源和网络情况进行设置。
建议值:通常不超过物理内存的50%。
最小套接字接收缓冲区大小 (Min Socket Receive Buffer Size) 在上面 xml 文件内 定义每个套接字接收缓冲区的最小大小。 视系统的网络延迟和传输负载而定。
建议值:根据具体应用,通常在几 KB 到几 MB 之间。
IP分片的超时时间 (IP Fragmentation Timeout) net.ipv4.ipfrag_time 等待所有 IP 分片到达的最大时间。 视网络传输延迟和分片大小而定。
建议值:根据具体网络情况,通常在几百毫秒到数秒之间。
IP分片的阈值 (IP Fragmentation Threshold) net.ipv4.ipfrag_high_thresh 允许 DDS 数据包被切分成 IP 分片的最大大小。 视网络传输 MTU 大小和数据包大小而定。
建议值:根据网络 MTU 和数据包大小,通常设置为适当的值以避免数据包过大或过小。

注意,不同的应用场景和系统配置可能需要不同的参数设置。对于特定的硬件平台、网络环境和通信要求,需要根据具体情况来优化这些参数,以实现最佳的性能和稳定性。建议在调优之前,先进行测试和性能评估,以便找到最合适的参数配置。在调整参数时,也要注意避免设置过大的缓冲区导致资源浪费或过小的缓冲区导致数据丢失。

2.3 QoS

QoS(Quality of Service,服务质量)是指在分布式系统中,用于描述通信协议和中间件如何提供服务的一组参数和规则。它允许应用程序在不同的通信需求和资源约束下进行配置,以达到满足特定的性能、可靠性、实时性和资源利用等要求的目标。

在ROS 2中,QoS是DDS(Data Distribution Service)中用于配置通信行为的重要概念。通过定义特定的QoS参数,可以对数据传输进行调优,以满足不同应用场景的需求。以下是一些常见的QoS参数:

  1. Reliability(可靠性): 描述数据传输的可靠性,可以是“可靠”或“不可靠”。可靠性要求数据包的可靠传输,确保数据不会丢失,并且按照发送的顺序到达;而不可靠性允许数据包丢失,适用于实时性要求较高但对数据完整性要求较低的场景。

  2. Durability(持久性): 指示数据在传输结束后是否会被保留,以便新的订阅者能够获取到历史数据。持久性可以是“持久”或“临时”,持久性允许历史数据保存,而临时性仅传输最新的数据。

  3. Deadline(截止时间): 规定数据在发送后的有效期限,超过截止时间后,接收方将不再接收过期的数据。

  4. Liveliness(活跃性): 描述发送方的活跃状态,用于检测是否有发送方不再活跃。活跃性机制可确保接收方能够及时知道发送方是否还在运行。

  5. History(历史): 描述订阅者接收到的历史数据的数量和顺序,可设置为”KEEP_LAST”(保留最新的若干数据)或”KEEP_ALL”(保留所有历史数据)。

  6. Resource Limits(资源限制): 定义通信使用的资源限制,如发送和接收缓冲区的大小,以及消息的最大大小等。

通过合理配置这些QoS参数,ROS 2中的DDS实现(如Cyclone DDS、Fast DDS等)可以根据不同应用场景的需求来优化通信性能、可靠性和实时性。这使得ROS 2能够适用于各种实时和分布式系统,如机器人控制、自动驾驶、医疗设备监控等。

下面是我在发布程序中的对于可靠性和持久性的设置:

rclcpp::QoS qos_profile_realtime(30); // 更高的发布频率,根据您的需求调整该值 
qos_profile_realtime.reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE); // 可靠的数据传输 
qos_profile_realtime.durability(RMW_QOS_POLICY_DURABILITY_VOLATILE); // 减少消息积压

auto image_pub = hk_camera->create_publisher<sensor_msgs::msg::CompressedImage>( "/hk_camera/rgb/compressed", qos_profile_realtime); // 使用自定义的 QoS 配置来进行可靠的图像发布

......

rclcpp::Rate loop_rate(30); // 这里也设置为 30,因为头文件中的相机帧率参数被设置为 30 帧了

头文件中的相机帧率参数被设置为 30 帧,实际相机确实是以 30 帧在录制视频,但是由于图像变量类型的转换和发布图像消息的耗时,ROS2 节点在从相机中读图像时只能以 20Hz 的频率读取,当然这里可以都设置为 20。

在订阅程序中也进行同样的设置:

rclcpp::QoS qos_profile_realtime(30); // 更高的发布频率,根据您的需求调整该值
qos_profile_realtime.reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE); // 可靠的数据传输
qos_profile_realtime.durability(RMW_QOS_POLICY_DURABILITY_VOLATILE); // 减少消息积压
// 创建图像消息的订阅者,订阅话题为"/hk_camera/rgb/compressed",使用可靠的QoS
auto image_subscriber = node->create_subscription<sensor_msgs::msg::CompressedImage>(
    "/hk_camera/rgb/compressed",
    qos_profile_realtime, // 使用自定义的 QoS 配置进行可靠的图像订阅
    imageCallback         // 回调函数处理接收到的图像消息
);