5.5.1 Using "Zero-Copy"
Background
Communication is a fundamental capability of robot development engines. Native ROS2 Foxy has issues such as high latency and high system load when communicating large amounts of data. TogetheROS.Bot Foxy implements "zero-copy" functionality based on the RDK system software library hbmem. Zero-copy cross-process data transfer can significantly reduce latency and system resource usage for large block data transfer. This section describes how to use tros.b Foxy/Humble/Jazzy to create publisher and subscriber nodes for large block data transfer and measure transfer latency.
- tros.b Foxy adds "zero-copy" functionality based on ROS2 Foxy.
- tros.b Humble and later versions use ROS2's "zero-copy" functionality. For usage details, refer to the ROS2 official documentation and code.
- Versions after tros.b Humble use the same approach as the Humble version. Refer to the Humble version example in this section.
Prerequisites
tros.b has been successfully installed as described in APT Installation and Upgrade. You should understand ROS2 node, topic, QoS, and other basics, and know how to create packages and use custom messages. See the ROS2 official documentation for tutorials.
ROS2 package build and compile tools. Install command: sudo apt install ros-dev-tools
Task Content
1. Create Package
Open a new terminal, source the tros.b setup script, and ensure the ros2 command runs.
- Foxy
- Humble
- Jazzy
# Configure tros.b environment
source /opt/tros/setup.bash
# Configure tros.b environment
source /opt/tros/humble/setup.bash
# Configure tros.b environment
source /opt/tros/jazzy/setup.bash
Use the following commands to create a workspace. For details, see the ROS2 official tutorial Creating a workspace.
mkdir -p ~/dev_ws/src
cd ~/dev_ws/src
Run the following command to create a package:
ros2 pkg create --build-type ament_cmake hbmem_pubsub
2. Create Custom Message
2.1 Create Message File
Run the following command to create a msg directory for custom message files:
cd ~/dev_ws/src/hbmem_pubsub
mkdir msg
Create a SampleMessage.msg file in the msg directory with the following content:
int32 index
uint64 time_stamp
uint8[4194304] data
uint32 MAX_SIZE=4194304
2.2 Build Dependencies
Return to the ~/dev_ws/src/hbmem_pubsub directory and modify package.xml. Add the following content below <buildtool_depend>ament_cmake</buildtool_depend>:
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
2.3 Build Script
Modify CMakeLists.txt and add the following content below # find_package(<dependency> REQUIRED) to compile the msg:
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/SampleMessage.msg"
)
3. Create Message Publisher Node
3.1 Create Publisher Node File
Create a publisher_hbmem.cpp file in the ~/dev_ws/src/hbmem_pubsub/src directory to create the publisher node. Code and explanation:
- Foxy
- Humble/Jazzy
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "hbmem_pubsub/msg/sample_message.hpp"
using namespace std::chrono_literals;
class MinimalHbmemPublisher : public rclcpp::Node {
public:
MinimalHbmemPublisher () : Node("minimal_hbmem_publisher"), count_(0) {
// 创建publisher_hbmem,topic为"topic"
publisher_ = this->create_publisher_hbmem<hbmem_pubsub::msg::SampleMessage>(
"topic", rclcpp::SensorDataQoS());
// 定时器,每隔40毫秒调用一次timer_callback进行消息发送
timer_ = this->create_wall_timer(
40ms, std::bind(&MinimalHbmemPublisher ::timer_callback, this));
}
private:
// 定时器回调函数
void timer_callback() {
// 获取要发送的消息
auto loanedMsg = publisher_->borrow_loaned_message();
// 判断消息是否可用,可能出现获取消息失败导致消息不可用的情况
if (loanedMsg.is_valid()) {
// 引用方式获取实际的消息
auto& msg = loanedMsg.get();
// 获取当前时间,单位为us
auto time_now =
std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now().time_since_epoch()).count();
// 对消息的index和time_stamp进行赋值
msg.index = count_;
msg.time_stamp = time_now;
// 打印发送消息
RCLCPP_INFO(this->get_logger(), "message: %d", msg.index);
publisher_->publish(std::move(loanedMsg));
// 注意,发送后,loanedMsg已不可用
// 计数器加一
count_++;
} else {
// 获取消息失败,丢弃该消息
RCLCPP_INFO(this->get_logger(), "Failed to get LoanMessage!");
}
}
// 定时器
rclcpp::TimerBase::SharedPtr timer_;
// hbmem publisher
rclcpp::PublisherHbmem<hbmem_pubsub::msg::SampleMessage>::SharedPtr publisher_;
// 计数器
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalHbmemPublisher>());
rclcpp::shutdown();
return 0;
}
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "hbmem_pubsub/msg/sample_message.hpp"
using namespace std::chrono_literals;
class MinimalHbmemPublisher : public rclcpp::Node {
public:
MinimalHbmemPublisher () : Node("minimal_hbmem_publisher"), count_(0) {
// 创建publisher_hbmem,topic为"topic"
publisher_ = this->create_publisher<hbmem_pubsub::msg::SampleMessage>(
"topic", rclcpp::SensorDataQoS());
// 定时器,每隔40毫秒调用一次timer_callback进行消息发送
timer_ = this->create_wall_timer(
40ms, std::bind(&MinimalHbmemPublisher ::timer_callback, this));
}
private:
// 定时器回调函数
void timer_callback() {
// 获取要发送的消息
auto loanedMsg = publisher_->borrow_loaned_message();
// 判断消息是否可用,可能出现获取消息失败导致消息不可用的情况
if (loanedMsg.is_valid()) {
// 引用方式获取实际的消息
auto& msg = loanedMsg.get();
// 获取当前时间,单位为us
auto time_now =
std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now().time_since_epoch()).count();
// 对消息的index和time_stamp进行赋值
msg.index = count_;
msg.time_stamp = time_now;
// 打印发送消息
RCLCPP_INFO(this->get_logger(), "message: %d", msg.index);
publisher_->publish(std::move(loanedMsg));
// 注意,发送后,loanedMsg已不可用
// 计数器加一
count_++;
} else {
// 获取消息失败,丢弃该消息
RCLCPP_INFO(this->get_logger(), "Failed to get LoanMessage!");
}
}
// 定时器
rclcpp::TimerBase::SharedPtr timer_;
// hbmem publisher
rclcpp::Publisher<hbmem_pubsub::msg::SampleMessage>::SharedPtr publisher_;
// 计数器
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalHbmemPublisher>());
rclcpp::shutdown();
return 0;
}
3.2 Build Dependencies
Return to the ~/dev_ws/src/hbmem_pubsub directory and modify package.xml. Add the rclcpp dependency below <member_of_group>rosidl_interface_packages</member_of_group>:
<depend>rclcpp</depend>
3.3 Build Script
Modify CMakeLists.txt and add the following content below the rosidl_generate_interfaces statement to complete publisher compilation:
find_package(rclcpp REQUIRED)
add_executable(talker src/publisher_hbmem.cpp)
ament_target_dependencies(talker rclcpp)
rosidl_target_interfaces(talker
${PROJECT_NAME} "rosidl_typesupport_cpp")
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
4. Create Message Subscriber Node
4.1 Create Subscriber Node File
Create a subscriber_hbmem.cpp file in the ~/dev_ws/src/hbmem_pubsub/src directory to create the subscriber node. Code and explanation:
- Foxy
- Humble/Jazzy
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "hbmem_pubsub/msg/sample_message.hpp"
class MinimalHbmemSubscriber : public rclcpp::Node {
public:
MinimalHbmemSubscriber () : Node("minimal_hbmem_subscriber") {
// 创建subscription_hbmem,topic为"sample"
// 消息回调函数为topic_callback
subscription_ =
this->create_subscription_hbmem<hbmem_pubsub::msg::SampleMessage>(
"topic", rclcpp::SensorDataQoS(),
std::bind(&MinimalHbmemSubscriber ::topic_callback, this,
std::placeholders::_1));
}
private:
// 消息回调函数
void topic_callback(
const hbmem_pubsub::msg::SampleMessage::SharedPtr msg) const {
// 注意,msg只能在回调函数中使用,回调函数返回后,该消息就会被释放
// 获取当前时间
auto time_now =
std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now().time_since_epoch())
.count();
// 计算延时并打印出来
RCLCPP_INFO(this->get_logger(), "msg %d, time cost %dus", msg->index,
time_now - msg->time_stamp);
}
// hbmem subscription
rclcpp::SubscriptionHbmem<hbmem_pubsub::msg::SampleMessage>::SharedPtr
subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalHbmemSubscriber>());
rclcpp::shutdown();
return 0;
}
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "hbmem_pubsub/msg/sample_message.hpp"
class MinimalHbmemSubscriber : public rclcpp::Node {
public:
MinimalHbmemSubscriber () : Node("minimal_hbmem_subscriber") {
// 创建subscription_hbmem,topic为"sample"
// 消息回调函数为topic_callback
subscription_ =
this->create_subscription<hbmem_pubsub::msg::SampleMessage>(
"topic", rclcpp::SensorDataQoS(),
std::bind(&MinimalHbmemSubscriber ::topic_callback, this,
std::placeholders::_1));
}
private:
// 消息回调函数
void topic_callback(
const hbmem_pubsub::msg::SampleMessage::SharedPtr msg) const {
// 注意,msg只能在回调函数中使用,回调函数返回后,该消息就会被释放
// 获取当前时间
auto time_now =
std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now().time_since_epoch())
.count();
// 计算延时并打印出来
RCLCPP_INFO(this->get_logger(), "msg %d, time cost %dus", msg->index,
time_now - msg->time_stamp);
}
// hbmem subscription
rclcpp::Subscription<hbmem_pubsub::msg::SampleMessage>::SharedPtr
subscription_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalHbmemSubscriber>());
rclcpp::shutdown();
return 0;
}
4.2 Build Script
Return to the ~/dev_ws/src/hbmem_pubsub directory. The rclcpp dependency was already added in package.xml, so no changes to package.xml are needed.
Modify CMakeLists.txt and add the following content below the install statement to complete subscriber compilation:
add_executable(listener src/subscriber_hbmem.cpp)
ament_target_dependencies(listener rclcpp)
rosidl_target_interfaces(listener
${PROJECT_NAME} "rosidl_typesupport_cpp")
install(TARGETS
listener
DESTINATION lib/${PROJECT_NAME})
5. Build
The complete workspace directory structure is as follows:
dev_ws/
└── src
└── hbmem_pubsub
├── CMakeLists.txt
├── include
│ └── hbmem_pubsub
├── msg
│ └── SampleMessage.msg
├── package.xml
└── src
├── publisher_hbmem.cpp
└── subscriber_hbmem.cpp
The complete package.xml content is as follows:
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>hbmem_pubsub</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="root@todo.todo">root</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<depend>rclcpp</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
The complete CMakeLists.txt content is as follows:
cmake_minimum_required(VERSION 3.5)
project(hbmem_pubsub)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/SampleMessage.msg"
)
find_package(rclcpp REQUIRED)
add_executable(talker src/publisher_hbmem.cpp)
ament_target_dependencies(talker rclcpp)
rosidl_target_interfaces(talker
${PROJECT_NAME} "rosidl_typesupport_cpp")
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME})
add_executable(listener src/subscriber_hbmem.cpp)
ament_target_dependencies(listener rclcpp)
rosidl_target_interfaces(listener
${PROJECT_NAME} "rosidl_typesupport_cpp")
install(TARGETS
listener
DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
In the workspace root directory ~/dev_ws, build the package:
colcon build --packages-select hbmem_pubsub
If the colcon command is not installed, install it with:
sudo apt install ros-dev-tools
6. Run
Open a new terminal, cd to the dev_ws directory, and source the tros.b and current workspace setup files:
- Foxy
- Humble
- Jazzy
source /opt/tros/setup.bash
cd ~/dev_ws
. install/setup.bash
# Run talker node:
ros2 run hbmem_pubsub talker
source /opt/tros/humble/setup.bash
cd ~/dev_ws
. install/setup.bash
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export FASTRTPS_DEFAULT_PROFILES_FILE=/opt/tros/humble/lib/hobot_shm/config/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export ROS_DISABLE_LOANED_MESSAGES=0
# Run talker node:
ros2 run hbmem_pubsub talker
source /opt/tros/jazzy/setup.bash
cd ~/dev_ws
. install/setup.bash
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export FASTRTPS_DEFAULT_PROFILES_FILE=/opt/tros/jazzy/lib/hobot_shm/config/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export ROS_DISABLE_LOANED_MESSAGES=0
# Run talker node:
ros2 run hbmem_pubsub talker
The terminal will show output like the following:
[INFO] [1649227473.431381673] [minimal_hbmem_publisher]: message: 0
[INFO] [1649227473.470746697] [minimal_hbmem_publisher]: message: 1
[INFO] [1649227473.510923361] [minimal_hbmem_publisher]: message: 2
[INFO] [1649227473.550886783] [minimal_hbmem_publisher]: message: 3
[INFO] [1649227473.590664377] [minimal_hbmem_publisher]: message: 4
[INFO] [1649227473.630857041] [minimal_hbmem_publisher]: message: 5
Open another new terminal, also cd to the dev_ws directory, source the setup files, then run the listener node:
- Foxy
- Humble
- Jazzy
source /opt/tros/setup.bash
cd ~/dev_ws
. install/setup.bash
ros2 run hbmem_pubsub listener
source /opt/tros/humble/setup.bash
cd ~/dev_ws
. install/setup.bash
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export FASTRTPS_DEFAULT_PROFILES_FILE=/opt/tros/humble/lib/hobot_shm/config/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export ROS_DISABLE_LOANED_MESSAGES=0
ros2 run hbmem_pubsub listener
source /opt/tros/jazzy/setup.bash
cd ~/dev_ws
. install/setup.bash
export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
export FASTRTPS_DEFAULT_PROFILES_FILE=/opt/tros/jazzy/lib/hobot_shm/config/shm_fastdds.xml
export RMW_FASTRTPS_USE_QOS_FROM_XML=1
export ROS_DISABLE_LOANED_MESSAGES=0
ros2 run hbmem_pubsub listener
The terminal will show output like the following, indicating the subscriber has successfully received messages from the publisher:
[INFO] [1649227450.387089523] [minimal_hbmem_subscriber]: msg 10, time cost 1663us
[INFO] [1649227450.427071280] [minimal_hbmem_subscriber]: msg 11, time cost 1713us
[INFO] [1649227450.466993413] [minimal_hbmem_subscriber]: msg 12, time cost 1622us
[INFO] [1649227450.507029960] [minimal_hbmem_subscriber]: msg 13, time cost 1666us
[INFO] [1649227450.546146910] [minimal_hbmem_subscriber]: msg 14, time cost 998us
[INFO] [1649227450.587002681] [minimal_hbmem_subscriber]: msg 15, time cost 1768us
Use Ctrl+C to stop each node.
Summary
- Foxy
- Humble/Jazzy
If you already understand how to use ROS2 publishers and subscribers, it is easy to switch to hbmem-based zero-copy publishers and subscribers. You only need to make the following changes:
- Change rclcpp::Publisher to rclcpp::PublisherHbmem
- Change create_publisher to create_publisher_hbmem
- Change rclcpp::Subscription to rclcpp::SubscriptionHbmem
- Change create_subscription to create_subscription_hbmem
- Before sending messages, the publisher must call borrow_loaned_message to obtain a message, then verify the message is available. If available, assign values and send.
- The subscription processes received messages in the callback function, and received messages can only be used within the callback function. After the callback completes, the message is released.
Notes:
-
Using hbmem-based zero-copy consumes ion memory. Creating multiple publishers with large messages may cause insufficient ion memory and creation failures.
-
When creating a publisher, ion memory equal to three times the KEEPLAST message size (up to 256MB) is allocated at once for message transfer and will not be dynamically allocated again. If the subscriber fails to process messages or does not process them in time, all message buffers may be occupied and the publisher may not be able to obtain available messages.
Usage Limitations
Compared to ROS2 publisher/subscriber data transfer, zero-copy transfer has the following limitations:
- QoS History only supports KEEPLAST, not KEEPALL. KEEPLAST cannot be set too large due to memory limits; the current maximum is 256MB.
- The transferred message size is fixed; the message
sizeofvalue does not change. Variable-length data types such as strings and dynamic arrays are not supported. - For TROS Humble and later versions, QoS Reliability is recommended to use
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT(it is recommended to userclcpp::SensorDataQoS()to set QoS).RMW_QOS_POLICY_RELIABILITY_RELIABLEhas stability issues with multiple communication methods. - Can only be used for inter-process communication on the same device; cannot transfer across devices.
- Publisher messages must be obtained before assignment and sending, and success of acquisition must be verified.
- Subscriber received messages are only valid within the callback function and cannot be used outside the callback function.