.tf坐标系广播与监听的编程实现[1]
以下代码使用tf广播器和监听器实现与roslaunch turtle_tf turtle_tf_demo.launch相同效果。首先,创建一程序订阅海龟的相对于world的位置,即海龟发布的/turtle_name/pose消息,接受到消息数据后,创建tf的广播器,并初始化tf数据,广播world与海龟坐标系之间的关系;然后,创建一程序产生第2只海龟turtle2,实时监听tf广播数据,依据turtle2与turtle1之间的坐标关系计算turtle2的速度,向turtle2发布速度控制指令,实现海龟turtle2跟踪turtle1。
订阅/pose消息,广播tf数据
/**
* 该例程产生tf数据,并计算、发布turtle2的速度指令
*/
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <turtlesim/Pose.h>
std::string turtle_name;
void poseCalllback(const turtlesim::PoseConstPtr& msg)
{
// 创建tf的广播器
static tf::TransformBroadcaster br;
// 初始化tf数据
tf::Transform transform;
// 设置平移参数(相对于world的位置,world实际为仿真器左下角端点)
transform.setOrigin(tf::Vector3(msg->x,msg->y,0.0));
// 设置旋转参数
tf::Quaternion q;
q.setRPY(0,0,msg->theta);
transform.setRotation(q);
// 广播world与海龟坐标系之间的tf数据
// 添加时间戳
// 描述world和turtle_name之间的关系
// 在TF Tree中会出现二者之间关系
br.sendTransform(tf::StampedTransform(transform,ros::Time::now(),"world",turtle_name));
}
int main(int argc,char** argv)
{
// 初始化ROS节点
ros::init(argc,argv,"my_tf_broadcaster");
// 输入参数作为海龟的名字
if(argc!=2)
{
ROS_ERROR("need turtle name as argument");
return -1;
}
turtle_name=argv[1];
// 订阅海龟的位姿话题
ros::NodeHandle node;
ros::Subscriber sub=node.subscribe(turtle_name+"/pose",10,&poseCalllback);
// 循环等待回调函数
ros::spin();
return 0;
}
监听tf数据,发布turtle2速度控制指令
/**
* 该例程监听tf数据,并计算、发布turtle2的速度指令
*/
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Twist.h>
#include <turtlesim/Spawn.h>
int main(int argc,char** argv)
{
// 初始化ROS节点
ros::init(argc,argv,"my_tf_listener");
// 创建ROS节点句柄
ros::NodeHandle node;
// 请求产生turtle2
ros::service::waitForService("/spawn");
ros::ServiceClient add_turtle=node.serviceClient<turtlesim::Spawn>("/spawn");
turtlesim::Spawn srv;
srv.request.x=2.0;
srv.request.y=2.0;
srv.request.name="/turtle2";
add_turtle.call(srv);
ROS_INFO("Create %s successfully",srv.response.name.c_str());
// 创建发布turtle2速度控制指令的发布者
ros::Publisher turtle_vel=node.advertise<geometry_msgs::Twist>("/turtle2/cmd_vel",10);
// 创建tf的监听器
tf::TransformListener listener;
// 1秒钟发布10次
ros::Rate rate(10);
while(node.ok())
{
// 获取turtle1与turtle2坐标系之间的tf数据
tf::StampedTransform transform;
try
{
// 等待系统中存在名为“/turtle2”和“/turtle1”的坐标系,查询当前时间,等待3秒超时
listener.waitForTransform("/turtle2","/turtle1",ros::Time(0),ros::Duration(3.0));
// 查询“/turtle2”和“/turtle1”的坐标系关系,结果保存在transform中
listener.lookupTransform("/turtle2","/turtle1",ros::Time(0),transform);
}
catch(tf::TransformException &ex)
{
ROS_ERROR("%s",ex.what());
ros::Duration(1.0).sleep();
continue;
}
// 根据turtle1与turtle2坐标系之间的位置关系,发布turtle2的速度控制指令
geometry_msgs::Twist vel_msg;
vel_msg.angular.z=4.0*atan2(transform.getOrigin().y(),transform.getOrigin().x());
vel_msg.linear.x=0.5*sqrt(pow(transform.getOrigin().x(),2)+pow(transform.getOrigin().y(),2));
turtle_vel.publish(vel_msg);
rate.sleep();
}
return 0;
}
命令行控制运行
$ roscore
$ rosrun turtlesim turtlesim_node
$ rosrun learning_tf turtle_tf_broadcaster __name:=turtle1_tf_broadcaster /turtle1
$ rosrun learning_tf turtle_tf_broadcaster __name:=turtle2_tf_broadcaster /turtle2
$ rosrun learning_tf turtle_tf_listener
$ rosrun turtlesim turtle_teleop_key
注意:在命令行输入rosrun learning_tf turtle_tf_broadcaster __name:=turtle1_tf_broadcaster /turtle1,该命令将对节点重命名为name后面的名字,即turtle1_tf_broadcaster,在ros中称之为重映射。
运行效果
参考资料
[1]古月居,ROS入门21讲: https://www.bilibili.com/video/BV1zt411G7Vn?p=18。