1 查看目前的坐标系变化
我们先安装功能包:
sudo apt install ros-melodic-tf2-tools
安装成功!
我们先启动上次的发布坐标变换的节点:
liuhongwei@liuhongwei-Legion-Y9000P-IRX8H:~/Desktop/final/my_catkin$ source devel/setup.bash liuhongwei@liuhongwei-Legion-Y9000P-IRX8H:~/Desktop/final/my_catkin$ roslaunch test tf_son1_son2.launch
<launch><node pkg="tf2_ros" type="static_transform_publisher" name="son1" args="0.2 0.8 0.3 0 0 0 /world /son1" output="screen" /><node pkg="tf2_ros" type="static_transform_publisher" name="son2" args="0.5 0 0 0 0 0 /world /son2" output="screen" /> </launch>
目前坐标系的关系已经发布了。
我们查看现在的坐标关系:
rosrun tf2_tools view_frames.py
liuhongwei@liuhongwei-Legion-Y9000P-IRX8H:~$ rosrun tf2_tools view_frames.py [INFO] [1701501936.157621]: Listening to tf data during 5 seconds... [INFO] [1701501941.163282]: Generating graph in frames.pdf file... liuhongwei@liuhongwei-Legion-Y9000P-IRX8H:~$
生成了一个pdf文件。
我们查看一下。
2 案例:产生两只乌龟并让一只跟随另一只
2.1 需求
程序启动之初: 产生两只乌龟,中间的乌龟(A) 和 左下乌龟(B), B 会自动运行至A的位置,并且键盘控制时,只是控制 A 的运动,但是 B 可以跟随 A 运行。
2.2 实现分析
乌龟跟随实现的核心,是乌龟A和B都要发布相对世界坐标系的坐标信息,然后,订阅到该信息需要转换获取A相对于B坐标系的信息,最后,再生成速度信息,并控制B运动。
- 启动乌龟显示节点
- 在乌龟显示窗体中生成一只新的乌龟(需要使用服务)
- 编写两只乌龟发布坐标信息的节点
- 编写订阅节点订阅坐标信息并生成新的相对关系生成速度信息
实现流程:
新建功能包,添加依赖
编写服务客户端,用于生成一只新的乌龟
编写发布方,发布两只乌龟的坐标信息
编写订阅方,订阅两只乌龟信息,生成速度信息并发布
运行
2.3 实现
2.3.1 实现1--启动乌龟1,生成乌龟2:GUI
建立gen_turtle.cpp创建第二只乌龟:
// // Created by liuhongwei on 23-12-2. // /*创建第二只小乌龟*/ #include "ros/ros.h" #include "turtlesim/Spawn.h"int main(int argc, char *argv[]) {setlocale(LC_ALL,"");//执行初始化ros::init(argc,argv,"create_turtle");//创建节点ros::NodeHandle nh;//创建服务客户端ros::ServiceClient client = nh.serviceClient<turtlesim::Spawn>("/spawn");ros::service::waitForService("/spawn");turtlesim::Spawn spawn;spawn.request.name = "turtle2";spawn.request.x = 1.0;spawn.request.y = 2.0;spawn.request.theta = 3.12415926;bool flag = client.call(spawn);if (flag){ROS_INFO("乌龟%s创建成功!",spawn.response.name.c_str());}else{ROS_INFO("乌龟2创建失败!");}ros::spin();return 0; }
放入launch文件中:
<launch><!-- 启动乌龟节点与键盘控制节点 --><node pkg="turtlesim" type="turtlesim_node" name="turtle1" output="screen" /><node pkg="turtlesim" type="turtle_teleop_key" name="key_control" output="screen"/><!-- 启动创建第二只乌龟的节点 --><node pkg="test" type="generate_turtle" name="turtle2" output="screen" /></launch>
启动节点:roslaunch test generate_turtle.launch
功能全部实现!
那么如何控制第二只乌龟运动呢?大家想一下怎么做!
2.3.2 发布乌龟坐标系相关关系
发布两只乌龟相对于世界坐标系之间的关系:
和前面基本一样,这里我们复用了前面的代码:
1.TF2与TF比较_简介
TF2已经替换了TF,TF2是TF的超集,建议学习 TF2 而非 TF
TF2 功能包的增强了内聚性,TF 与 TF2 所依赖的功能包是不同的,TF 对应的是
tf
包,TF2 对应的是tf2
和tf2_ros
包,在 TF2 中不同类型的 API 实现做了分包处理。TF2 实现效率更高,比如在:TF2 的静态坐标实现、TF2 坐标变换监听器中的 Buffer 实现等
2.TF2与TF比较_静态坐标变换演示
接下来,我们通过静态坐标变换来演示TF2的实现效率。
2.1启动 TF2 与 TF 两个版本的静态坐标变换
TF2 版静态坐标变换:
rosrun tf2_ros static_transform_publisher 0 0 0 0 0 0 /base_link /laser
TF 版静态坐标变换:
rosrun tf static_transform_publisher 0 0 0 0 0 0 /base_link /laser 100
会发现,TF 版本的启动中最后多一个参数,该参数是指定发布频率
2.2运行结果比对
使用
rostopic
查看话题,包含/tf
与/tf_static
, 前者是 TF 发布的话题,后者是 TF2 发布的话题,分别调用命令打印二者的话题消息
rostopic echo /tf
: 当前会循环输出坐标系信息
rostopic echo /tf_static
: 坐标系信息只有一次2.3结论
如果是静态坐标转换,那么不同坐标系之间的相对状态是固定的,既然是固定的,那么没有必要重复发布坐标系的转换消息,很显然的,tf2 实现较之于 tf 更为高效
我们把它写入launch文件。
<!--tf2 实现小乌龟跟随案例 --> <launch><!-- 启动乌龟节点与键盘控制节点 --><node pkg="turtlesim" type="turtlesim_node" name="turtle1" output="screen" /><node pkg="turtlesim" type="turtle_teleop_key" name="key_control" output="screen"/><!-- 启动创建第二只乌龟的节点 --><node pkg="test" type="generate_turtle" name="turtle2" output="screen" /><!-- 启动两个坐标发布节点 --><node pkg="test" type="generate_turtle_locate" name="caster1" output="screen" args="turtle1" /><node pkg="test" type="generate_turtle_locate" name="caster2" output="screen" args="turtle2" /></launch>
启动launch文件:roslaunch test generate_turtle.launch
我们打开RVIZ可视化一下:
2.3.3 订阅坐标信息并生成速度信息
订阅 turtle1 和 turtle2 的 TF 广播信息,查找并转换时间最近的 TF 信息
将 turtle1 转换成相对 turtle2 的坐标,在计算线速度和角速度并发布实现流程:
1.包含头文件
2.初始化 ros 节点
3.创建 ros 句柄
4.创建 TF 订阅对象
5.处理订阅到的 TF
6.spin先来看t1怎么到t2:
他们的直线距离为,角度为,我们乘以一个参数就是速度、角速度。
//5-1.先获取 turtle1 相对 turtle2 的坐标信息geometry_msgs::TransformStamped tfs = buffer.lookupTransform("turtle2","turtle1",ros::Time(0));//5-2.根据坐标信息生成速度信息 -- geometry_msgs/Twist.hgeometry_msgs::Twist twist;twist.linear.x = 0.5 * sqrt(pow(tfs.transform.translation.x,2) + pow(tfs.transform.translation.y,2));twist.angular.z = 4 * atan2(tfs.transform.translation.y,tfs.transform.translation.x);//5-3.发布速度信息 -- 需要提前创建 publish 对象pub.publish(twist);
因此我们得到了角速度、线速度并发布。
// // Created by liuhongwei on 23-12-2. // /*订阅 turtle1 和 turtle2 的 TF 广播信息,查找并转换时间最近的 TF 信息将 turtle1 转换成相对 turtle2 的坐标,在计算线速度和角速度并发布实现流程:1.包含头文件2.初始化 ros 节点3.创建 ros 句柄4.创建 TF 订阅对象5.处理订阅到的 TF6.spin*/ //1.包含头文件 #include "ros/ros.h" #include "tf2_ros/transform_listener.h" #include "geometry_msgs/TransformStamped.h" #include "geometry_msgs/Twist.h"int main(int argc, char *argv[]) {setlocale(LC_ALL,"");// 2.初始化 ros 节点ros::init(argc,argv,"sub_TF");// 3.创建 ros 句柄ros::NodeHandle nh;// 4.创建 TF 订阅对象tf2_ros::Buffer buffer;tf2_ros::TransformListener listener(buffer);// 5.处理订阅到的 TF// 需要创建发布 /turtle2/cmd_vel 的 publisher 对象ros::Publisher pub = nh.advertise<geometry_msgs::Twist>("/turtle2/cmd_vel",1000);ros::Rate rate(10);while (ros::ok()){try{//5-1.先获取 turtle1 相对 turtle2 的坐标信息geometry_msgs::TransformStamped tfs = buffer.lookupTransform("turtle2","turtle1",ros::Time(0));//5-2.根据坐标信息生成速度信息 -- geometry_msgs/Twist.hgeometry_msgs::Twist twist;twist.linear.x = 0.5 * sqrt(pow(tfs.transform.translation.x,2) + pow(tfs.transform.translation.y,2));twist.angular.z = 4 * atan2(tfs.transform.translation.y,tfs.transform.translation.x);//5-3.发布速度信息 -- 需要提前创建 publish 对象pub.publish(twist);}catch(const std::exception& e){// std::cerr << e.what() << '\n';ROS_INFO("错误提示:%s",e.what());}rate.sleep();// 6.spinros::spinOnce();}return 0; }
我们执行launch文件。
可以的。
3 小结
坐标变换在机器人系统中是一个极其重要的组成模块,在 ROS 中 TF2 组件是专门用于实现坐标变换的,TF2 实现具体内容又主要介绍了如下几部分:
1.静态坐标变换广播器,可以编码方式或调用内置功能包来实现(建议后者),适用于相对固定的坐标系关系
2.动态坐标变换广播器,以编码的方式广播坐标系之间的相对关系,适用于易变的坐标系关系
3.坐标变换监听器,用于监听广播器广播的坐标系消息,可以实现不同坐标系之间或同一点在不同坐标系之间的变换
4.机器人系统中的坐标系关系是较为复杂的,还可以通过 tf2_tools 工具包来生成 ros 中的坐标系关系图
5.当前 TF2 已经替换了 TF,官网建议直接学习 TF2,并且 TF 与 TF2 的使用流程与实现 API 比较类似,只要有任意一方的使用经验,另一方也可以做到触类旁通。
1.TF2与TF比较_简介
TF2已经替换了TF,TF2是TF的超集,建议学习 TF2 而非 TF
TF2 功能包的增强了内聚性,TF 与 TF2 所依赖的功能包是不同的,TF 对应的是
tf
包,TF2 对应的是tf2
和tf2_ros
包,在 TF2 中不同类型的 API 实现做了分包处理。TF2 实现效率更高,比如在:TF2 的静态坐标实现、TF2 坐标变换监听器中的 Buffer 实现等
2.TF2与TF比较_静态坐标变换演示
接下来,我们通过静态坐标变换来演示TF2的实现效率。
2.1启动 TF2 与 TF 两个版本的静态坐标变换
TF2 版静态坐标变换:
rosrun tf2_ros static_transform_publisher 0 0 0 0 0 0 /base_link /laser
TF 版静态坐标变换:
rosrun tf static_transform_publisher 0 0 0 0 0 0 /base_link /laser 100
会发现,TF 版本的启动中最后多一个参数,该参数是指定发布频率
2.2运行结果比对
使用
rostopic
查看话题,包含/tf
与/tf_static
, 前者是 TF 发布的话题,后者是 TF2 发布的话题,分别调用命令打印二者的话题消息
rostopic echo /tf
: 当前会循环输出坐标系信息
rostopic echo /tf_static
: 坐标系信息只有一次2.3结论
如果是静态坐标转换,那么不同坐标系之间的相对状态是固定的,既然是固定的,那么没有必要重复发布坐标系的转换消息,很显然的,tf2 实现较之于 tf 更为高效