对ROS2有一定了解后,我们会发现ROS2中节点和ROS1中节点的概率有很大的区别。在ROS1中节点是最小的进程单元。在ROS2中节点与进程和线程的概念完全区分开了。具体区别可以参考 ROS2学习(四)进程,线程与节点的关系。
在ROS2中同一个进程中可能存在多个节点。两个节点直接交换数据依旧使用典型的topic发布订阅,则听起来像在一个房间的两个人,需要通过邮寄快递来交换物品一样。所以,ROS2中,设计了一种进程内通信的更好的方式。即intra processing.这个选项位于节点的选项中,即Node-Option,
- 使用进程内通信(use_intra_process_comms):类型是bool.如果为true,则在此上下文中发布和订阅的主题消息通过特殊的进程内通信代码路径。可以避免序列化和反序列化,不必要的复制。并在某些情况下实现更低的延迟。该选项默认值为false。
在构造节点时添加“使用进程内通信”选项,即可启用该功能。如下
Node(node_name, rclcpp::NodeOptions().use_intra_process_comms(true));
下面的例子是在一个进程中创建两个节点,都是用intra_process,包括一个发布器的节点,和一个订阅器的节点,二者都使用了节点的进程内通信,并通过unique指针打印了其中地址。每次通信的时候,二者消息指针的地址都是一致的,即消息没有通过UDP传输,而是通过直接读写内存区块传输的。
#include <cstdio>
#include <memory>
#include <string>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include <chrono>
class PubNode : public rclcpp::Node
{
public:
explicit PubNode(const std::string& node_name):
Node(node_name, rclcpp::NodeOptions().use_intra_process_comms(true))
{
using namespace std::chrono_literals;
publisher_ = this->create_publisher<builtin_interfaces::msg::Time>(
"current_time",
10
);
auto topictimer_callback =
[&]()->void {
builtin_interfaces::msg::Time::UniquePtr timestamp_ =
std::make_unique<builtin_interfaces::msg::Time>(this->get_clock()->now());
RCLCPP_INFO_STREAM(this->get_logger(), "pub:Addr is:" << reinterpret_cast<std::uintptr_t>(timestamp_.get()));
publisher_->publish(std::move(timestamp_));
};
timer_ = this->create_wall_timer(std::chrono::milliseconds(500), topictimer_callback);
}
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<builtin_interfaces::msg::Time>::SharedPtr publisher_;
};
class SubNode : public rclcpp::Node
{
public:
explicit SubNode(const std::string & node_name):
Node(node_name, rclcpp::NodeOptions().use_intra_process_comms(true))
{
subscriber_ = this->create_subscription<builtin_interfaces::msg::Time>(
"current_time",
10,
std::bind(&SubNode::count_sub_callback, this, std::placeholders::_1));
}
private:
rclcpp::Subscription<builtin_interfaces::msg::Time>::SharedPtr subscriber_;
void count_sub_callback(const builtin_interfaces::msg::Time::UniquePtr msg)
{
RCLCPP_INFO_STREAM(this->get_logger(), "sub::Addr is: " <<
reinterpret_cast<std::uintptr_t>(msg.get()));
}
};
void another_executor()
{
rclcpp::executors::SingleThreadedExecutor executor_;
auto sub_node_ = std::make_shared<SubNode>("topic_sub");
executor_.add_node(sub_node_);
executor_.spin();
}
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto pub_node_ = std::make_shared<PubNode>("topic_pub");
rclcpp::executors::SingleThreadedExecutor executor_;
std::thread another(another_executor);
executor_.add_node(pub_node_);
executor_.spin();
another.join();
rclcpp::shutdown();
return 0;
}
测试进程内通信:
crabe@crabe-virtual-machine:~/Desktop/ROS2_Sample/sample4$ ros2 run sample4 sample4
[INFO] [1691321973.618474226] [topic_pub]: pub:Addr is:94612283905568
[INFO] [1691321973.619805241] [topic_sub]: sub::Addr is: 94612283905568
[INFO] [1691321974.111633655] [topic_pub]: pub:Addr is:94612283906592
[INFO] [1691321974.112431228] [topic_sub]: sub::Addr is: 94612283906592
[INFO] [1691321974.621381952] [topic_pub]: pub:Addr is:94612283906752
[INFO] [1691321974.622338223] [topic_sub]: sub::Addr is: 94612283906752
[INFO] [1691321975.116415866] [topic_pub]: pub:Addr is:94612283906592
[INFO] [1691321975.117153538] [topic_sub]: sub::Addr is: 94612283906592
[INFO] [1691321975.626275913] [topic_pub]: pub:Addr is:94612283906752
[INFO] [1691321975.627212976] [topic_sub]: sub::Addr is: 94612283906752
[INFO] [1691321976.119609316] [topic_pub]: pub:Addr is:94612283906592
[INFO] [1691321976.119766941] [topic_sub]: sub::Addr is: 94612283906592
[INFO] [1691321976.612854241] [topic_pub]: pub:Addr is:94612283906752
[INFO] [1691321976.612988887] [topic_sub]: sub::Addr is: 94612283906752
[INFO] [1691321977.121834835] [topic_pub]: pub:Addr is:94612283906592
[INFO] [1691321977.122012812] [topic_sub]: sub::Addr is: 94612283906592
[INFO] [1691321977.615035889] [topic_pub]: pub:Addr is:94612283906752
[INFO] [1691321977.615166100] [topic_sub]: sub::Addr is: 94612283906752
[INFO] [1691321978.123765480] [topic_pub]: pub:Addr is:94612283906592
[INFO] [1691321978.123915765] [topic_sub]: sub::Addr is: 94612283906592
[INFO] [1691321978.615940232] [topic_pub]: pub:Addr is:94612283906752
[INFO] [1691321978.616072038] [topic_sub]: sub::Addr is: 94612283906752
intra_process与节点执行器无直接关系,仅与是否为同一进程有关。
使用intra_process的节点,其中的topic可以同时支持进程内和进程外的通信,只不过进程外的通信仍然使用UDP作为媒介。如果需要在进程外也使用共享内存的高效方案,则需要考虑在DDS的中间件上下功夫。