当前位置:网站首页>Ros2 node communication realizes zero copy
Ros2 node communication realizes zero copy
2022-07-26 21:18:00 【Shoufei loves playing with robots】
The following example demonstrates how to realize zero copy communication between two nodes .
Be careful , The following test example ROS2 Version is Galactic.
#include <chrono>
#include <cinttypes>
#include <cstdio>
#include <memory>
#include <string>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/int32.hpp"
using namespace std::chrono_literals;
// Node that produces messages.
struct Producer : public rclcpp::Node
{
Producer(const std::string & name, const std::string & output)
: Node(name, rclcpp::NodeOptions().use_intra_process_comms(true))
{
// Create a publisher on the output topic.
pub_ = this->create_publisher<std_msgs::msg::Int32>(output, 10);
std::weak_ptr<std::remove_pointer<decltype(pub_.get())>::type> captured_pub = pub_;
// Create a timer which publishes on the output topic at ~1Hz.
auto callback = [captured_pub]() -> void {
auto pub_ptr = captured_pub.lock();
if (!pub_ptr) {
return;
}
static int32_t count = 0;
std_msgs::msg::Int32::UniquePtr msg(new std_msgs::msg::Int32());
msg->data = count++;
printf(
"Published message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data,
reinterpret_cast<std::uintptr_t>(msg.get()));
pub_ptr->publish(std::move(msg));
};
timer_ = this->create_wall_timer(1s, callback);
}
rclcpp::Publisher<std_msgs::msg::Int32>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};
// Node that consumes messages.
struct Consumer : public rclcpp::Node
{
Consumer(const std::string & name, const std::string & input)
: Node(name, rclcpp::NodeOptions().use_intra_process_comms(true))
{
// Create a subscription on the input topic which prints on receipt of new messages.
sub_ = this->create_subscription<std_msgs::msg::Int32>(
input,
10,
[](std_msgs::msg::Int32::UniquePtr msg) {
printf(
" Received message with value: %d, and address: 0x%" PRIXPTR "\n", msg->data,
reinterpret_cast<std::uintptr_t>(msg.get()));
});
}
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr sub_;
};
int main(int argc, char * argv[])
{
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor executor;
auto producer = std::make_shared<Producer>("producer", "number");
auto consumer = std::make_shared<Consumer>("consumer", "number");
executor.add_node(producer);
executor.add_node(consumer);
executor.spin();
rclcpp::shutdown();
return 0;
}
There are several points to pay attention to in the establishment of nodes in the example :
- Can make
intra_process
Node(name, rclcpp::NodeOptions().use_intra_process_comms(true))
Enable when configuring nodes intra_process.
- Use when publishing messages
UniquePtrandstd::move(msg)
In addition to the writing in the above example , You can also write in the following way :
auto dis = std::make_unique<std_msgs::msg::Float32>();
dis->data = 10.0;
pub_->publish(std::move(dis));
- Add the nodes that need to communicate to the same process
rclcpp::executors::SingleThreadedExecutor executor;
auto producer = std::make_shared<Producer>("producer", "number");
auto consumer = std::make_shared<Consumer>("consumer", "number");
executor.add_node(producer);
executor.add_node(consumer);
The complete function code can be obtained through the following link :
https://github.com/shoufei403/ros2_galactic_tutorials
The corresponding code is in demos/intra_process_demo Catalog .
After compiling the code, use the following command to start the sample program
source install/setup.bash
ros2 run intra_process_demo two_node_pipeline
Output results :
Published message with value: 0, and address: 0x5625E3159130
Received message with value: 0, and address: 0x5625E3159130
Published message with value: 1, and address: 0x5625E3159130
Received message with value: 1, and address: 0x5625E3159130
Published message with value: 2, and address: 0x5625E3159130
Received message with value: 2, and address: 0x5625E3159130
Published message with value: 3, and address: 0x5625E3159130
Received message with value: 3, and address: 0x5625E3159130
Published message with value: 4, and address: 0x5625E3159130
Received message with value: 4, and address: 0x5625E3159130
Published message with value: 5, and address: 0x5625E3159130
Received message with value: 5, and address: 0x5625E3159130
Published message with value: 6, and address: 0x5625E3159130
Received message with value: 6, and address: 0x5625E3159130
Published message with value: 7, and address: 0x5625E3159130
Received message with value: 7, and address: 0x5625E3159130
Published message with value: 8, and address: 0x5625E3159130
Received message with value: 8, and address: 0x5625E3159130
Published message with value: 9, and address: 0x5625E3159130
Received message with value: 9, and address: 0x5625E3159130
You can find , The address of the sending end data is consistent with that of the receiving end data . Therefore, the sender just sends the address where the data is stored to the receiver, and there is no data copy .
The zero copy feature is particularly useful for transmitting image data . For an example of image transmission, please refer to demos/intra_process_demo Other examples in the catalog .
Reference resources :
https://docs.ros.org/en/galactic/Tutorials/Demos/Intra-Process-Communication.html
If you think it's useful, just praise it !
It's me , One to help everyone Filling pit Robot development siege lion .
In addition, the official account. 《 First flight 》 Internal reply “ robot ” Get carefully recommended C/C++,Python,Docker,Qt,ROS1/2 And other commonly used technical data in the robot industry .
边栏推荐
- 软考 --- 数据库(1)数据库基础
- Pointpillars: fast encoders for object detection from point clouds reading notes
- Is it reliable, reliable and safe to open an account with a low commission for funds in Galaxy Securities
- [Oracle training] - deploy Ogg known as zero downtime migration
- 和月薪3W的字节程序员聊过后,才知道自己一直在打杂...
- 【虚拟机数据恢复】意外断电导致XenServer虚拟机不可用的数据恢复
- Leetcode hash table class
- What is the function of the serializable interface?
- [JVM series] JVM tuning
- Modify excel default code
猜你喜欢

