ROS study notes 7 (the definition and use of topic messages)

Topic model

The picture below is from Gu Yue's "Introduction to ROS 21 Lectures"
Insert picture description here

The topic messages used in the above two sections are all defined in ROS. This time we will customize a new message type for topic communication. ROS Master manages two nodes, subscribers and publishers. We create a new learning_topic::Person type message and communicate between the two nodes through topic/person_info.

Custom topic message

Define msg file

Person.msg

string name
uint8 sex
uint8 age

uint8 unknown = 0
uint8 male = 1
uint8 female = 2

msg is language-independent and will be dynamically converted to the corresponding data type when compiling, so compile options need to be added.

Add compilation options in CMakeLists.txt

find_package(... message_generation)
add_message_files(FILES Person.msg)
generate_messages(DEPENDENCIES std_msgs)
catkin_package(...cmessage_runtime)

Add function package dependency in package.xml

<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>

Compile and run dependencies

Compile and generate language-related files

Create Publisher Code (C++)

/**
 * 该例程将发布/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;
}

Create subscriber code (C++)

/**
 * 该例程将订阅/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:%d  sex:%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;
}

Configure code compilation rules

  • Set the code to be compiled and the executable file generated
  • Set up the link library
  • Add dependencies
add_executable(person_publisher src/person_publisher.cpp)
target_link_libraries(person_publisher ${catkin_LIBRARIES})
add_dependencies(person_publisher ${PROJECT_NAME}_generate_messages_cpp)

add_executable(person_subscriber src/person_subscriber.cpp)
target_link_libraries(person_subscriber ${catkin_LIBRARIES})
add_dependencies(person_subscriber ${PROJECT_NAME}_generate_messages_cpp)

Compile and run publishers and subscribers

$ cd~/catkin_ws
$ catkin_make
$ source devel/setup.bash
$ roscore
$ rosrun learning_topic person_publisher
$ rosrun learning_topic person_subscriber

The result is as follows.
Insert picture description hereAt this time, roscore is closed, and communication can continue normally because the two have established a link.

Publisher and subscriber code implementation (Python)

announcer

#!/usr/bin/env python
# -*- coding: utf-8 -*-
# 该例程将发布/person_info话题,自定义消息类型learning_topic::Person

import rospy
from learning_topic.msg import Person

def velocity_publisher():
	# ROS节点初始化
    rospy.init_node('person_publisher', anonymous=True)

	# 创建一个Publisher,发布名为/person_info的topic,消息类型为learning_topic::Person,队列长度10
    person_info_pub = rospy.Publisher('/person_info', Person, queue_size=10)

	#设置循环的频率
    rate = rospy.Rate(10) 

    while not rospy.is_shutdown():
		# 初始化learning_topic::Person类型的消息
    	person_msg = Person()
    	person_msg.name = "Tom";
    	person_msg.age  = 18;
    	person_msg.sex  = Person.male;

		# 发布消息
        person_info_pub.publish(person_msg)
    	rospy.loginfo("Publsh person message[%s, %d, %d]", 
				person_msg.name, person_msg.age, person_msg.sex)

		# 按照循环频率延时
        rate.sleep()

if __name__ == '__main__':
    try:
        velocity_publisher()
    except rospy.ROSInterruptException:
        pass

subscriber

#!/usr/bin/env python
# -*- coding: utf-8 -*-
# 该例程将订阅/person_info话题,自定义消息类型learning_topic::Person

import rospy
from learning_topic.msg import Person

def personInfoCallback(msg):
    rospy.loginfo("Subcribe Person Info: name:%s  age:%d  sex:%d", 
			 msg.name, msg.age, msg.sex)

def person_subscriber():
	# ROS节点初始化
    rospy.init_node('person_subscriber', anonymous=True)

	# 创建一个Subscriber,订阅名为/person_info的topic,注册回调函数personInfoCallback
    rospy.Subscriber("/person_info", Person, personInfoCallback)

	# 循环等待回调函数
    rospy.spin()

if __name__ == '__main__':
    person_subscriber()

Part of the code in this article comes from Gu Yue "21 Lectures on ROS Introduction"

Previous link

ROS study notes 6 (programming implementation of subscribers)
ROS study notes 5 (programming implementation of publishers)
ROS study notes 4 (creating workspaces and functional packages)
ROS study notes 3 (use of ROS command line tools)
ROS study Notes 2 (Core Concepts of ROS )
ROS Study Notes 1 (Basic Operation of Linux System)

Guess you like

Origin blog.csdn.net/weixin_44911075/article/details/114212952