零、Topic机制
1.Publisher向MASTER注册,包含将要发布的Topic名称
2.Subscriber向MASTER注册,包含要订阅的Topic名称
3.ROS MASTER根据Subscriber的订阅要求查找并等待对应的Topic出现,则向Subscriber发送Publisher的RPC地址信息
4.Subscriber向Publisher发起连接请求,传输要订阅的Topic名称、所需的消息类型
5.Publisher向Subscriber确认信息,并发送自我的TCP地址
6.Subscriber接收到确认信息,开始尝试与Publisher的TCP连接
7.Publisher向Subscriber发送话题消息数据
一、发布
1.新建功能包
catkin_create_pkg learning_topic roscpp rospy std_msgs geometry_msgs turtlesim
反馈:
Created file learning_topic/package.xml
Created file learning_topic/CMakeLists.txt
Created folder learning_topic/include/learning_topic
Created folder learning_topic/src
Successfully created files in /home/hermanye/learning_topic.
Please adjust the values in package.xml.
2.新建源码文件
在功能包src文件夹下新建源码文件publisher_example.cpp
touch publisher_example.cpp
3.编写源码
- 初始化ROS节点
- 向ROS Master注册节点信息(话题名、所用的消息类型等)
- 初始化消息数据
- 按设定的频率循环发布
/*
Publish a topic named turtle1/cmd_vel,the type of the message is geometry_msgs::Twist
*/
#include<ros/ros.h>//包含了大量的ROS头文件
#include<geometry_msgs/Twist.h>//包含Twist类型的消息结构头文件
//the main function
int main(int argc,char **argv)
{
//ROS initialize
ros::init(argc,argv,"velocity_publisher");//前两参数为命令行或launch文件输入的参数,可用于重映射等功能
//create NodeHandle
//NodeHandle is used to recognize Nodes for APIs
ros::NodeHandle n;//节点句柄用于使用和管理节点资源
//create a publisher
//the publisher public a topic named /turtle1/cmd_vel
//the type of the message is geometry_msgs::Twist
//length of the message line is 10
ros::Publisher turtle_vel_pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel",10);
//向MASTER注册publisher名为 turtle_vel_pub,告诉系统,消息类型为geometry_msgs::Twist,将要发布的话题名为/turtle1/cmd_vel,队列大小为10
//set rotation speed
ros::Rate loop_rate(10);
//之后调用Rate::sleep()时,ros会根据这里设置的频率来调整休眠时间
int count = 0;
while(ros::ok())
{
//set the content of the message
//initialize message,type of the message is geometry_msgs::Twist
geometry_msgs::Twist vel_msg;//初始化数据结构并进行封装
vel_msg.linear.x=0.5;
vel_msg.angular.z=0.2;
//publish message
turtle_vel_pub.publish(vel_msg);
//print information
ROS_INFO("Publish turtle velocity command[%0.2f m/s,%0.2f rad/s]",vel_msg.linear.x,vel_msg.angular.z);
//delay
loop_rate.sleep();
}
}
4.修改CMakeLists
修改当前功能包所在位置的CMakeLists.txt
在build部分添加如下命令
add_executable用于设置源码和生成的可执行文件
target_link_libraries用于链接库
# add_executable(exename,cpp)
# compile cpp to a executable file named exename
#target_link_libraries(exename ${catkin_LIBRARIES})
# link the file to ROS Libraries
add_executable(velocity_publisher src/velocity_publisher.cpp)
target_link_libraries(velocity_publisher ${
catkin_LIBRARIES})
5.开始编译
在工作空间catkin_ws目录下
catkin_make
6.添加到环境变量
刷新了新文件到环境变量便于后续使用时访问
source /home/hermanye/catkin_ws/devel/setup.bash
一劳永逸的办法:
Ctrl + H解锁隐藏文件显示
打开系统目录下的.bashrc文件
在其中输入
/home/hermanye/catkin_ws对应自己系统下的catkin_ws文件夹目录
source /home/hermanye/catkin_ws/devel/setup.bash
快捷输入到.bashrc的命令:
echo "source /home/hermanye/catkin_ws/devel/setup.bash" >> ~/.bashrc
此时重新打开终端即可自动执行该命令
避免多次重复输入
二、订阅
1.新建源码文件
在功能包src文件夹下新建源码文件pose_subscriber.cpp
touch pose_subscriber.cpp
2.编写源码
- 初始化节点
- 订阅话题
- 循环等待话题消息
- 收到消息后进入回调函数执行对应操作
gedit pose_subscriber.cpp
/*
This is a subscriber for topic named /turtle1/pose
the type of the message is turtlesim::Pose
*/
#include<ros/ros.h>
#include "turtlesim/Pose.h"
//callback function,when the subsciber receive msgs,it will call this function
void poseCallBack(const turtlesim::Pose::ConstPtr& msg)//回调函数部分,当检测到相关Topic发布时,回调函数触发了
{
//print out the info of turtle
ROS_INFO("Turtle Pose: x:%0.3f,y:%0.3f",msg->x,msg->y);
}
int main(int argc,char **argv)
{
//ROS init
ros::init(argc,argv,"pose_subscriber");
//create nodehandle
ros::NodeHandle n;
//create a subscriber,named /turtle1/pose
//register the callback function
//the length of line is 10
ros::Subscriber pose_sub = n.subscribe("/turtle1/pose",10,poseCallBack);
//注册Subscriber,名为pose_sub,接受的Topic名为/turtle1/pose",缓冲队列长度10,触发回调函数poseCallBack
//waiting for the interrupt function trigger
ros::spin();
//建议每个节点都加,用于处理所有的回调函数
return 0;
}
4.修改CMakeLists
修改当前功能包所在位置的CMakeLists.txt
在build部分添加如下命令
# add_executable(exename,cpp)
# compile cpp to a executable file named exename
# target_link_libraries(exename ${catkin_LIBRARIES})
# link the file to ROS Libraries
add_executable(pose_subscriber src/pose_subscriber.cpp)
target_link_libraries(pose_subscriber ${
catkin_LIBRARIES})
5.编译
三、话题消息的定义与使用
消息类型元功能包common_mesgs下有许多不同的消息类型
标准数据类型std_msgs 几何学数据类型geometry_msgs 传感器数据类型sensor_msgs
也可以自定义消息类型
1.定义消息
在功能包目录下建立msg文件夹用于存放.msg文件
Person.msg源码
编译后生成Person消息类型
string name
uint8 sex
uint8 age
uint8 unknown = 0
uint8 male = 1
uint8 female =2
2.修改package.xml文件
动态编译生成msg的功能包依赖
运行依赖runtime功能包
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
3.修改CMakeLists.txt文件
1.在此处
################################################
## Declare ROS messages, services and actions ##
################################################
添加
add_message_files(FILES Person.msg)
generate_messages(DEPENDENCIES std_msgs)
将Person定义成消息接口
以及添加编译时所需要的依赖包
2.在此处
###################################
## catkin specific configuration ##
###################################
修改catkin_package为
去掉了#,添加了message_runtime的catkin包编译依赖
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES learning_topic
CATKIN_DEPENDS geometry_msgs roscpp rospy std_msgs turtlesim message_runtime
# DEPENDS system_lib
)
4.编写pub和sub的源码
发布者:
/*
Publish a topic named /person_info,the type of the message is learning_topic::Person
*/
#include<ros/ros.h>
#include<learning_topic/Person.h>
//the main function
int main(int argc,char **argv)
{
//ROS initialize
ros::init(argc,argv,"person_publisher");
//create NodeHandle
//NodeHandle is used to recognize Nodes for APIs
ros::NodeHandle n;
//create a publisher
//the publisher public a topic named /person_info
//the type of the message is learning_topic::Person
//length of the message line is 10
ros::Publisher person_info_pub = n.advertise<learning_topic::Person>("/person_info",10);
//set rotation speed
ros::Rate loop_rate(10);
int count = 0;
while(ros::ok())
{
//set the content of the message
//initialize message,type of the message is learning_topic::Person
learning_topic::Person person_msg;
person_msg.name="Herman";
person_msg.age = 66;
person_msg.sex = learning_topic::Person::male;
//publish message
person_info_pub.publish(person_msg);
//print information
//c_str()is used to trans person_msg.name into string type in c
ROS_INFO("Publishing Person Info:\nname:%s age:%d sex:%d",person_msg.name.c_str(),person_msg.age,person_msg.sex);
//delay
loop_rate.sleep();
}
}
订阅者:
/*
This is a subscriber for topic named /person_info
the type of the message is learning_topic::Person
*/
#include<ros/ros.h>
#include "learning_topic/Person.h"
//callback function,when the subsciber receive msgs,it will call this function
void PersonInfoCallBack(const learning_topic::Person::ConstPtr& msg)
{
//print out the info of person
ROS_INFO("Person_INFO:\nname:%s age:%d sex:%d",msg->name.c_str(),msg->age,msg->sex);
}
int main(int argc,char **argv)
{
//ROS init
ros::init(argc,argv,"person_subscriber");
//create nodehandle
ros::NodeHandle n;
//create a subscriber,named person_subscriber
//subscribe the topic:/person_info
//register the callback function
//the length of line is 10
ros::Subscriber person_info_sub = n.subscribe("/person_info",10,PersonInfoCallBack);
//waiting for the interrupt function trigger
ros::spin();
return 0;
}
值得注意的是此处string需特殊声明为.c_str() 否则无法识别会产生乱码
5.继续修改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_publisher ${
PROJECT_NAME}_generate_messages_cpp)
此处添加message的依赖
add_dependencies(person_publisher ${PROJECT_NAME}_generate_messages_cpp)
具体作用暂不明
6.编译、运行
rosmsg show Person
查看Person消息类型