5.5.1 Using "zero-copy"
Feature Background
Communication is a fundamental capability in robotic development engines. Native ROS2 Foxy exhibits issues such as high latency and elevated system load when handling large-volume data communication. TogetheROS.Bot Foxy implements the "zero-copy" feature based on the RDK system software library hbmem, enabling zero-copy data transmission across processes. This significantly reduces transmission latency and system resource consumption for large data blocks. This section describes how to use tros.b Foxy and Humble to create publisher and subscriber nodes for large data transmission and measure the transmission latency.
- The tros.b Foxy version adds the "zero-copy" feature on top of ROS2 Foxy.
- The tros.b Humble version leverages the native "zero-copy" functionality provided by ROS2 Humble. For specific usage instructions, please refer to the official ROS2 documentation and code example.
Prerequisites
You have successfully installed tros.b following the Installation Guide, and you are already familiar with basic ROS2 concepts such as nodes, topics, QoS policies, as well as how to create packages and use custom messages. Detailed tutorials can be found in the official ROS2 documentation.
You also need ROS2 package building and compilation tools. Install them using the command: sudo apt install ros-dev-tools
Task Steps
1. Create a Package
Open a new terminal, source the tros.b setup script to ensure the ros2 command is available.
- Foxy
- Humble
source /opt/tros/setup.bash
source /opt/tros/humble/setup.bash
Use the following commands to create a workspace. For more details, refer to the ROS2 official tutorial on 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 a Custom Message
2.1 Create a Message File
Run the following commands to create a msg directory for storing your custom message file:
cd ~/dev_ws/src/hbmem_pubsub
mkdir msg
Create a new file named SampleMessage.msg inside the msg directory with the following content:
int32 index
uint64 time_stamp
uint8[4194304] data
uint32 MAX_SIZE=4194304
2.2 Build Dependencies
Navigate back to the ~/dev_ws/src/hbmem_pubsub directory and modify package.xml. Add the following lines 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 the line # find_package(<dependency> REQUIRED) to enable message compilation:
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/SampleMessage.msg"
)
3. Create a Message Publisher Node
3.1 Create the Publisher Node File
Create a new file named publisher_hbmem.cpp in the ~/dev_ws/src/hbmem_pubsub/src directory to implement the publisher node. The code and explanations are as follows:
- Foxy
- Humble
#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) {
// Create a zero-copy publisher on the topic "topic"
publisher_ = this->create_publisher_hbmem<hbmem_pubsub::msg::SampleMessage>(
"topic", rclcpp::SensorDataQoS());
// Set up a timer that calls timer_callback every 40 milliseconds to send messages
timer_ = this->create_wall_timer(
40ms, std::bind(&MinimalHbmemPublisher::timer_callback, this));
}
private:
// Timer callback function
void timer_callback() {
// Borrow a loaned message for publishing
auto loanedMsg = publisher_->borrow_loaned_message();
// Check if the message is valid; borrowing might fail
if (loanedMsg.is_valid()) {
// Access the actual message via reference
auto& msg = loanedMsg.get();
// Get current timestamp in microseconds
auto time_now =
std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now().time_since_epoch()).count();
// Assign values to index and time_stamp fields
msg.index = count_;
msg.time_stamp = time_now;
// Log the message being sent
RCLCPP_INFO(this->get_logger(), "message: %d", msg.index);
publisher_->publish(std::move(loanedMsg));
// Note: loanedMsg is no longer valid after publishing
// Increment the counter
count_++;
} else {
// Failed to borrow a message; skip this cycle
RCLCPP_INFO(this->get_logger(), "Failed to get LoanMessage!");
}
}
// Timer handle
rclcpp::TimerBase::SharedPtr timer_;
// Zero-copy publisher
rclcpp::PublisherHbmem<hbmem_pubsub::msg::SampleMessage>::SharedPtr publisher_;
// Message counter
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) {
// Create publisher_hbmem with topic name "topic"
publisher_ = this->create_publisher<hbmem_pubsub::msg::SampleMessage>(
"topic", rclcpp::SensorDataQoS());
// Timer that invokes timer_callback every 40 milliseconds to send messages
timer_ = this->create_wall_timer(
40ms, std::bind(&MinimalHbmemPublisher ::timer_callback, this));
}
private:
// Timer callback function
void timer_callback() {
// Obtain the message to be sent
auto loanedMsg = publisher_->borrow_loaned_message();
// Check if the message is valid; it might become invalid if message acquisition fails
if (loanedMsg.is_valid()) {
// Get the actual message by reference
auto& msg = loanedMsg.get();
// Get current time in microseconds
auto time_now =
std::chrono::duration_cast<std::chrono::microseconds>(
std::chrono::steady_clock::now().time_since_epoch()).count();
// Assign values to index and time_stamp fields of the message
msg.index = count_;
msg.time_stamp = time_now;
// Print the message being sent
RCLCPP_INFO(this->get_logger(), "message: %d", msg.index);
publisher_->publish(std::move(loanedMsg));
// Note: after publishing, loanedMsg becomes invalid
// Increment counter
count_++;
} else {
// Failed to acquire message; discard this message
RCLCPP_INFO(this->get_logger(), "Failed to get LoanMessage!");
}
}
// Timer
rclcpp::TimerBase::SharedPtr timer_;
// hbmem publisher
rclcpp::Publisher<hbmem_pubsub::msg::SampleMessage>::SharedPtr publisher_;
// Counter
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 the line <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 the 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})