TF坐标变换:
- 广播TF变换
- 监听TF变换
通过TF将雷达坐标系变换成本体坐标系
安装TF
rosversion -d 查询ros版本
sudo apt-get install ros-<版本号>-turtle-tf
启动launch文件
roslaunch turtle_tf turtle_tf_demo.launch
问题:/usr/bin/env python没有那个文件或目录
有可能是python2、python3语法不兼容。安装的noetic版本(支持python3),而教程是另外的版本(只支持Python2)。
解决方法:sudo update-alternatives --install /usr/bin/python python /usr/bin/python3.8 1
效果图:
注意:noetic版本不需要运行键盘控制节点,可直接控制小海龟移动
view_frames可视化工具
rosrun tf view_frames
保存当前TF坐标间关系 成PDF在当前目录
遇到的问题:不能对字节的对象用符号串模式
解决方案:
sudo vim /opt/ros/noetic/lib/tf/view_frames
然后修改m = r.search(vstr.decode('utf-8'))
按ESC,左下角输入:wq //保存退出
效果图:
ECHO可视化工具
rosrun tf tf_echo <name> <name>
实时获取任意两坐标系关系
RVIZ三维可视化显示平台
rosrun rviz rviz -d `rospack find turtle_tf`/rviz/turtle_rviz.rviz
Fixed Frame改成world
add添加TF
TF坐标系广播与监听的编程
创建功能包
$ cd ~/catkin_ws/src
$ catkin_create_pkg learning_tf roscpp rospy tf turtlesim
创建TF广播器
定义TF广播器
创建坐标变换值
发布坐标变化
/**
* 该例程产生tf数据,并计算、发布turtle2的速度指令
*/
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <turtlesim/Pose.h>
std::string turtle_name;
void poseCallback(const turtlesim::PoseConstPtr& msg)
{
// 创建tf的广播器
static tf::TransformBroadcaster br;
// 初始化tf数据
tf::Transform transform;
transform.setOrigin( tf::Vector3(msg->x, msg->y, 0.0) );
tf::Quaternion q;
q.setRPY(0, 0, msg->theta);
transform.setRotation(q);
// 广播world与海龟坐标系之间的tf数据
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, &poseCallback);
// 循环等待回调函数
ros::spin();
return 0;
};
创建TF监听器
定义监听器,查找坐标变换
/**
* 该例程监听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::NodeHandle node;
// 请求产生turtle2
ros::service::waitForService("/spawn");
ros::ServiceClient add_turtle = node.serviceClient<turtlesim::Spawn>("/spawn");
turtlesim::Spawn srv;
add_turtle.call(srv);
// 创建发布turtle2速度控制指令的发布者
ros::Publisher turtle_vel = node.advertise<geometry_msgs::Twist>("/turtle2/cmd_vel", 10);
// 创建tf的监听器
tf::TransformListener listener;
ros::Rate rate(10.0);
while (node.ok())
{
// 获取turtle1与turtle2坐标系之间的tf数据
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;
}
// 根据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;
};
配置CMakeLists编译规则
add_executable(turtle_tf_broadcaster src/turtle_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})
编译运行
cd ~/catkin_ws
catkin_make
source devel/setup.bash //省略
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 //键盘控制