ROS(七)——话题消息的定义与使用

上节课Twist消息和Pose消息都是ROS直接定义好的,我们可以直接拿来使用。

那如果我们在自己的开发当中,这些ROS定义好的消息无法满足我们的要求,这是我们就可以自己来定义消息的类型

本节就来完成消息自定义,并且完成Publisher和Subscriber的使用。

完成一个person个人信息的传输,包括名字、年龄、性别

 

如何自定义话题消息

创建msg文件

msg文件是语言无关的 

在learning_topic目录下创建msg文件夹

 

在msg目录下创建Person.msg文件,完成数据接口的定义

string name
uint8 sex
uint8 age

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

 

根据数据接口定义来设置编译规则

在package.xml中添加功能包依赖

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

打开learning_topic下的package.xml, 在最后添加依赖

 

在CMakeLists.txt添加编译选项

①在find_package中

message_generation

②添加 把.msg文件编译成对应的不同的程序文件的配置项

add_message_files(FILES Person.msg)
generate_messages(DEPENDENCIES std_msgs) #依赖

message_runtime

以前是这样的

现在

 

编译

catkin_make

编译成功以后可以查看一下所编译生成的头文件

 

下面来看如果调用Person.msg生成的这个头文件

创建发布者代码(C++)

在src目录下创建发布者和订阅者代码

person_publisher.cpp

/**
 * 该例程将发布/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.msg中定义的宏

        // 发布消息
		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_subscriber.cpp

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

 

配置代码编译规则

配置CMakeLists.txt中的编译规则

如何配置CMakeLists.txt中的编译规则

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

 

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)

添加到CMakeLists.txt当中

 

下面就可以做编译了

 

编译并运行发布者和订阅者

在catkin_ws目录下

catkin_make

设置环境变量

roscore

rosrun learning_topic person_subscriber

rosrun learning_topic person_publisher

subscriber和publisher谁先运行都可以

ctrl+c即可中断退出

 

此时如果把rosmaster关掉,仍然可以继续运行。因为连接已经建立了,就没rosmaster什么事了

 

Python代码

将代码放到learning_topic的scripts下面, 注意设置为允许作为程序执行文件

person_publisher.py

#!/usr/bin/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

 

person_sunscriber.py

#!/usr/bin/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()

然后直接执行就行了

roscore

rosrun learning_topic person_subscriber.py

rosrun learning_topic person_publisher.py

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值