ros2 node 之间的通信方式之 —— Topic通信案例

ros2 node 之间的通信方式之 Topic通信

ROS 2 将复杂系统分解为许多模块化node。Topic是ROS的重要组成部分,充当node交换消息的总线。
请添加图片描述
一个节点可以将数据发布到任意数量的主题,并同时订阅任意数量的主题。

请添加图片描述
Topic是在node之间移动数据的主要方式之一,因此也是在系统的不同部分之间移动数据的主要方式之一。

Topic 通信案例

1、创建工作空间

如果没有创建工作空间,创建工作空间,反之则不用,进入目录src/下

$ mkdir -p ~/devnode_ws/src
$ cd ~/devnode_ws/src

2、创建功能包

$ ros2 pkg create --build-type ament_cmake topic_helloworld_cpp

在这里插入图片描述

3、编写发布者和订阅者代码

进入topic_helloworld_cpp功能包路径下的src文件,新键topic_helloworld_pub.cpp和topic_helloworld_sub.cpp

$ cd topic_helloworld_cpp/src
$ vim topic_helloworld_pub.cpp
$ vim topic_helloworld_sub.cpp

3.1 topic_helloworld_pub.cpp

#include<chrono>
#include<functional>
#include<memory>
#include<string>

#include"rclcpp/rclcpp.hpp"        //ROS2C++接口
#include"std_msgs/msg/string.hpp"  //字符串消息类型

using namespace std::chrono_literals;

class PublisherNode:public rclcpp::Node
{
public:
    PublisherNode():Node("topic_helloword_pub") //构造函数初始化
    {
        //创建发布者对象
        publisher_ = this->create_publisher<std_msgs::msg::String>("chatter",10);
        //创建一个定时器,执行回调函数
        timer_ = this->create_wall_timer(500ms,std::bind(&PublisherNode::timer_callback,this));
    }
private:
    //创建定时器周期执行回调函数
    void timer_callback()
    {
        auto msg = std_msgs::msg::String();//创建一个String类型的对象
        msg.data = "Hello World ROS2";     //添加消息对象中的数据
        //发布Topic信息
        RCLCPP_INFO(this->get_logger(),"Publishing: '%s'" ,msg.data.c_str());
        publisher_->publish(msg);
    }
    rclcpp::TimerBase::SharedPtr timer_;
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
};

int main(int argc,char* argv[])
{
    rclcpp::init(argc,argv);
    rclcpp::spin(std::make_shared<PublisherNode>());
    rclcpp::shutdown();
    return 0;
}

3.2 topic_helloworld_sub.cpp

#include<memory>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"


using std::placeholders::_1;

class SubscriberNode:public rclcpp::Node
{
public:
    SubscriberNode():Node("topic_helloworld_sub")
    {
        subscription_ = this->create_subscription<std_msgs::msg::String>(
            "chatter",10,std::bind(&SubscriberNode::topic_callback,this,_1)
        );
    }
private:
    
    void topic_callback(const std_msgs::msg::String::SharedPtr msg)const
    {
        RCLCPP_INFO(this->get_logger(),"I heard : '%s'",msg->data.c_str());
    }
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_; //订阅者指针
};


int main(int argc,char*argv[])
{
    rclcpp::init(argc,argv);
    rclcpp::spin(std::make_shared<SubscriberNode>());
    rclcpp::shutdown();
    return 0;
}

4、编写CMakeLists.txt

在# find_package( REQUIRED)行后加入

find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)

add_executable(topic_helloworld_pub src/topic_helloworld_pub.cpp)
ament_target_dependencies(topic_helloworld_pub rclcpp std_msgs)

add_executable(topic_helloworld_sub src/topic_helloworld_sub.cpp)
ament_target_dependencies(topic_helloworld_sub rclcpp std_msgs)

install(TARGETS topic_helloworld_pub topic_helloworld_sub DESTINATION lib/${PROJECT_NAME})

在这里插入图片描述

5、编译工作空间下的功能包

$ cd ~/devnode_ws/
$ colcon build

sour

6、运行结果

启动第一个终端运行Topic 发布者node

$ source install/local_setup.bash
$ ros2 run topic_helloworld_cpp  topic_helloworld_pub

在这里插入图片描述

启动第二个终端运行Topic 订阅者node

$ source install/local_setup.bash
$ ros2 run topic_helloworld_cpp  topic_helloworld_sub

在这里插入图片描述

最近更新

  1. TCP协议是安全的吗?

    2024-04-25 08:12:03       18 阅读
  2. 阿里云服务器执行yum,一直下载docker-ce-stable失败

    2024-04-25 08:12:03       19 阅读
  3. 【Python教程】压缩PDF文件大小

    2024-04-25 08:12:03       19 阅读
  4. 通过文章id递归查询所有评论(xml)

    2024-04-25 08:12:03       20 阅读

热门阅读

  1. 双机部署学习

    2024-04-25 08:12:03       11 阅读
  2. 图论基础知识 并查集/例题

    2024-04-25 08:12:03       13 阅读
  3. 树形dp,LeetCode 2385. 感染二叉树需要的总时间

    2024-04-25 08:12:03       12 阅读
  4. 猎聘爬虫(附源码)

    2024-04-25 08:12:03       10 阅读
  5. 06.2_c/c++开源库boost_coroutine2 协程库

    2024-04-25 08:12:03       14 阅读
  6. Debian常用命令

    2024-04-25 08:12:03       15 阅读
  7. 前端算法

    2024-04-25 08:12:03       15 阅读
  8. SpringBoot + Dubbo + zookeeper实现

    2024-04-25 08:12:03       14 阅读