引言
这篇文章讲解我们自己按需定义消息。

ROS系列文章

ROS 消息文件
消息文件的扩展名是.msg,我们可以在这个消息文件中自定义需要的消息格式。

这其实是很好理解的,就绪C语言一样有各种结构体,各种类型的数据,消息也是一样的,ROS自带了一系列的消息, 如std_msgs(标准数据类型) 、 geometry_msgs(几何学数据类型) 、sensor_msgs(传感器数据类型) 等,这么多的数据类型可以满足绝大多数场景下的应用,不过ROS也可以用户自定义消息,消息的类型是与语言无关的,无论你是用C++也好还是Python也好,都一样可以使用消息文件。msg文件一般放置在功能包目录下的msg文件夹中。 在编译的时候ROS会根据编译规则生成不同的代码文件,当然,这会依赖于其他功能包,比如message_generation、message_runtime。

message_generation功能包是用于生成C++或Python能使用的代码。

message_runtime则是提供运行时的支持。

消息类型与C++或者Python的数据类型对应关系如下表:

自定义消息

  1. 在功能包中新建一个文件夹,名字为msg,这很重要,若非特别想要,尽量不要修改这个文件夹的名字。

  2. 在msg文件夹其中新建一个名为topic_msg.msg消息类型文件。

  3. 然后在这个消息文件写入以下测试内容:

bool bool_msg
int8 int8_msg
uint8 uint8_msg
int16 int16_msg
uint16 uint16_msg
int32 int32_msg
uint32 uint32_msg
int64 int64_msg
uint64 uint64_msg
float32 float32_msg
float64 float64_msg
string string_msg
time time_msg
duration duration_msg

ps:消息是可以嵌套的,比如你可以使用ROS中的消息类型,具体的可以参考官方wiki。

http://wiki.ros.org/std_msgs

http://wiki.ros.org/common_msgs

添加源码文件
在功能包的src文件夹下随便建立两个文件,主要是为了能编译通过,名字分别为publisher_topic002.cpp、subscriber_topic002.cpp,先在里面随便写个main函数就行了。

#include <cstdlib>
#include "ros/ros.h"
#include <iostream>
#include <string>
#include <cstring>

int main(void)
{
    return 0;
}

添加依赖

关于创建功能包与工作空间这些,就看我上一篇文章即可。

如果你是新建的功能包,最好通过catkin_create_pkg命令依赖message_generationmessage_runtime这两个功能包,具体命令如下:

catkin_create_pkg my_topic002 roscpp rospy std_msgs message_generation message_runtime

如果你是在已有的功能包中想要自定义消息,则在package.xml文件中添加功能包依赖:

<build_depend>message_generation</build_depend>
<run_depend>message_runtime</run_depend>

修改编译规则
CMakeLists.txt是配置编译规则的文件,具体的CMake语法参考我以前的博客文章。

CMakeLists.txt要修改4-5个地方,根据实际场景修改即可:

首先调用find_package查找依赖的功能包,必须要有的是roscpp、rospy、message_generation、message_runtime,而在消息文件中嵌套了其他的消息,则需要依赖其他的功能包。
有时候你会发现,即使你没有调用find_package,你也可以编译通过。这是因为catkin把你所有的package都整合在一起,因此,如果其他的package调用了find_package,你的package的依赖就会是同样的配置。但是,在你单独编译时,忘记调用find_package会很容易出错。

find_package(catkin REQUIRED COMPONENTS
  message_generation
  message_runtime
  roscpp
  rospy
  std_msgs
)

添加消息文件,指定.msg文件。

