0%

零拷贝

下面的一个例子演示了两个节点之间如何实现零拷贝通讯。

注意,下面测试例子的ROS2版本为Galactic

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
#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;
}

例子中节点的建立有几点需要注意:

  1. 使能intra_process
1
Node(name, rclcpp::NodeOptions().use_intra_process_comms(true))

配置节点时要开启intra_process

  1. 发布消息时使用UniquePtrstd::move(msg)

除了上面例子中的写法,还可以采用下面的写法:

1
2
3
auto dis = std::make_unique<std_msgs::msg::Float32>();
dis->data = 10.0;
pub_->publish(std::move(dis));
  1. 将需通信的节点加入到同一个进程中
1
2
3
4
5
6
7
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目录。

编译好代码后使用下面的命令启动示例程序

1
2
source install/setup.bash
ros2 run intra_process_demo two_node_pipeline

输出结果:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
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等机器人行业常用技术资料。

公众号