当前位置:网站首页>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等机器人行业常用技术资料。
边栏推荐
- Discussion on loan agreement mode with NFT as collateral
- GOM login configuration free version generate graphic tutorial
- 【打新必读】工大科雅估值分析,供热节能产品
- idea中debug时如何进入指定的用户方法体中?
- In the era of Web3.0, the technical theory of implementing a DAPP based on P2P DB
- Increased uncertainty in BTC and eth due to the approaching interest rate hike? The US economy will face more pain
- 微服务化解决文库下载业务问题实践
- Deployment of kubernetes
- Buu brush inscription 4
- How to configure the legendary SF lander to automatically read the list without a network
猜你喜欢

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

LeetCode链表问题——19.删除链表的倒数第N个节点(一题一文学会链表)

QT基础第一天 (1)QT,GUI(图形用户接口)开发

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

Pointpillars: fast encoders for object detection from point clouds reading notes

微服务化解决文库下载业务问题实践

"Enterprise management" sincere crm+ - integrated management of enterprise business processes

09_ue4进阶_进入下一关并保留血量

09_ UE4 advanced_ Enter the next level and reserve the blood volume

serializable接口的作用是什么?
随机推荐
JDBC connection
Today, the company came across an Alibaba P8, which was really seen as the ceiling of the foundation
2022 pole technology communication - anmou technology opens a new chapter of commercialization
牛客刷题——Mysql系列
Buu brush inscription - WANGDING cup column 2
微信支付的分账功能介绍
【虚拟机数据恢复】意外断电导致XenServer虚拟机不可用的数据恢复
【Oracle实训】-部署号称零停机迁移的OGG
Kotlin - coroutinebuilder
Leetcode linked list class
[JVM series] JVM tuning
Arm TZ hardware support
Introduction to the billing function of wechat payment
How to configure the legendary SF lander to automatically read the list without a network
Explain the 190 secondary compiler (decoding table) module of SMR laminated hard disk of Western data in detail
IT系统为什么需要可观测性?
Modify excel default code
Svn uses fragmented ideas
GOM登录器配置免费版生成图文教程
JVM learning - memory structure - program counter & virtual machine stack & local method stack & heap & method area