add_message_files(
  FILES
  topic_msg.msg
)
  1. 指定生成消息文件时的依赖项,其实如果消息文件中有依赖的话,就需要在这里设置,此处假设我依赖了std_msgs(当然我是没有依赖的),就要配置如下:                     
    generate_messages(
      DEPENDENCIES
      std_msgs
    )
    

     

    1. catkin_package声明相关的依赖,一般来通过catkin_create_pkg命令选择了依赖的话,这里是不需要设置的,不过我也给出来我的配置:                                       
      catkin_package(
      #  INCLUDE_DIRS include
      #  LIBRARIES my_topic002
      #  CATKIN_DEPENDS message_generation message_runtime roscpp rospy std_msgs
      #  DEPENDS system_lib
      )
      
    2. 编写编译规则,生成的可执行文件名字、源码、链接库、依赖等内容。
    add_executable(publisher_topic002 src/publisher_topic002.cpp)
    target_link_libraries(publisher_topic002 ${catkin_LIBRARIES})
    add_dependencies(publisher_topic002 ${PROJECT_NAME}_generate_messages_cpp) 
    
    add_executable(subscriber_topic002 src/subscriber_topic002.cpp)
    target_link_libraries(subscriber_topic002 ${catkin_LIBRARIES})
    add_dependencies(subscriber_topic002 ${PROJECT_NAME}_generate_messages_cpp) 
    

     

    尝试编译

    回到工作空间的根目录下,运行catkin_make命令就可以编译了,此时如果不出意外就会出现类似以下的信息表上编译成功:

    ···
    [ 69%] Built target my_topic002_generate_messages_py
    [ 76%] Built target my_topic002_generate_messages_eus
    [ 80%] Built target my_topic002_generate_messages_nodejs
    [ 84%] Built target my_topic002_generate_messages_lisp
    [ 92%] Built target my_topic002_generate_messages
    [ 92%] Built target subscriber_topic002
    [100%] Built target publisher_topic002
    

     

    查看生成的消息源码文件
    在devel的include文件夹中生成一个my_topic002文件夹(具体是叫啥子得根据你自定义的功能包名字生产),里面有topic_msg.h文件(具体是啥名字也是你自定义的消息文件名)。

    它里面有一大串消息的类型,都是我们自定义的,我随意列举一下:

    namespace my_topic002
    {
    template <class ContainerAllocator>
    struct topic_msg_
    {
      typedef topic_msg_<ContainerAllocator> Type;
    
      topic_msg_()
        : bool_msg(false)
        , int8_msg(0)
        , uint8_msg(0)
        , int16_msg(0)
        , uint16_msg(0)
        , int32_msg(0)
        , uint32_msg(0)
        , int64_msg(0)
        , uint64_msg(0)
        , float32_msg(0.0)
        , float64_msg(0.0)
        , string_msg()
        , time_msg()
        , duration_msg()  {
        }
      topic_msg_(const ContainerAllocator& _alloc)
        : bool_msg(false)
        , int8_msg(0)
        , uint8_msg(0)
        , int16_msg(0)
        , uint16_msg(0)
        , int32_msg(0)
        , uint32_msg(0)
        , int64_msg(0)
        , uint64_msg(0)
        , float32_msg(0.0)
        , float64_msg(0.0)
        , string_msg(_alloc)
        , time_msg()
        , duration_msg()  {
        }
        ···
    }
    

     

    使用自定义的消息

    那么使用消息也是非常简单的,我们可以像使用ROS标准消息一样,包含头文件,然后使用即可,比如:

    • 包含头文件
    • #include "my_topic002/topic_msg.h"
      
    • 创建一个Publisher,发布名为my_topic_msg,消息类型为my_topic002::topic_msg,队列长度100:
    • ros::Publisher pub_topic = n.advertise<my_topic002::topic_msg>("my_topic_msg",100);
      
    • 初始化std_msgs::String类型的消息
    •     my_topic002::topic_msg msg;
      
          msg.bool_msg = true;
          msg.string_msg = "hello world!";
          msg.float32_msg = 6.66;
          msg.float64_msg = 666.666;
          msg.int8_msg = -66;
          msg.int16_msg = -666;
          msg.int32_msg = -6666;
          msg.int64_msg = -66666;
          msg.uint8_msg = 66;
          msg.uint16_msg = 666;
          msg.uint32_msg = 6666;
          msg.uint64_msg = 66666;
          msg.time_msg = ros::Time::now();
      

       关于ros::Time
      如果有人注意的话,自定义消息类型中有一个叫time和duration的类型消息,它使用到的是ros本身的一些数据类型,就是时间,关于这个类型的描述可以参考官网wiki:http://wiki.ros.org/roscpp/Overview/Time,它的内部其实是两个变量,与我们linux下的时间是很像的,一个表示秒,一个表示纳秒:

      int32 sec
      int32 nsec
      

       

      同时ros::Time中也包含了很多方法,也重载了很多运算符,大家有兴趣可以自行去研究研究。

      例程源码
      直接将以下源码放到一开始随意添加的两个源码文件publisher_topic002.cpp、subscriber_topic002.cpp中

      publisher_topic002.cpp:

      /*
       * @Author: jiejie
       * @Github: https://github.com/jiejieTop
       * @Date: 2020-04-11 23:16:46
       * @LastEditTime: 2020-04-12 12:17:00
       * @Description: the code belongs to jiejie, please keep the author information and source code according to the license.
       */
      #include <ros/ros.h>
      #include "my_topic002/topic_msg.h"
      #include "std_msgs/String.h"
      
      int main(int argc, char **argv)
      {
      	// ROS节点初始化
      	ros::init(argc, argv, "publisher_topic002");
      
      	// 创建节点句柄
      	ros::NodeHandle n;
      
      	// 创建一个Publisher,发布名为my_topic_msg,消息类型为my_topic002::topic_msg,队列长度100
      	ros::Publisher pub_topic = n.advertise<my_topic002::topic_msg>("my_topic_msg",100);
      
      	// 设置循环的频率
      	ros::Rate loop_rate(1);
      
      	while (ros::ok())
      	{
      	    // 初始化std_msgs::String类型的消息
      		my_topic002::topic_msg msg;
      		msg.bool_msg = true;
      		msg.string_msg = "hello world!";
      		msg.float32_msg = 6.66;
              msg.float64_msg = 666.666;
      		msg.int8_msg = -66;
      		msg.int16_msg = -666;
      		msg.int32_msg = -6666;
              msg.int64_msg = -66666;
              msg.uint8_msg = 66;
              msg.uint16_msg = 666;
              msg.uint32_msg = 6666;
              msg.uint64_msg = 66666;
              msg.time_msg = ros::Time::now();
              
      	    // 发布消息
      		pub_topic.publish(msg);
      
      	    // 按照循环频率延时
      	    loop_rate.sleep();
      	}
      
      	return 0;
      }
      

       

      • subscriber_topic002.cpp:                                                                                                                                                                                                               
        #include <ros/ros.h>
        #include "my_topic002/topic_msg.h"
        #include <std_msgs/String.h>
        
        // 接收到订阅的消息后,会进入消息回调函数
        void test_topic_cb(const my_topic002::topic_msg::ConstPtr & msg)
        {
            // 将接收到的消息打印出来
            ROS_INFO("------------------ msg ---------------------");
            ROS_INFO("bool_msg:    [%d]", msg->bool_msg);
            ROS_INFO("string_msg:  [%s]", msg->string_msg.c_str());
            ROS_INFO("float32_msg: [%f]", msg->float32_msg);
            ROS_INFO("float64_msg: [%f]", msg->float64_msg);
            ROS_INFO("int8_msg:    [%d]", msg->int8_msg);
            ROS_INFO("int16_msg:   [%d]", msg->int16_msg);
            ROS_INFO("int32_msg:   [%d]", msg->int32_msg);
            ROS_INFO("int64_msg:   [%ld]", msg->int64_msg);
            ROS_INFO("uint8_msg:   [%d]", msg->uint8_msg);
            ROS_INFO("uint16_msg:  [%d]", msg->uint16_msg);
            ROS_INFO("uint32_msg:  [%d]", msg->uint32_msg);
            ROS_INFO("uint64_msg:  [%ld]", msg->uint64_msg);
            ROS_INFO("time_msg:    [%d.%d]", msg->time_msg.sec, msg->time_msg.nsec);
        }
        
        int main(int argc, char **argv)
        {
            // 初始化ROS节点
            ros::init(argc, argv, "subscriber_topic002");
        
            // 创建节点句柄
            ros::NodeHandle n;
        
            // 创建一个Subscriber,订阅名为my_topic_msg的消息,注册回调函数test_topic_cb
            ros::Subscriber sub_topic = n.subscribe<my_topic002::topic_msg>("my_topic_msg", 100, test_topic_cb);
        
            // 循环等待回调函数
            ros::spin();
        
            return 0;
        }
        

         

        运行效果

        使用catkin_make重新编译后,运行,效果如下:

      • ros023 

        参考

        《ROS机器人开发实践》 胡春旭 著

        vscode开发ROS(7)-自定义消息