for English please refer English
零拷贝机制可以节省IPC过程中的拷贝次数,可以降低cpu占用率和传输时延,对于时间敏感系统和资源受限的计算平台很有用。
对于单进程内使用零拷贝,可以使用rclcpp intra-process communication,在dashing版本后就可以使用。
对于ros2应用在IPC场景的零拷贝通信,在foxy版本后提供了loaned-api机制,参考ros2_design: Zero Copy via Loaned Messages
- ros2_shm_vision_demo: Demonstrate how to use shared memory with image processing algorithms.
- ros2_shm_demo by ApexAI: demonstrates how to use zero-copy Shared Memory data transfer in ROS 2 with CycloneDDS
该库参考了上述项目实现,以可扩展的方式提供了统一的图像和点云消息定义,类型转换方法,rviz桥接器,示例程序以及性能测试,对IPC(intra-machine, inter-process)零拷贝场景有很好的支持。
该版本在ros2 galactic和humble中测试通过,以下中间件可用
- rmw_cyclonedds_cpp
- cyclonedds(0.8.x)+iceoryx(1.0.x)
- rmw_fastrtps_cpp
- fastdds(>=2.3.x)
关于zero-copy的性能,请看ros2_jetson_benchmarks,性能测试基于这个基准测试框架GitHub - ZhenshengLee/performance_test: Github repo for apex.ai performance_test for more middlewares
该库已经应用在 定制版本的ros2_v4l2_camera and 定制版本的rslidar_sdk, 性能提升显著!
在Dell3630台式机的测试结果,基于fastdds,对于shm_msgs::msg::Image1m的零拷贝数据传输,相比于默认传输机制而言传输时延性能提升80%,from 1.4ms to 0.3ms.
this package includes ros2 msg definitions and demos that supports the msgs.
- shm_msgs::msg::PointCloud8k
- shm_msgs::msg::Image8k
- PointCloud2Modifier8k
- open3d_conversions
- opencv_conversions
- pcl_conversions
- shm_pcl_bridge
- shm_image_bridge
- shm_open3d_bridge
本包计划支持pointcloud 和 image两种数据类型。
feature | Status |
---|---|
pointcloud8k | ✔️ |
pointcloud512k | ✔️ |
pointcloud1m | ✔️ |
pointcloud2m | ✔️ |
pointcloud4m | ✔️ |
pointcloud8m | ✔️ |
image8k | ✔️ |
image512k | ✔️ |
image1m | ✔️ |
image2m | ✔️ |
image4m | ✔️ |
image8m | ✔️ |
open3d_conversions | ✔️ |
opencv_conversions | ✔️ |
pcl_conversions | ✔️ |
shm_image_bridge | ✔️ |
shm_open3d_bridge | ✔️ |
shm_pcl_bridge | ✔️ |
for rmw_cyclonedds
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
export CYCLONEDDS_URI=file:///$HOME/shm_cyclonedds.xml
# t0
iox-roudi
for rmw_fastrtps_cpp
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export FASTRTPS_DEFAULT_PROFILES_FILE=$HOME/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
for rmw_cyclonedds_cpp
iox-introspection-client --all
# to check if iceoryx_rt process has been created
for rmw_fastrtps_cpp,检查是否有内存映射文件生成
# check if shm-transport
ls /dev/shm/fastrtps_
# check if data-sharing
ls /dev/shm/fast_datasharing*
# t1
cd ./install/shm_msgs/lib/shm_msgs/
./image1m_talker
# t2
cd ./install/shm_msgs/lib/shm_msgs/
./image1m_listener
# configure topic remapping
ros2 launch shm_msgs shm_image_bridge.launch.py
to check the msg flow and visualize the msg
# t1
cd ./install/shm_msgs/lib/shm_msgs/
./pcl2m_talker
# t2
cd ./install/shm_msgs/lib/shm_msgs/
./pcl2m_listener
# configure topic remapping
ros2 launch shm_msgs shm_pcl_bridge.launch.py
to check the msg flow and visualize the msg
# t1
cd ./install/shm_msgs/lib/shm_msgs/
./open3d2m_talker
# t2
cd ./install/shm_msgs/lib/shm_msgs/
./open3d2m_listener
github and ros2 社区讨论了该库的实现方式和成果。
- 2021 08 05 Eclipse iceoryx developer meetup
- ros discourse about z copy with cycloedds and iceoryx
- ros discourse about using zero copy with ros2_shm_msgs
- autoware.auto issue: Enable zero-copy for pointcloud processing
- image_common issue: Use loaned messages to optimize the performance for image transport
- realsense-ros issue: Zero-copy point cloud subscriber in ROS2
欢迎在本库提交issues。
在ros2的使用表明,当传输数据量大于64k时,零拷贝可以提供显著的性能提升。
关于零拷贝的概念请参考APEX的PPT Using_Zero_Copy_In_ROS2.pdf
简单讲,零拷贝机制需要自顶向下所有软件层的支持
对于CycloneDDS,参考doc from cyclonedds和doc from rmw_cyclonedds
对于FastDDS,参考doc from fastdds and doc from rmw_cyclonedds
当没有固定大小数据类型时,IPC需要序列化和反序列化操作,所以数据拷贝不可避免
但是与传统dds基于Loopback的网络通信(比如udp 组播)相比,数据拷贝的次数依然有减少。
所以在最少拷贝的传输方式下,性能依然能够得到提升。
大陆集团的中间件 eCAL 使用了iceoryx制作了零拷贝数据传输通道,不过需要从源代码编译,增加额外的编译选项。
性能请参考 The performance of eCAL, 编译方式和选项请看 Enable ECAL_LAYER_ICEORYX
eCAL 也提供了自己的基于共享内存的传输通道,虽然不能得到零拷贝,但是可以实现最少拷贝,其性能可以查看this issue
Cyclonedds和eCAL都使用iceoryx作为零拷贝的传输通道
Iceoryx同样可以提供rmw的接口,查看rmw_iceoryx
FastDDS在v2.2后提供了zero copy功能,所以在rmw_fastrtps的支持下,在ros2-galactic中也能使用loaned-api.
Iceoryx Apex.AI CycloneDDS eCAL
todo.
关于分布式系统的性能请阅读 理论基础