【ROS学习5(Topic)】话题消息(message)的自定义与使用

话题消息的自定义与使用:

在上几次的学习当中,无论是给小海龟发送速度指令的Twist消息,还是去订阅小海龟的位姿Pose消息,都是ROS里默认定义的,假如这些消息仍无法满足我们的需求,我们就需要自定义一个消息类型。

我们以创建一个个人信息的消息类型为例:
在这里插入图片描述

如何定义话题消息:

➢定义msg文件:(Person.msg)
cd learning_topic
mkdir msg
#用touch命令创建一个空文件
touch Person.msg
#放置在该文件夹下

包含以下内容:

string name
uint8 sex
uint8 age

#类似于宏定义
uint8 unknown = 0
uint8 male = 1
uint8 female = 2

#msg文件里的语法不属于任何一种语言,在编译时会根据不同的语言需求自动扩展成该语言下的表示语法。

➢ 在package.xml中添加功能包依赖:
<build_depend>message_generation</build_depend>

#执行依赖

<exec_depend>message_runtime</exec_depend>

#运行依赖(动态依赖)
在这里插入图片描述

➢在CMakeLists.txt添加编译选项:

#添加依赖包

find_package( ...... message_generation)

#将Person.msg定义为消息接口

add_message_files(FILES Person.msg)

#编译消息接口依赖包

generate_messages(DEPENDENCIES std_msgs)

#创建运行依赖

•catkin_package(...... message_runtime)

在CMakeLists里根据注释找到对应的位置并添加即可。

注意,Ubuntu16.04的catkin_depends应删去catkin_package,否则会报错
在这里插入图片描述

回到工作空间根目录,catkin_make编译:

编译完成后会在devel里生成Person.h头文件

其中learning_topic类:
在这里插入图片描述

创建发布者:

/**
 * 该例程将发布/person_info话题,自定义消息类型learning_topic::Person
 */

#include <ros/ros.h>
#include"learning_topic/Person.h"

int main(int argc, char **argv)
{
    
       
    // ROS节点初始化   
    ros::init(argc, argv, "person_publisher");  
    
    // 创建节点句柄
    ros::NodeHandle n;
    
    // 创建一个Publisher,发布名为/person_info的topic,消息类型为learning_topic::Person,队列长度10
    ros::Publisher person_info_pub = n.advertise<learning_topic::Person>("/person_info",10);
 
    // 设置循环的频率  
    ros::Rate loop_rate(1);
    int count = 0; 
    while (ros::ok())
    {
    
        
        // 初始化learning_topic::Person类型的消息
        learning_topic::Person person_msg;
        person_msg.name= "Tom";
        person_msg.age  = 18;
        person_msg.sex  = learning_topic::Person::male;
      
       // 发布消息
       person_info_pub.publish(person_msg);
       ROS_INFO("Publish Person
       Info: name:%s  age:%d  sex:%d", person_msg.name.c_str(),person_msg.age,person_msg.sex);
      
       // 按照循环频率延时       
       loop_rate.sleep();
    }
return 0;
}

创建一个订阅者:

/**
 * 该例程将订阅/person_info话题,自定义消息类型learning_topic::Person
 */

#include <ros/ros.h>
#include"learning_topic/Person.h"
 
// 接收到订阅的消息后,会进入消息回调函数
void personInfoCallback(const
learning_topic::Person::ConstPtr& msg)
{
    
      
    // 将接收到的消息打印出来
    ROS_INFO("Subcribe Person Info: name:%s  age:%dsex:%d", msg->name.c_str(), msg->age,msg->sex);
}
 
int main(int argc, char **argv)
{
    
    
    // 初始化ROS节点
    ros::init(argc, argv, "person_subscriber");

    // 创建节点句柄
    ros::NodeHandle n;
    
    // 创建一个Subscriber,订阅名为/person_info的topic,注册回调函数personInfoCallback
    ros::Subscriber person_info_sub = n.subscribe("/person_info",10, personInfoCallback);

    // 循环等待回调函数  
    ros::spin();
    return 0;
}

learning_topic配置CMakelists:
• 设置需要编译的代码和生成的可执行文件;
• 设置链接库;
• 添加依赖项

add_executable(person_publishersrc/person_publisher.cpp)
target_link_libraries(person_publisher${catkin_LIBRARIES})
add_dependencies(person_publisher${PROJECT_NAME_generate_messages_cpp)

add_executable(person_subscribersrc/person_subscriber.cpp)
target_link_libraries(person_subscriber${catkin_LIBRARIES})
add_dependencies(person_subscriber${PROJECT_NAME_generate_messages_cpp)

#其中add_dependencies使可执行程序和动态生成的程序产生依赖。

编译运行:

roscore
rosrun learning_topic person_subscriber
rosrun learning_topic person_publisher

在这里插入图片描述在这里插入图片描述

这时候如果关闭ros_master并不会影响话题的发布和接收,
这是由于ros_master只作为最初节点之间建立连接的一个媒介,
而如果要新加入一个节点,ros_master就必须存在。

查看计算图:
在这里插入图片描述

Guess you like

Origin blog.csdn.net/SESESssss/article/details/105362365