开辟新的工作空间
mkdir -p learn_ros/src
cd learn_ros/src
创建相应的功能包
catkin_create_pkg learning_tf geometry_msgs roscpp tf turtlesim
编写一个tf坐标系的发布节点,发布turtlr在世界坐标系的位姿信息
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <turtlesim/Pose.h>
std::string turtle_name;
void posecallback(const turtlesim::PoseConstPtr & msg)
{
static tf::TransformBroadcaster br;
tf::Transform transform;
transform.setOrigin(tf::Vector3(msg->x,msg->y,0));
tf::Quaternion q;
q.setRPY(0,0,msg->theta);
transform.setRotation(q);
br.sendTransform(tf::StampedTransform(transform,ros::Time::now(),"world",turtle_name));
}
int main(int argc, char**argv)
{
ros::init(argc,argv,"turtle_tf");
if(argc!=2)
{
ROS_ERROR("name of the turtle is needed");
return -1;
}
turtle_name=argv[1];
ros::NodeHandle n;
ros::Subscriber sub =n.subscribe(turtle_name+"/pose",10,&posecallback);
//函数名前加&表示返回值为引用
ros::spin();
//阻塞轮询,程序会停在这个点上直到接收到消息。为同步机制。
}
编写一个tf_listener程序,生成turtle2,并利用监听得到的坐标系转化使turtle2追踪turtle1
#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::init(argc,argv,"tf_listener");
ros::NodeHandle n;
ros::service::waitForService("spawn");
ros::ServiceClient add_turtle=n.serviceClient<turtlesim::Spawn>("spawn");
turtlesim::Spawn srv;
add_turtle.call(srv);
ros::Publisher vel_pub=n.advertise<geometry_msgs::Twist>("turtle2/cmd_vel",10);
tf::TransformListener listener;
ros::Rate rate(10.0);
while(n.ok())
{
tf::StampedTransform transform;
try
{
listener.waitForTransform("/turtle2", "/turtle1", ros::Time(0), ros::Duration(3.0));
listener.lookupTransform("/turtle2", "/turtle1", ros::Time(0), transform);
}
catch (tf::TransformException &ex)
{
ROS_ERROR("%s",ex.what());
ros::Duration(1.0).sleep();
continue;
}
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));
vel_pub.publish(vel_msg);
rate.sleep();
}
return 0;
}
在cmakelist中添加可执行程序,并与库链接。
add_executable(turtle_tf_broadcaster src/tf_broadcaster.cpp)
target_link_libraries(turtle_tf_broadcaster ${catkin_LIBRARIES})
add_executable(turtle_tf_listener src/turtle_tf_listener.cpp)
target_link_libraries(turtle_tf_listener ${catkin_LIBRARIES})
进行catkin_make
在功能包内创建launch文件夹,并创建launch文件。
<launch>
<!-- 海龟仿真器 -->
<node pkg="turtlesim" type="turtlesim_node" name="sim"/>
<!-- 键盘控制 -->
<node pkg="turtlesim" type="turtle_teleop_key" name="teleop" output="screen"/>
<!-- 两只海龟的tf广播 -->
<node pkg="learning_tf" type="turtle_tf_broadcaster"
args="/turtle1" name="turtle1_tf_broadcaster" />
<node pkg="learning_tf" type="turtle_tf_broadcaster"
args="/turtle2" name="turtle2_tf_broadcaster" />
<!-- 监听tf广播,并且控制turtle2移动 -->
<node pkg="learning_tf" type="turtle_tf_listener"
name="listener" />
</launch>
运行launch文件
source devel/setup.bash
roslaunch learning_tf start_demo_with_listener.launch
运行结果如下:
使用rviz订阅tf来对坐标系可视化
rviz
将fixed frame改为world
依次添加三个坐标系和tf,完成可视化