在 ROS 通信协议中,数据载体是一个较为重要组成部分,ROS 中通过 std_msgs 封装了一些原生的数据类型,但这些数据一般只包含一个 data 字段,当传输一些复杂的数据,可以使用自定义的消息类型
- 案例需求:创建自定义消息,该消息包含人的信息:姓名、身高、年龄等并发布使消息被订阅
- 创建自定义msg
功能包下新建msg目录,添加Person.msg
string name
int32 age
float32 height
- 编译配置文件(包括package.xml和CMakeList.txt)
package.xml中添加编译与执行依赖
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
CMakeList.txt中相关配置
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
## 配置 msg 源文件
add_message_files(
FILES
Person.msg
)
# 生成消息时依赖std_msgs
generate_messages(
DEPENDENCIES
std_msgs
)
#执行时依赖
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES demo02_talker_listener
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
# DEPENDS system_lib
)
- 配置完成后ctrl +shift +B编译,会生成一些中间文件(Person.h/_Person.py)
- 话题自定义msg的发布与订阅
4.0 Vscode配置
将前面生成的 head文件路径配置进 c_cpp_properties.json 的 includepath属性;将前面生成的 python 文件路径配置进 settings.json
4.1 C++实现
(1)发布方实现:
#include "ros/ros.h"
#include "plumbing_pub_sub/Person.h"
/*
发布方:发布人的消息
1.包含头文件
2.初始化ROS节点
3.创建节点句柄
4.创建发布者对象
5.编写发布逻辑,发布数据
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ROS_INFO("这是消息的发布方");
//初始化ROS节点
ros::init(argc,argv,"banzhuren");
//创建节点句柄
ros::NodeHandle nh;
//创建发布者对象
ros::Publisher pub = nh.advertise<plumbing_pub_sub::Person>("liaotian",10);
//编写发布逻辑,发布数据
//5.1创建被发布的数据
plumbing_pub_sub::Person person;
person.name = "张三";
person.age = 12;
person.height = 1.73;
//5.2设置发布频率
ros::Rate rate(1);
//5.3 循环发布数据
while(ros::ok()){
//修改数据
person.age +=1;
//核心:数据发布
pub.publish(person);
ROS_INFO("发布的消息:%s,%d,%.2f",person.name.c_str(),person.age,person.height);
//休眠
rate.sleep();
//建议
ros::spinOnce();
}
return 0;
}
(2)订阅方实现:
#include "ros/ros.h"
#include "plumbing_pub_sub/Person.h"
/*
订阅方:订阅消息
1.包含头文件
2.初始化ROS节点
3.创建节点句柄
4.创建订阅者对象
5.处理订阅的数据
6.调用spin()函数
*/
void doPerson(const plumbing_pub_sub::Person::ConstPtr& person){
ROS_INFO("订阅人的信息:%s,%d,%.2f",person->name.c_str(),person->age,person->height);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
ROS_INFO("这是消息的订阅方");
//初始化ROS节点
ros::init(argc,argv,"jiazhang");
//创建节点句柄
ros::NodeHandle nh;
//创建订阅者对象
ros::Subscriber sub = nh.subscribe("liaotian",10,doPerson);
//处理订阅的数据
//调用spin()函数
ros::spin();
return 0;
}
(3)配置CMakeList.txt文件 (略)
(4)执行
4.2 Python实现
(1)发布方实现:
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
import rospy
from plumbing_pub_sub.msg import Person
if __name__ == "__main__":
rospy.init_node("dama")
#创建发布者对象
pub=rospy.Publisher("guangchangwu",Person,queue_size=10)
#组织消息
p = Person()
p.name = "lili"
p.age = 18
p.height = 1.73
#编写发布逻辑并发布数据
rate = rospy.Rate(1)
while not rospy.is_shutdown():
#发布数据
pub.publish(p)
rospy.loginfo("name:%s, age:%d, height:%.2f",p.name,p.age,p.height)
rate.sleep()
(2)订阅方实现:
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
import rospy
from plumbing_pub_sub.msg import Person
def doPerson(p):
rospy.loginfo("发布的数据: %s,%d,%.2f",p.name,p.age,p.height)
if __name__ == "__main__":
#初始化ROS节点
rospy.init_node("daye")
#创建订阅对象
sub=rospy.Subscriber("guangchangwu",Person,doPerson,queue_size=10)
#循环
rospy.spin()
(3)添加可执行权限:
chmod +x *py
ll
(4)编译执行