话题通信实操主要是通过ROS内置的turtlesim案例,结合已经介绍ROS命令获取节点、话题、话题消息等实现实现乌龟运动的控制。
需求描述: 编码实现乌龟运动控制,让小乌龟做圆周运动。
实现分析:
实现流程:
通过计算图查看话题:
rqt_graph
或者通过 rostopic 列出话题:
rostopic list
获取消息类型:
rostopic type /turtle1/cmd_vel
output:
geometry_msgs/Twist
获取消息格式:
rosmsg info geometry_msgs/Twist
output:
geometry_msgs/Vector3 linear ## xyz方向的线速度
float64 x
float64 y
float64 z
geometry_msgs/Vector3 angular ## x轴上的翻滚、y轴上的俯仰和z轴上的偏航的角速度
float64 x
float64 y
float64 z
创建功能包需要依赖的功能包: roscpp rospy std_msgs geometry_msgs
/*
编写 ROS 节点,控制小乌龟画圆
准备工作:
1.获取topic(已知: /turtle1/cmd_vel)
2.获取消息类型(已知: geometry_msgs/Twist)
3.运行前,注意先启动 turtlesim_node 节点
实现流程:
1.包含头文件
2.初始化 ROS 节点
3.创建发布者对象
4.循环发布运动控制消息
*/
#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2.初始化 ROS 节点
ros::init(argc,argv,"control");
ros::NodeHandle nh;
// 3.创建发布者对象
ros::Publisher pub = nh.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel",1000);
// 4.循环发布运动控制消息
//4-1.组织消息
geometry_msgs::Twist msg;
msg.linear.x = 1.0;
msg.linear.y = 0.0;
msg.linear.z = 0.0;
msg.angular.x = 0.0;
msg.angular.y = 0.0;
msg.angular.z = 2.0;
//4-2.设置发送频率
ros::Rate r(10);
//4-3.循环发送
while (ros::ok())
{
pub.publish(msg);
ros::spinOnce();
}
return 0;
}
配置文件同ROS系列(四):ROS通信机制系列(1):话题通信中的发布方配置文件。
运行同本文 1.1 启动tutlesim节点。
需求描述:
已知turtlesim中的乌龟显示节点,会发布当前乌龟的位姿(窗体中乌龟的坐标以及朝向),要求控制乌龟运动,并时时打印当前乌龟的位姿。
实现流程:
获取话题:/turtle1/pose:
rostopic list
获取消息类型:turtlesim/Pose
rostopic type /turtle1/pose
获取消息格式:
rosmsg info turtlesim/Pose
结果:
float32 x
float32 y
float32 theta
float32 linear_velocity
float32 angular_velocity
创建功能包需要依赖的功能包: roscpp rospy std_msgs turtlesim
/*
订阅小乌龟的位姿: 时时获取小乌龟在窗体中的坐标并打印
准备工作:
1.获取话题名称 /turtle1/pose
2.获取消息类型 turtlesim/Pose
3.运行前启动 turtlesim_node 与 turtle_teleop_key 节点
实现流程:
1.包含头文件
2.初始化 ROS 节点
3.创建 ROS 句柄
4.创建订阅者对象
5.回调函数处理订阅的数据
6.spin
*/
#include "ros/ros.h"
#include "turtlesim/Pose.h"
void doPose(const turtlesim::Pose::ConstPtr& p){
ROS_INFO("乌龟位姿信息:x=%.2f,y=%.2f,theta=%.2f,lv=%.2f,av=%.2f",
p->x,p->y,p->theta,p->linear_velocity,p->angular_velocity
);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2.初始化 ROS 节点
ros::init(argc,argv,"sub_pose");
// 3.创建 ROS 句柄
ros::NodeHandle nh;
// 4.创建订阅者对象
ros::Subscriber sub = nh.subscribe<turtlesim::Pose>("/turtle1/pose",1000,doPose);
// 5.回调函数处理订阅的数据
// 6.spin
ros::spin();
return 0;
}
配置文件同ROS系列(四):ROS通信机制系列(1):话题通信中的订阅方配置文件。