Test cases should never be used casually, recording the thinking caused by the exception of a test case

PointPillars: Fast Encoders for Object Detection from Point Clouds 阅读笔记

Shell comprehensive application cases, archive files

In addition to "adding machines", in fact, your micro service can be optimized like this

idea中设置核心配置文件的模板

我们从Crypto市场中学到的最艰难一课
![[Oracle training] - deploy Ogg known as zero downtime migration](/img/bc/4ee0493129d5abab931ca50dbdce6f.png)
[Oracle training] - deploy Ogg known as zero downtime migration

2022 open atom global open source summit agenda express | list of sub forum agenda on July 27

JDBC的连接

DeepFake捏脸真假难辨,汤姆·克鲁斯比本人还像本人!
随机推荐
Practice of microservice in solving Library Download business problems
ROS2获取当前系统时间的方法
Increased uncertainty in BTC and eth due to the approaching interest rate hike? The US economy will face more pain
GOM login configuration free version generate graphic tutorial
Sign up now: July 29 recommendation system summit 2022
Discussion on loan agreement mode with NFT as collateral
Flutter性能优化实践 —— UI篇
测试用例千万不能随便,记录由一个测试用例异常引起的思考
Today, the company came across an Alibaba P8, which was really seen as the ceiling of the foundation
软考 --- 数据库(1)数据库基础
详细图解b树及C语言实现
Multivariable time series prediction using LSTM -- problem summary
APaaS低代码平台(一) | 把复杂留给自己,把简单留给用户
Rare discounts on Apple's official website, with a discount of 600 yuan for all iphone13 series; Chess robot injured the fingers of chess playing children; Domestic go language lovers launch a new pro
Relevant contents about wireless communication
[MySQL series] - how much do you know about the index
Monitor MySQL based on MySQL exporter
腾讯为什么没能造创造出《原神》这样的游戏
LeetCode_ Backtracking_ Medium_ 40. Combined sum II
[download materials of harmoniyos topics] HDD Hangzhou station · offline salon focuses on application innovation to show the ecological charm of Hongmeng