当前位置:网站首页>ROS2节点通信实现零拷贝
ROS2节点通信实现零拷贝
2022-07-26 20:22:00 【首飞爱玩机器人】
下面的一个例子演示了两个节点之间如何实现零拷贝通讯。
注意,下面测试例子的ROS2版本为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;
}
例子中节点的建立有几点需要注意:
- 使能
intra_process
Node(name, rclcpp::NodeOptions().use_intra_process_comms(true))
配置节点时要开启intra_process。
- 发布消息时使用
UniquePtr和std::move(msg)
除了上面例子中的写法,还可以采用下面的写法:
auto dis = std::make_unique<std_msgs::msg::Float32>();
dis->data = 10.0;
pub_->publish(std::move(dis));
- 将需通信的节点加入到同一个进程中
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);
完整的功能代码可通过下面的链接获取:
https://github.com/shoufei403/ros2_galactic_tutorials
相应的代码在demos/intra_process_demo目录。
编译好代码后使用下面的命令启动示例程序
source install/setup.bash
ros2 run intra_process_demo two_node_pipeline
输出结果:
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
可以发现,发送端数据的地址和接收端数据地址是一致的。所以发送端只是把数据存放的地址发送给了接收端并没有发生数据拷贝。
零拷贝的特性对于传输图像数据尤为有用。关于图像传输的例子请参看demos/intra_process_demo目录中的其他例子。
参考:
https://docs.ros.org/en/galactic/Tutorials/Demos/Intra-Process-Communication.html
觉得有用就点赞吧!
我是首飞,一个帮大家填坑的机器人开发攻城狮。
另外在公众号《首飞》内回复“机器人”获取精心推荐的C/C++,Python,Docker,Qt,ROS1/2等机器人行业常用技术资料。
边栏推荐
- After chatting with byte programmers with a monthly salary of 3W, I realized that I had been doing chores
- Discussion on loan agreement mode with NFT as collateral
- Buu brush inscription - WANGDING cup column 2
- 软考 --- 数据库(1)数据库基础
- [pytorch advanced] preservation and use of pytorch model
- How to block the legendary GEE engine version? Close player account tutorial through script + engine
- Leetcode linked list class
- Kotlin - coroutinecontext
- 09_ UE4 advanced_ Enter the next level and reserve the blood volume
- 除了「加机器」,其实你的微服务还能这样优化
猜你喜欢
![[Oracle training] - deploy Ogg known as zero downtime migration](/img/bc/4ee0493129d5abab931ca50dbdce6f.png)
[Oracle training] - deploy Ogg known as zero downtime migration

Today, the company came across an Alibaba P8, which was really seen as the ceiling of the foundation

Use Baidu PaddlePaddle easydl to complete garbage classification

Tinui development history

Leetcode linked list problem -- 24. Exchange the nodes in the linked list in pairs (learn the linked list with one question and one article)

Shell comprehensive application cases, archive files

IT系统为什么需要可观测性?

4年软件测试工作经验,跳槽之后面试20余家公司的总结

今天公司碰到一个阿里p8,算是真正见识到了基础的天花板

Error in render: “TypeError: data.slice is not a function“
随机推荐
What kind of security problems will the server encounter?
微服务化解决文库下载业务问题实践
Today, the company came across an Alibaba P8, which was really seen as the ceiling of the foundation
GOM and GEE lander list file encryption tutorial
Auto. JS rotation Icon
Transaction rollback and record exception information at the same time
Beginner experience of safety testing
How to enter the specified user method body when debugging in idea?
Multivariable time series prediction using LSTM -- problem summary
JVM learning - memory structure - program counter & virtual machine stack & local method stack & heap & method area
GOM登录器配置免费版生成图文教程
Set the template of core configuration file in idea
拦截器、、
Swiftui 4's new function of real-time access to click location.Ontapgeture {location in} (tutorial with source code)
Sign up now: July 29 recommendation system summit 2022
[must read new] Keya valuation analysis of University of technology, heating energy-saving products
和月薪3W的字节程序员聊过后,才知道自己一直在打杂...
如何借助自动化工具落地DevOps|含低代码与DevOps应用实践
[JVM series] JVM tuning
LeetCode链表问题——19.删除链表的倒数第N个节点(一题一文学会链表)