前面我们已经学习了publisher如何向ros发布消息,subscriber如何从ros接收消息。那publisher和subscriber之间能由什么联系呢?这节课我们来学习publisher向subscriber发送自定义的信息。
定义msg文件
首先在文件夹learning_topic
中新建一个命名为msg
的文件夹,这个文件夹用来存放后续的消息类文件
进入该文件夹下并在该文件夹下打开命令行,使用touch
指令新建Person.msg
文件
打开该文件,输入以下信息后保存
string name
uint8 sex
uint8 age
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
这里写的并不是cpp,也不是python。但他在编译过程中会由ros自动编译成cpp或python
在package.xml中添加功能包依赖
打开文件夹learning_topic
,打开package.xml
。如果你的电脑安装了浏览器,xml
文件可能会由浏览器默认打开,不能编辑。可以在这个目录下打开命令行,可以输入以下指令打开
gedit package.xml
滚动到最下方,在如图所示位置添加以下语句,保存
message_generation
message_runtime
message_generation
功能包
在CMakeLists.txt添加编译选项
打开文件夹learning_topic
,打开CMakeLists.txt
。
- 在最上方的
find_package
中添加message_generation
- 找到
Declare ROS dynamic reconfigure parameters
的位置,在上方添加如下语句
add_message_files(FILES Person.msg)
generate_messages(DEPENDENCIES std_msgs)
- 第一句话,告诉编译器
Person.msg
是我们定义的消息接口 - 第二句话,告诉编译器在编译
Person.msg
文件的时候,需要依赖哪些库/包。这里我们需要依赖std_msgs
,刚刚我们写的如string
、uint8
,就是在std_msgs
中定义的。
- 找到
catkin specific configuration
(即Build
上方),在图示位置添加以下语句(我这里比较特殊,正上方的注释掉的语句与要添加的语句一模一样,这种情况可以不添加新语句而是直接把那句话的注释解除掉)
CATKIN_DEPENDS geometry_msgs roscpp rospy std_msgs turtlesim
做完以上三步,保存退出。
回到工作空间的根目录catkin_ws
下,打开命令行,尝试进行编译。输入指令
catkin_make
编译成功,可以在图示的路径下,找到刚刚编写的Person.msg
文件已经被编译成为Person.h
文件
编写cpp程序
在图示路径下建立两个cpp文件。代码如下
person_publisher.cpp
/**
* 该例程将发布/person_info话题,自定义消息类型learning_topic::Person
*/
#include
//!!!!!关键!!!!!
#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("/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_subscriber.cpp
/**
* 该例程将订阅/person_info话题,自定义消息类型learning_topic::Person
*/
#include
//!!!!!关键!!!!!
#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;
}
cpp文件编写好后,编写图示路径下的CMakeLists.txt
文件,对刚刚编写的内容进行配置。
找到Install
位置的上方,添加以下语句。保存
说明:这里相比之前配置CMakeLists.txt
,多了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)
编译、运行
步骤和之前的完全一样。
- 回到工作空间根目录
catkin_ws
,运行
catkin_make
- 新开一个终端,执行
roscore
- 新开一个终端,执行
rosrun learning_topic person_subscriber
- 新开一个终端,执行
rosrun learning_topic person_publisher
消息发送者publisher和消息接收者subscriber已经构建联系
概念:ROS Master是帮助节点的创建和链接的。节点一旦创建和链接后,就不受ROS Master影响
此时,在执行命令roscore
的终端按ctrl+c
退出roscore(即退出ROS Master),会发现subscriber和publisher还在收发数据。
除非是需要再访问ROS Master介入的参数
python代码实现
在图示路径下建立python文件,代码如下
右键你的python文件,选择properties
,务必确保Allow executing files as program
选项是打钩的
person_publisher.py
#!/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
person_subscriber.py
#!/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()
- 新开一个终端,执行
roscore
- 新开一个终端,执行
rosrun learning_topic person_subscriber.py
- 新开一个终端,执行
rosrun learning_topic person_publisher.py