需求
实现所用编程语言: C++
发布方:
- 节点名称:talker
- 发出文本信息以及序列号
- 节点发布频率:1Hz
- 输出发布日志信息
订阅方:
- 节点名称:listener
- 监听发布方talker的信息
- 输出监听到的信息
- 持续监听
实现过程
创建发布与订阅ros包
- 打开终端,转移到ros工作空间下,执行文件包创建
cd src
catkin_create_pkg pub_sub roscpp rospy std_msgs
创建发布方
- 在生成的pub_sub包下的src文件夹中,新建文件talker.cpp文件,编写发布代码如下:
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <sstream> // 字符与数字拼接为字符串的库
int main(int argc, char *argv[])
{
// 设置中文编码
setlocale(LC_ALL, "");
// 初始化 ROS 节点
ros::init(argc, argv, "talker_node");
// 创建节点句柄
ros::NodeHandle nh;
// 创建发布这对象
ros::Publisher pub = nh.advertise<std_msgs::String>("talker", 10);
// 创建发布的消息
std_msgs::String msg;
// 编写循环,循环发布数据
ros::Rate r(1); // 发布评率为1Hz
int count = 0; // 用于记录发布序号
while (ros::ok())
{
count++;
// 使用string stream进行文字与数字拼接
std::stringstream ss;
ss << "Can you here me? Pub time: " << count;
msg.data = ss.str();
pub.publish(msg);
// 添加发布日志信息
ROS_INFO("已发布数据 %d 次", count);
r.sleep();
// ros::spinOnce(); // 当前文件无回调函数,可不写
}
return 0;
}
- 修改CMakeLists.txt文件,添加对talker.cpp的编译,以及编译生成的可执行文件的链接,具体修改内容如下:
add_executable(talker_node src/talker.cpp)
target_link_libraries(talker_node
${catkin_LIBRARIES}
)
创建订阅方
- 在生成的pub_sub包下的src文件夹中,新建文件listener.cpp文件,编写发布代码如下:
#include "ros/ros.h"
#include "std_msgs/String.h"
// 回调函数,用于获取发布队列中的信息
void getMsg(const std_msgs::String::ConstPtr &msg)
{
// 通过msg参数获取并操作订阅到的数据
ROS_INFO("听到talker 发布的数据为: %s", msg->data.c_str());
return;
}
int main(int argc, char *argv[])
{
// 设置中文编码
setlocale(LC_ALL, "");
// 初始化 ROS 节点
ros::init(argc, argv, "listener");
// 创建节点句柄
ros::NodeHandle nh;
// 创建订阅者对象
ros::Subscriber sub = nh.subscribe("talker", 10, getMsg);
// 持续监听发布队列,不断调用回调函数
ros::spin();
return 0;
}
注:当回调函数为类中的成员函数时,需要加入this来指定。
例如:ros::Subscriber sub = nh.subscribe("talker", 10, getMsg); 中,
若回调函数 getMsg() 为 Demo 类内的函数,
则需要更改为 ros::Subscriber sub = nh.subscribe("talker", 10, Demo::getMsg, this);
- 修改CMakeLists.txt文件,添加对listener.cpp的编译,以及编译生成的可执行文件的链接,具体修改内容如下:
add_executable(listener_node src/listener.cpp)
target_link_libraries(listener_node
${catkin_LIBRARIES}
)
验证结果
- 打开终端启动master节点
roscore
- 新开一个终端启动发布方talker_node
rosrun pub_sub talker_node
- 新开一终端启动订阅方listener_node
rosrun pub_sub listener_node
题外点:ros::spin()与ros::spinOnce()
- 二者均用于对回调函数的调用
- ros::spin()之后的代码片段均不会被执行,卡在此处不断调用回调函数
- ros::spinOnce()只调用一次回调函数,调用完之后继续执行之后的代码。故一般与循环语句搭配使用,以此来不断对回调函数进行调用
- 二者关系可以简单粗暴的理解为:ros::spinOnce() + 循环 ≈ ros::spin()
约等于是由于ros::spin()会卡壳,而ros::spinOnce()不会