< >
Home » ROS2与C++入门教程 » ROS2与C++入门教程-进程内(intra_process)话题发布和订阅演示

ROS2与C++入门教程-进程内(intra_process)话题发布和订阅演示

ROS2与C++入门教程-进程内(intra_process)话题发布和订阅演示

说明:

  • 介绍ros2下实现进程内(intra_process)话题发布和订阅
  • 在同一进程内的不同节点,可以通过共享指针方式实现内容读取,减少消息的拷贝开销
  • 对于图像之类数据量比较大的节点间处理的效率和性能将大大提高

步骤:

  • 新建一个包cpp_intra_process_topic
cd ~/dev_ws/src
ros2 pkg create --build-type ament_cmake cpp_intra_process_topic
  • 进入src目录,新建文件two_node_pipeline.cpp
cd ~/dev_ws/src/cpp_intra_process_topic/src
touch two_node_pipeline.cpp
  • 内容如下:
#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;
}
  • 编译package.xml
  • 在<buildtool_depend>ament_cmake</buildtool_depend>后增加
<build_depend>rclcpp</build_depend>
<build_depend>std_msgs</build_depend>
  • 编译CMakelist.txt
  • 在find_package(ament_cmake REQUIRED)后增加
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
  • 生成执行文件
include_directories(include)

add_executable(two_node_pipeline 
  src/two_node_pipeline.cpp)
target_link_libraries(two_node_pipeline
  rclcpp::rclcpp
  ${std_msgs_TARGETS})
  • 安装相关库文件和执行文件
install(TARGETS
  two_node_pipeline
  DESTINATION lib/${PROJECT_NAME})
  • 编译包
colcon build --symlink-install --packages-select cpp_intra_process_topic
  • 加载工作空间
. install/setup.bash
  • 测试: 
ros2 run cpp_intra_process_topic two_node_pipeline
  • 效果如下: 
$ ros2 run cpp_intra_process_topic two_node_pipeline
Published message with value: 0, and address: 0x55AD15216420
 Received message with value: 0, and address: 0x55AD15216420
Published message with value: 1, and address: 0x55AD15216420
 Received message with value: 1, and address: 0x55AD15216420
Published message with value: 2, and address: 0x55AD15216420
 Received message with value: 2, and address: 0x55AD15216420
Published message with value: 3, and address: 0x55AD15216420
 Received message with value: 3, and address: 0x55AD15216420

参考:

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ROS2与C++入门教程