fou Chinese reader please refer 简体中文
Zero copy can save times of copy in IPC, thus reduces cpu usage and transport latency, which can be used in time-critical systems or resource-constrained computing platforms.
For intra-process context, the zero copy can be achieved with rclcpp intra-process communication, which is avaiable since dashing.
For zero-copy with inter-process-communication in ros2, there's loaned-api provided since ros2-foxy, see ros2_design: Zero Copy via Loaned Messages
This repo is inspired by projects above, with providing unified image and pointcloud2 msg definition, type conversion function, rviz bridge, and demos with performance test, in a scalable way to have a good support to true zero copy transportation in IPC(intra-machine, inter-process) context.
Currently tested in ros2 galactic with the following layers:
the performance of zero copy can be seen in ros2_jetson_benchmarks, which is tested within GitHub - ZhenshengLee/performance_test: Github repo for apex.ai performance_test for more middlewares.
this lib has been used in the custom version of ros2_v4l2_camera and the custom version of rslidar_sdk, and the performance improvement is awesome!
For example, in my pc of dell 3630, the zero-copy transport of a shm_msgs::msg::Image1m can save about 80% of transport time, from 1.4ms to 0.3ms.
this package includes ros2 msg definitions and demos that supports the msgs.
pointcloud and image are currently supported.
feature | Status |
---|---|
pointcloud8k | :heavy_check_mark: |
pointcloud512k | :heavy_check_mark: |
pointcloud1m | :heavy_check_mark: |
pointcloud2m | :heavy_check_mark: |
pointcloud4m | :heavy_check_mark: |
pointcloud8m | :heavy_check_mark: |
image8k | :heavy_check_mark: |
image512k | :heavy_check_mark: |
image1m | :heavy_check_mark: |
image2m | :heavy_check_mark: |
image4m | :heavy_check_mark: |
image8m | :heavy_check_mark: |
open3d_conversions | :heavy_check_mark: |
opencv_conversions | :heavy_check_mark: |
pcl_conversions | :heavy_check_mark: |
shm_image_bridge | :heavy_check_mark: |
shm_open3d_bridge | :heavy_check_mark: |
shm_pcl_bridge | :heavy_check_mark: |
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, to check if there is fastdds shm file being created
# 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
Comments have been given from github and ros2 community.
Feel free to create issues in the repo.
Zero_copy is a transport layer to get a better performance especially when payload size exceeds 64k.
Please refer Using_Zero_Copy_In_ROS2.pdf for more info of concept of z copy.
In short, zero copy needs api support through all software layers.
For CycloneDDS, see doc from cyclonedds and doc from rmw_cyclonedds for details
For FastDDS, see doc from fastdds and doc from rmw_cyclonedds
Without fixed-length msg, a serialization is needed before IPC, so copy can not be avoided.
But time of copy can still be reduced comparing to Loopback Network Communication(such as udp multicast), which is the default transport layer in most cases of dds.
Performance can still be improved with minimum copy.
The eCAL by Continental provides iceoryx transport layer to get true zero copy, but extra cmake based compilation is needed.
refer The performance of eCAL, and Enable ECAL_LAYER_ICEORYX for more details.
eCAL also provides default shm based transport layer to get minimum copy performance, see this issue for details.
Cyclonedds and eCAL both use iceoryx as the z copy transport layer.
Iceoryx alos provide direct access to rmw, see rmw_iceoryx for details.
FastDDS provide zero-copy since v2.2, so with rmw_fastrtps the loaned-api canbe used since ros2-galactic.
todo.