在ros下有一个库:tf,其主要功能是维护整个系统中所有坐标系,形成一个完整的坐标转换树。利用tf库,可以描述一个物体相对于另一个物体坐标系的坐标转换,从而形成单链的描述。而将整个系统中所有物体均链接此树后,则可以得到任何两个坐标的相互关系;如下图所示。
已知如下关系:
laser->baselink
depth->baselink
baselink->odom
odom->map
gps->map
如此当利用tf进行管理时,laser、baselink、depth、odom、map、gps任意之间均可获取相互转换关系。
需要注意的是,一个系统中必须仅有一个tf树,即所有坐标系都应在此坐标树中,否则无法使用;
基本的数据类型有(Quaternion, Vector, Point, Pose, Transform);
tf::Stamped 为tf变换中使用的数据类型,其中T为上述除了Transform其他类型;tf::Stamped 主要根据监听的tf进行转标转换的类型;
namespace tf
{
class TransformBroadcaster{
public:
TransformBroadcaster();
void sendTransform(const StampedTransform & transform);
void sendTransform(const std::vector & transforms);
void sendTransform(const geometry_msgs::TransformStamped & transform);
void sendTransform(const std::vector & transforms);
private:
tf2_ros::TransformBroadcaster tf2_broadcaster_;
};
}
transform.setOrigin( tf::Vector3(2.0*sin(ros::Time::now().toSec()), 2.0*cos(ros::Time::now().toSec()), 0.0) );
transform.setRotation( tf::Quaternion(0, 0, 0, 1) );
Transform对象内包含两种信息,即平移和旋转量。其中旋转量采用4元数表示;
例子:
static tf::TransformBroadcaster br;
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);
br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", turtle_name));
geometry_msgs::TransformStamped transformStamped;
//坐标转换广播
tf::TransformBroadcaster broadcaster;
//初始转换参数
transformStamped.header.frame_id = "origin_base";
transformStamped.child_frame_id = "trans_base";
transformStamped.transform.translation.x = 0;
transformStamped.transform.translation.y = 0;
transformStamped.transform.translation.z = 0;
transformStamped.transform.rotation.x = 0;
transformStamped.transform.rotation.y = 0;
transformStamped.transform.rotation.z = 0;
transformStamped.transform.rotation.w = 1;
broadcaster.sendTransform(transformStamped);
tf::TransformListener listener(ros::Duration(10)); // 缓存10s内的变换
tf::TransformListener listener; // 缓存默认是时间数据
tf::StampedTransform transform;
//
listener.waitForTransform("world" ,"base_link", ros::Time(0),ros::Duration(3.0));
// transform则为获取当前base_link在world坐标系下的坐标,即为从“world”到“baselink”下的转换
// 其中ros::Time(0)表示获取最近时刻的转换参数,因为无法实时,故不能修改为 ros::Time::now();
listener.lookupTransform("world" ,"base_link" ros::Time(0), transform);
转换信息是描述两个坐标系的相互关系,采用一个6自由度的相对位姿表示:平移量(translation)和旋转量(rotation)
平移量(translation)是一个向量,用 W t A W_{tA} WtA。在ROS中用tf::Vector3来表示,包括 ( x , y , z ) (x,y,z) (x,y,z);
旋转量(rotation)用一个旋转量矩阵(rotation matrices)来表示,符号为 W A R W_{A^R} WAR,同样为3维向量,表示为 ( p i t c h , r o l l , y a w ) (pitch,roll,yaw) (pitch,roll,yaw)。 但是在ros的tf变换中采用四元素表示tf::Quaternion;
但是TF库中可以将4元数和旋转矩阵进行转换;
tf::Quaternion tf::createQuaternionFromRPY (double roll, double pitch, double yaw)
static Quaternion tf::createQuaternionFromYaw (double yaw)
static geometry_msgs::Quaternion tf::createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw)
如果转换信息可用4*4矩阵表示,我们称为 W A T W_{A^T} WAT,其表示形式为
W A R W t A 0 1 \begin{matrix} W_{A^R} & W_{tA} \\ 0 & 1 \end{matrix} WAR0WtA1
在平面坐标下,如已知A点在W下在坐标为 W p ( x , y , θ ) W_p(x,y,\theta) Wp(x,y,θ)即所谓的 W A T W_{A^T} WAT(即transform)。假设A_p点在A坐标下坐标为(x_a,y_b);则 A p A_p Ap点在W下的坐标为
1.采用公式直接转换
W A T × A p = W p W_{A^T}×A_p=W_p WAT×Ap=Wp
[ x ′ y ′ 1 ] = [ c o s ( θ ) − s i n ( θ ) x s i n ( θ ) c o s ( θ ) ) y 0 0 1 ] ∗ [ x a y a 1 ] \left[ \begin{matrix} x'\\ y'\\ 1 \end{matrix} \right] = \left[ \begin{matrix} cos(\theta) & -sin(\theta) & x\\ sin(\theta) & cos(\theta)) & y\\ 0& 0 & 1 \end{matrix} \right] *\left[ \begin{matrix} x_a\\ y_a\\ 1\\ \end{matrix} \right] ⎣⎡x′y′1⎦⎤=⎣⎡cos(θ)sin(θ)0−sin(θ)cos(θ))0xy1⎦⎤∗⎣⎡xaya1⎦⎤
x w = x + x a ∗ c o s ( θ ) − y a ∗ s i n ( θ ) x_w = x + x_a*cos(\theta) - y_a*sin(\theta) xw=x+xa∗cos(θ)−ya∗sin(θ)
y w = y + y a ∗ c o s ( θ ) + x a ∗ s i n ( θ ) y_w = y + y_a* cos(\theta) + x_a*sin(\theta) yw=y+ya∗cos(θ)+xa∗sin(θ)
Eigen::Affine3d W_to_A_eig; // 仿射变换矩阵
tf::Transform W_to_A;
tf::transformTFToEigen(W_to_A, W_to_A_eig); // 转换eigen矩阵格式
Eigen::Vector3d pos(x_a,y_a,z_a);
Eigen::Vector3d pos = W_to_A_eig * pos;
// 对坐标点进行转换
void TransformListener::transformPoint ( const std::string & target_frame,
const geometry_msgs::PointStamped & stamped_in,
geometry_msgs::PointStamped & stamped_out
)
// 对点云坐标转换
void TransformListener::transformPointCloud ( const std::string & target_frame,
const sensor_msgs::PointCloud & pcin,
sensor_msgs::PointCloud & pcout
)
// 对pose进行转换,包含 point和Quaternion
void TransformListener::transformPose ( const std::string & target_frame,
const geometry_msgs::PoseStamped & stamped_in,
geometry_msgs::PoseStamped & stamped_out
)
// 对方向进行转换
void TransformListener::transformQuaternion ( const std::string & target_frame,
const geometry_msgs::QuaternionStamped & stamped_in,
geometry_msgs::QuaternionStamped & stamped_out
)
// 对坐标向量进行转换,同样为point,仅类型为vector
void TransformListener::transformVector ( const std::string & target_frame,
const geometry_msgs::Vector3Stamped & stamped_in,
geometry_msgs::Vector3Stamped & stamped_out
)
例如:若已知map到baselink的坐标转换,同时已知里程计到baselink下的坐标转换,则可获取odom到map下的坐标转换。
tf::Transform map_to_base; // 已知baselink在 map下的坐标
tf::Transform odom_to_base; // 已知baselink在odom下的坐标
odom_to_map_ = odom_to_base * map_to_base.inverse();