智能机器人(77):ROS的TF-transform(04)

使用变换的方式, 如何跟踪坐标系树?

这棵tf-tree一直随着时间的推移而变化,并且每个变换都被存储了时间快照,默认的是最多保存10秒之内的。
可以用lookupTransform()函数来访问该tf-tree中最新的可用转换,但其实并不知道该转换会在什么时间发生。

例如,以下广播了一个新的坐标系转换,从父turtle1到新的carrot1,carrot1的左偏离turtle1了2米:
br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), “turtle1”, “carrot1”));
这里现给变换一个时间戳,用的就是当前时间ros :: Time :: now()。

随后, 可以开始使用carrot1的各种信息了:
listener.lookupTransform(“/turtle2”, “/carrot1”, ros::Time(0), transform);
这里指定了一个等于0的时间,对于tf来说, time0就是表示缓冲区中最新可用的变换。

当然,也可以获取特定的时间所进行的转换, 例如, 改为当前时间的变换:
listener.lookupTransform(“/turtle2”, “/carrot1”, ros::Time::now(), transform);

但是这时候, lookupTransform会失败,反复出错说:
You requested a transform that is 0.018 miliseconds in the past,
but the most recent transform in the tf buffer is 7.681 miliseconds old.
When trying to transform between /carrot1 and /turtle2.

或者这样的出错:
Exception thrown:
Lookup would require extrapolation into the past.
Requested time 1516087296.727826475 but the earliest data is at time 1516087297.522204578,
when looking up transform from frame [laser_link] to frame [map]

或者:
Transform [sender=unknown_publisher]
For frame [laser_link]: No transform to fixed frame [map]. TF error: [Lookup would require extrapolation into the future. Requested time 1516092877.852408757 but the latest data is at time 1516092875.632156846, when looking up transform from frame [laser_link] to frame [map]]

为什么?

因为每个listener都有一个缓冲区,存储来自不同broadcaster的所有坐标变换。
而当broadster发送一个转换时,该转换真正进入缓冲区需要几个毫秒的时间。

所以,如果在“现在”的时刻请求请求“现在“进行的转换的时候,应该等待几毫秒才能到达。
ros::Time now = ros::Time::now();
listener.waitForTransform(“/turtle2”, “/carrot1”, now, ros::Duration(3.0));
listener.lookupTransform(“/turtle2”, “/carrot1”, now, transform);
意思是,等待从这个t1到c1的变换,在now这个时候,等待不要超过3.0这个最长持续时间。

因此,这个waitForTransform()实际上会阻塞,直到两个frame间的转换可用;
这通常需要几毫秒,或者,严重的,如果转换一直不可用,那么一直等到3.0second的超时。

总结: lookupTransform是一个较低级别的方法,它返回两个坐标系之间的变换,这个方法是tf库的核心功能
然而最常见的是transform *方法,将被最终用户使用。
这个方法被设计用于transform *()方法中。

智能机器人(75):ROS的TF-transform(03)

PART I – 几个坐标系
*1. map
*2. odom
*3. base_link

PART II – 几个变换
0. base_link–>-base_laser
1. odom–>base_link
2. map–>base_link
*3. map–>odom

PART III – map -> odom的代码

PART IV – map-> odom的作用

PART I – 几个坐标系

关于map,odom, base_link, base_laser,fixed_frame,target_frame的关系。

这些frames具体表述于 http://www.ros.org/reps/rep-0105.html :
earth -> map -> odom -> base_link,
the map frame is the parent of odom, and odom is the parent of base_link.

1. map:代表了一个固定不变的世界。定位了机器人的绝对位姿
2. odom:代表了一个固定不变的世界。定位了机器人的相对位姿。
这个是里程计所测绘到的世界(odom is the world as measured by odometry)。用于定位机器人的相对位姿。
如果里程计/激光雷达等均是完美无缺的,那么odom frame无差别的等同于map frame。也就是map->odom的变换为0。
3. base_link: is rigidly attached to the robot base

*1. map
map是虚拟世界中的固定frame, 一般与odom(或者odom_combined)相连。 它的Z轴指向正上方,也就是天空。map与odom同为全局坐标系,原点为地图原点(地图原点在地图相应的yaml文件中有规定)。

The map frame is useful as a long-term global reference, but discrete jumps in position estimators make it a poor reference frame for local sensing and acting.
In a typical setup, a localization component constantly recomputes the robot pose in the map frame based on sensor observations, therefore eliminating drift, but causing discrete jumps when new sensor information arrives.

*2. odom
在一个典型设置中,odom 坐标系是基于测距源来计算的,如车轮里程计odom,视觉里程计vo或惯性测量单元imu。
In a typical setup the odom frame is computed based on an odometry source, such as wheel odometry, visual odometry or an inertial measurement unit.

odom是一个很好的固定参照frame。机器人的姿态相对odom而言是随时间是经常可变,所以在长远中它不是一个好的全局参照系。但在某一时间点而言它相对机器人的位置是不变的。
However, the pose of a robot in the odom frame is guaranteed to be continuous, meaning that the pose of a mobile platform in the odom frame always evolves in a smooth way, without discrete jumps.

Odom frame is called so because it is the frame where the odometry is used to update the pose of the robot.
The odom frame represents the starting point of the robot, and, the transform from odom to base_link represents the current position of the robot as measured by odometry.
The odometry measurements are a measure of how far the robot has traveled with respect to the /odom frame. The point of odometry messages is to give a measure of the distance the robot has traveled.
In this frame, there is no correction or jumps in the robot’s pose, it is continually updated based on the data coming from the motor’s encoders (sometimes fused with accelerometer and gyro).

*3. base_link
base_link参照系紧紧粘在移动机器人基座上的任何一个位置和角度。
一般位于tf-tree的最根部,物理语义原点一般为表示机器人中心,为相对机器人的本体的坐标系。其它所有的 frame都是相对于base_link定义并粘在一起的。
它们一起相对于大地图map移动,让机器人移动就是向tf发布geometry_msgs::TransformStamped 消息通知 base_link相对于map的tf转换关系。机器人监听到这个变换后移动。

PART II – 几个变换

0. base_link–>-base_laser,提供激光先对于机器人的位置信息,可以直接提供,或者通过urdf模型中提供。
1. odom–>base_link,是里程计节点,机器人在odom中的相对位姿。
2. map–>base_link,通常是在amcl的定位软件模块中,机器人相对于map的绝对位姿。
*3. map–>odom,由于上面1和2的发布导致base_link具有两个parent, 所以通常是这种形势发布。

坐标系变化重要的是,每个帧都只有一个父帧,有时候两个坐标A/B都和C有关联的话,就是A和B关联,B再和C关联,而不是A/B都和C关联。
具体到这里的三个坐标帧map/odom/base_link,其实map和odom都应该和base_link关联,但为了遵守“每个帧只能有一个父帧”的原则,所以只能有一个节点:或者由里程计发布odom->base_link的坐标关系,或者由激光雷达发布map->base_link,但只能有一个,不能同时; 但是却又要体现三个坐标的关系,所以是发布的A->B->C,即map –> odom –> base_link。
就是说:

1.的odom->base_link的坐标关系,由里程计节点计算,并且发布,
2.的map->base_link的坐标关系,由定位节点计算,但并不发布;而是利用odom->base_link的坐标关系,
计算出3.的map->odom,并且发布。

说明:
应用中也并不总是正规的1+3这种形式发布map->odom->base_link, 偶尔的也可以用1或者2这种的简单形式。
例如只有里程计没有激光雷达也能跑,只发布1. odom–>base_link
例如只有激光雷达没有里程计也能跑,只发布2. map–>base_link
或者既有激光雷达也有里程计,也可以仅仅发布1. odom–>base_link或者2. map–>base_link。

*0. base_link–>base_laser
It’s normally static, published by: static_tf published in one of launch files, or
robot_state_publisher from urdf model, such as turtlebot_description.

*1. odom->base_link
odom->base_link的转换是由里程计源计算和发布的。The link between odom and base_link is job of localization node.
It’s computed and broadcast by the odometry sources, or, published by robot_pose_ekf.
So, it may be robot_pose_ekf, or it will be controller’s node directly: just set /mobile_base_controller/enable_odom_tf to true.

*2. map–>base_link
It’s computed by a localization component.
However, the localization component does not broadcast map->base_link.
Instead, it get map->base_link, and with information of odom -> base_link, through this way, get map–>odom.

**3. map–>odom
Although someone would say that both map and odom should be attached to base_link, yes, map->base_link and odom->base_link are both correct.
From map->base_link subtracte base_link->odom will get map->odom.
Dehaoz Tips:
If we have a “perfect” odometry sensor and a “perfect” laser, the map–>odom tf will always be 0.

5. So, the tree looks like this:
But, this is not allowed , because each frame can only have one parent.

PART III – map -> odom的代码

(根据map和base_link以及odom和base_link的关系计算map和odom的坐标关系的代码)

ROS的AMCL算法,主要是:
根据订阅到的地图数据,配合激光扫描特征,使用粒子滤波器,获取最佳定位点Mp (point on map), 也就是base_link在map中的坐标。(map->base_link)
然后根据里程计得到的相对位姿信息 odom->base_link,原点是机器人启动时刻的位置
从而得到map->odom。

代码分析:

$ vi https://github.com/ros-planning/navigation/blob/kinetic-devel/amcl/src/amcl_node.cpp
at lien 1299:

AmclNode::AmclNode()
{
… …
private_nh_.param(“odom_frame_id”, odom_frame_id_, std::string(“odom”));
private_nh_.param(“base_frame_id”, base_frame_id_, std::string(“base_link”));
private_nh_.param(“global_frame_id”, global_frame_id_, std::string(“map”));
… …
odom_frame_id_ = config.odom_frame_id;
base_frame_id_ = config.base_frame_id;
global_frame_id_ = config.global_frame_id;
… …
updatePoseFromServer();
… …
void AmclNode::laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan)
{
… …
// Where was the robot when this scan was taken?
pf_vector_t pose;
if(!getOdomPose(latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2],
laser_scan->header.stamp, base_frame_id_))
{
ROS_ERROR(“Couldn’t determine robot’s pose associated with laser scan”);
return;
}
… …
geometry_msgs::PoseWithCovarianceStamped p;
// Fill in the header
p.header.frame_id = global_frame_id_;
p.header.stamp = laser_scan->header.stamp;
// Copy in the pose
p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0];
p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1];
tf::quaternionTFToMsg(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]), p.pose.pose.orientation);
// hyps[max_weight_hyp].pf_pose_mean.v[0], [1], [2] 代表了粒子滤波器的最佳定位点Mp,
// 也就是base_link在map中的坐标(map->base_link)

… …
pose_pub_.publish(p);
last_published_pose = p; // the pose of base_link among map.
ROS_DEBUG(“New pose: %6.3f %6.3f %6.3f”,
hyps[max_weight_hyp].pf_pose_mean.v[0],
hyps[max_weight_hyp].pf_pose_mean.v[1],
hyps[max_weight_hyp].pf_pose_mean.v[2]); // //amcl估计出的map上的点

// subtracting base_link->odom FROM map->base_link, we get map->odom !

// 这个odom->map是需要求解的关键,
// 即odom坐标系到map坐标系的变换,或者说map在odom的位姿坐标。
tf::Stamped odom_to_map;

try
{
// 根据假设的颗粒点在map的坐标
// 得到 tmp_tf = map->base_link的坐标变换,即base_link在map的位姿坐标,或者从map原点看base_link的位置。
tf::Transform tmp_tf(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]),
tf::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0],
hyps[max_weight_hyp].pf_pose_mean.v[1],
0.0));

// 翻转得到tmp_tf_stamped = base_link->map
// 即获得map在base_kink坐标系中的坐标
tf::Stamped tmp_tf_stamped (tmp_tf.inverse(),
laser_scan->header.stamp,
base_frame_id_);

// transformPose (“frame_c”, b->a, ??), ?? ==>> c->a。
// 这个函数就是由a在b中的位姿,得到a在c中的位姿。
// 这里根据tmp_tf_stamped = base_link->map
// 得到odom_to_map = odom->map,也就是odom坐标系到map坐标系的变换,或者说map在odom的位姿坐标,或者说从odom原点看map原点的位置。
this->tf_->transformPose(odom_frame_id_,
tmp_tf_stamped,
odom_to_map);
}
// subtracting base_link/odom from map/base_link and get map/odom , send map to odom instead
catch(tf::TransformException)
{
ROS_DEBUG(“Failed to subtract base to odom transform”);
return;
}

// latest_tf_ = odom->map
latest_tf_ = tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
tf::Point(odom_to_map.getOrigin()));
latest_tf_valid_ = true;

if (tf_broadcast_ == true)
{
// We want to send a transform that is good until a tolerance time so that odom can be used
ros::Time transform_expiration = (laser_scan->header.stamp + transform_tolerance_);

// 翻转为 map->odom,即odom在map中的位姿坐标,或者说从map原点看odom原点的位置。
tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
transform_expiration,
global_frame_id_, odom_frame_id_);
// 发布 map->odom
this->tfb_->sendTransform(tmp_tf_stamped);
sent_first_transform_ = true;
}
… …

odom->base_link是码盘提供的原始数据
map->base_link是激光帧间匹配计算得到的
ODOM_map = MAP_basekink * ODOM_bae_link,
odom坐标到map坐标的变换矩阵 = map坐标到baselink坐标的变换矩阵 * odom坐标到base_link坐标的变换矩阵
map在odom坐标中的位姿 = baselink在map坐标中的位姿 * map在odom坐标中位姿。

REF:
http://wiki.ros.org/amcl
https://github.com/ros-planning/navigation/tree/kinetic-devel/amcl#amcl_node.cpp
https://answers.ros.org/question/227425/why-gmapping-package-requires-the-base_link-odom-tf/
http://blog.csdn.net/crazyquhezheng/article/details/49154805

PART III – Hi58的总结

ROS的tf坐标系,最终都要归结为三个标准框架,可以解决许多常见的机器人问题:
1. 全局不准确,但局部光滑框架(odom)
2. 全局准确,但局部不连续的帧(map)
3. 机器人自身框架(base_link)

The odom pose is the /base_link frame pose relative to /odom frame.
IMU and encoders provide the odom pose which drifts over time and thus only right for a short time.
odom frame is a pseudo-global reference frame in which a dead reckoning position and orientation estimate is represented.

The absolute/global pose is the /base_link frame pose relative to /map frame.
GPS, amcl and indoor position system provide the absolute/global pose.

got odom pose means you got the tf odom->base_link,
got absolute/global pose means you got map->base_link,

To correct the robot location, you have to provide the tf map->odom,
which can be calculated from odom->base_link – map->base_link.

例如在 hector_slam_launch:

*1. publishes the map->odom transform:

*2 do not require the use of a odom frame (for example because your platform does not provide any usable odometry) ,
you can directly publish a transformation from map to base_link:

*3 it can also be used without broadcasting any tf transformation.
This can be useful if another node is responsible for publishing the map->odom or map->base_frame transform.

PART IV – map-> odom的作用

In order to run robot localization and model the drifts of the robot while it is navigating, a transform between the frame map and the frame odom was introduced.
At the beginning map and odom frame are overlapping.
While the robot navigates and localizes (using amcl for example) it will correct its drift but it will not do this correction by changing its pose in the odom frame (this pose published under the topic /odom).
It will update the transform between map and odom frames such that when you chain the transforms to get the pose of the robot in the map frame, you will get the corrected pose (thus the transform between map and odom frames represents the offset in the robot’s pose that is given in the odom frame).
Do not confuse the frame odom with the robot’s pose published under the topic /odom.
The frame odom is just a coordinate system where the robot has to be located. This location of the robot would then be the coordinates of base_link in the odom frame. These coordinates are published in the /odom topic.
So when you turn on the robot, base_link and odom are overlapping as the robot’s pose is zero at the beginning.
But once the robot’s wheels start rotating, base_link will get away from odom.
So base_link is a mobile frame and odom a fixed one.

1.
In the beginning, we assume that the origin of the world coordinate system and the origin of odometry are the same.
https://qiita-image-store.s3.amazonaws.com/0/110138/0e9bfbe3-8061-405c-c26b-191f2a87b0c4.png

2.
Then tobot move:
https://qiita-image-store.s3.amazonaws.com/0/110138/f35f03da-a3b5-f959-363d-c9e1a26f4aed.png

3.
However, in fact, due to accumulation of various disturbances, the origin of the world coordinate system and odometry will deviate.
https://qiita-image-store.s3.amazonaws.com/0/110138/40a3eada-b7ed-a304-3f74-3e7cdeaea151.png
Therefore, by matching the sensor information and the map information, we come to the idea of ​​correcting the deviation between the origin of the world coordinate system and the origin of odometry. The package for that will be amcl .

智能机器人(73):ROS的TF-transform(02)

9. tf frame

抽象层面上,变换其实就是一种“偏移”(包括平移和旋转),代表了不同坐标系之间的变换和旋转。
在ROS中坐标系是3维的,用右手表示的,即食指X轴指向前方,其余四指Y轴指向左方,拇指Z轴指向上方。
许多ROS软件包都要使用TF软件功能包,以机器人识别的变换树的形式发布。

在tf中,两个坐标系的关系(也就是转换信息),用一个6自由度的相对位姿表示:
平移量(translation) + 旋转量(rotation)。类型分别是Vector3 和Quaternion 。
简单说tf类中定义了两个刚体之间的旋转与平移矩阵,并且重载了乘法运算符,这样就可以通过相乘两个tf来沿着tf树的方向求末段执行器相对世界坐标的位置与方向.

Let’s choose the “base_link” coordinat frame as the parent. This means the transform associated with the edge connecting “base_link” and “base_laser” should be (x: 0.1m, y: 0.0m, z: 0.2m).
For example beow shows that object in base-laser frame is (x: 0.3m, y: 0.0m, z: 0.0m) ,
例如:

and same object in base-link frame is (x: 0.4m, y: 0.0m, z: 0.2m).

9.1 TF软件包,最主要的是坐标转换的生产和消费。

TF基本原理是TransformBroadcaster(tb)生产信息,TransformListener(tl)消费信息。
所有的tb会发布某一特定的parent到child的变换,而所有tl会收到所有的这些变换,然后tl利用一个 tfbuffercore的数据结构维护一个完整的树结构及其状态。
因此,只要是一个tl,就要跟所有tb建立连接,就要收取所有的tf消息,来维护一颗完整的树并且搜索这棵树从而找到一条变换的路径,然后乘呀乘,每次都要如此。

广播树:
TF树结构的建立和维护是靠tf提供的tfbroadcastor的sendtransform接口。
tb发布一个从已有的parent frame到新的child frame的坐标系变换时,这棵树就会添加一个树枝,之后就是维护。
监听树:
用tf的tflisener监听某一个指定的从一个a frame到b frame的变换即可,当然前提是树上的树杈能把a,b联通。
这个变换是a frame->到b frame的变换,也表示了b frame在a frame的描述,也代表了一个在b frame里的点的坐标变换成在a frame里的坐标的坐标变换。

还是生产和消费好:

生产:
TransformBroadcaster有一个方法sendTransform发布坐标系1到坐标系2的旋转算子。
消费:
TransformListener有一个方法transformPoint用来变换坐标。
TransformListener有一个方法lookupTransform直接使用算子。

911. 生产
TransformBroadcaster有一个方法sendTransform发布坐标系1到坐标系2的旋转算子。

tf::TransformBroadcaster br;
tf::Quaternion q;//(x,y,z,w)
tf::Vector3 p; //(x,y,z)
tf::Transform ts; //(Quaternion(x,y,z,w), tf::Vector3(x,y,z))
tf::StampedTransform(ts, ros::Time::now(), “world”,”t1″)

那么这个这个发布:
br.sendTransform( tf::StampedTransform(ts, ros::Time::now(), “world”,”t1″) );
就是表明了t1坐标系在world坐标系的信息,评议是p:xyz适量所描述的那样,旋转是q:xyzw四元数所描述的那样。
也是说,word坐标系–>变换到t1坐标系的旋转算子就是【q,p】。
或者说,已知t1坐标系中的某点pont,其在world坐标系中的坐标就是【q,p】乘point。

再例如常见的,base_laser的激光安装在base_link的前方x=0.1m、左右正中心y=0、上方z=0.2m处的发布:
br.sendTransform( tf::TransformStamped ( tf::transform( tf::Quaternion(0,0,0,1), tf::Vector3(0.1,0,0.2), ros::time()::now(), “base_link”, “base_laser”) );

那么就是表明了base_laser激光坐标系base_link基坐标系的信息,平移是(0.1, 0.0, 0.2)适量所描述的那样, 旋转是(0,0,0,1)四元数所描述的那样。
也是说,base_link坐标系–>变换到base_laser坐标系的旋转算子就是【q,p】。
或者说,由base_laser激光坐标系扫描的数据点pont,其在base_link基坐标系中的坐标就是【q,p】乘point。

=== 例子 ===
某个机器人只有一个基本的移动机体,以及,挂在机体上方的激光。
这就定义了两个坐标系:一个对应于机体中心点的坐标系,一个对应于扫描仪中心的坐标系,分别取名为“base_link”和“baser_laser。

假设已经从传感器获取了一些数据,以一种代表了障碍物体到扫描仪中心点的距离的形式给出。
换句话说,已经有了一些“base_laser”坐标系的数据。
现在,期望通过这些数据,来帮助机器人避开物理世界的障碍物。
此处成功的关键是,需要一种方式,把传感器扫描的数据,从“base_laser”坐标系转换到“base_link”坐标系中去。
本质上,就是定义一种两个坐标系的关系。

为了定义这种关系,假设激光是挂在机体中心的前方10cm,高度20cm处,可以理解成传感器到机体中心的向量(0.1,0.0,0.2),这就等于给了一种转换的偏移关系。
具体来说,就是,从传感器到机体的坐标转换关系应该为(x:0.1m,y:0.0m, z:0.2m),相反的转换即是(x:-0.1m,y:0.0m,z:0.2m)。

基于该简单的例子的需求,需要创建两个frame,一个“base_link”,一个是“base_laser”。
为了定义两者的关系,首先需要决定谁是parent,谁是child。
时刻记得,由于tf假设所有的转换都是从parent到child的,因此谁是parent是有差别的。
这里选择“base_link”坐标系作为parent,其他的传感器等,都是被添加进robot的,对于“base_link”和“base_laser”他们来说,是最适合的。
这就意味着转换关系的表达式应该是(x:0.1m,y0.0m,z:0.2m)。

关系建立后,在收到“base_laser”的数据到“base_link”的转换过程,就可以是简单的调用tf库即可完成。
机器人就可以利用这些信息,在“base_link”坐标系中,就可以推理出传感器扫描出的数据,并可安全的规划路径和避障等工作。
以上层来描述“base_laser”坐标系的点,来转换到”base_link”坐标系。

9.2 相应代码

921. 生产
TransformBroadcaster有一个方法sendTransform发布坐标系1到坐标系2的旋转算子。
922 消费方法一
TransformListener有一个方法transformPoint用来变换坐标。
923 消费方法二
TransformListener有一个方法lookupTransform直接使用算子。

921. 生产
TransformBroadcaster有一个方法sendTransform发布坐标系1到坐标系2的旋转算子。

ros::NodeHandle n;
ros::Rate r(100);

tf::TransformBroadcaster br;
//create a TransformBroadcaster object to send base_link → base_laser transform

while(n.ok()){
br.sendTransform( tf::TransformStamped ( tf::transform( tf::Quaternion(0,0,0,1), tf::Vector3(0.1,0,0.2), ros::time()::now(), “base_link”, “base_laser”) );
r.sleep();
}

HINTS:
broadcaster.sendTransform() Sending a transform with a TransformBroadcaster requires five arguments need 4 params:
PARAM1 = tf::StampedTransform( PARAM1=tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0.0, 0.2)),
PARAM2=ros::Time::now(),
PARAM3=”base_link”,
PARAM4=”base_laser”
PARAM1:
First, we pass in the rotation transform, which is specified by a btQuaternion for any rotation that needs to occur between the two coordinate frames.
In this case, we want to apply no rotation, so we send in a btQuaternion constructed from pitch, roll, and yaw values equal to zero.
Second, a btVector3 for any translation that we’d like to apply. We do, however, want to apply a translation, so we create a btVector3 corresponding to the laser’s x offset of 10cm and z offset of 20cm from the robot base.
And, we need to give the transform being published a timestamp, we’ll just stamp it with ros::Time::now().
And, We need to pass the name of the parent node of the link we’re creating, in this case “base_link.”
And, we need to pass the name of the child node of the link we’re creating, in this case “base_laser.”

922 消费方法一
TransformListener有一个方法transformPoint用来变换坐标。
这是建立了一个定时器,定时把base_laser坐标系的数据转换到base-link坐标系里使用。

#include <tf/transform_listener.h>
// 作用: 将“base_laser”坐标系的点,变换到“base_link”坐标系中。

ros::NodeHandle n;
tf::TransformListener listener(ros::Duration(10));

//transform a point once every second
ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));
ros::spin();
//这个函数将会以ros::Timer定义的周期,作为一个回调函数周期调用。目前周期是1s

void transformPoint(const tf::TransformListener& listener)
//创建一个虚拟点,作为geometry_msgs::PointStamped。
//消息名字最后的”Stamped”的意义是,它包含了一个头部,允许我们去把时间戳和消息的frame_id相关关联起来。
geometry_msgs::PointStamped laser_point;

//关联frame_id也就是将node定义为frame_id
laser_point.header.frame_id = “base_laser”;

//设置laser_point的时间戳为ros::time(),即是允许我们请求TransformListener取得最新的变换数据
laser_point.header.stamp = ros::Time();

//伪造几个虚拟的点,即所需要变换过去的数据
laser_point.point.x = 1.1;
laser_point.point.y = 2.2;
laser_point.point.z = 3.3;

geometry_msgs::PointStamped base_point;

//通过TransformListener对象,调用transformPoint(),填充三个参数来进行数据变换
listener.transformPoint(“base_link”, laser_point, base_point);
//arg1,代表想要变换到的目标坐标系的名字。
//arg2,填充需要变换的原始坐标系的点对象。
//arg3,目标坐标系的点对象。
… …

ROS_INFO(“base_laser: (%.2f, %.2f. %.2f) —–> base_link: (%.2f, %.2f, %.2f) at time %.2f”,
laser_point.point.x, laser_point.point.y, laser_point.point.z,
base_point.point.x, base_point.point.y, base_point.point.z, base_point.header.stamp.toSec());
//THEN base_point should be (1.1, 2, 3.2).

923 消费方法二
TransformListener有一个方法lookupTransform直接使用算子。

ros::Publisher base_laser_vel = node.advertise(“base_laser/cmd_vel”, 10); // to control

tf::TransformListener listener;

ros::Rate rate(10.0);
while (node.ok()){
try {
listener.waitForTransform(“/base_link”, “/base_laser”, ros::Time(0), ros::Duration(10.0) );
listener.lookupTransform(“/base_link”, “/base_laser”, ros::Time(0), transform );
} catch (tf::TransformException &ex) {
ROS_ERROR(“%s”,ex.what());
}

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));
base_laser_vel.publish(vel_msg);
//while transform of t2 in t1 is iavailable then cal new linear and angular data for turtle2
//based on its distance and angle from turtle1
//New velocity is published in the topic “turtle2/cmd_vel”, t2 = base_laser
//HINTS: turtle2 is the dest child we needed, tutlr1 is the source parent we based.

rate.sleep();
}
这个是一旦等到”/base_link”, “/base_laser的变换可用,就取出这个transform,根据base_laser的数据信息控制base_link行为。

9.3. 发布变换的几种方式

931 常见方式的代码:

#include<tf/transform_broadcaster.h>
void posecallback(turtlesim::PoseConstPtr &msg)

static tf::TransformBroadcaster br;

//创建Transform存储变换相关信息,它包含旋转和位移的信息,有一个向量Vector3表示坐标,以及四元组表示方向。
tf::Transform transform;

//创建四元组
tf::Quaternion q;
//调用q的方法,绕着z轴旋转,有下面参数形式
q.setRPY(0,0,msg->theta);
//填充transform
transform.setOrigin(tf::Vector3(msg->x,msg->y,0));
transform.setRotation(q);

//创建一个transform::stamped对象,广播出去
br.sendTransform(tf::StampedTransform(transform,ros::Time::now(),”world”,”turtle1″));


}
解释直接在代码了。

932 其实变换可以直接用四元数:
transform.setOrigin( tf::Vector3(0.0, 0.0, 0.0) );
transform.setRotation( tf::Quaternion(0, 0, 0, 1) );
br.sendTransform(tf::StampedTransform(transform,ros::Time::now(), “world”, “turtle1″)
这三句话分别做了以下工作:
设置turtle1在world坐标系下的坐标原点
设置turtle1相对于world的旋转角度,这里用四元数表示
发送变换信息

933 上面这种四元数表示旋转角度的方式不太直观,写代码的时候一般不想将旋转变换换算成四元数,
大部分采用前面代码中的下方法写这个变换:
tf::Quaternion q;
q.setRPY(0, 0, msg->theta);
transform.setOrigin( tf::Vector3(msg->x, msg->y, 0.0) );
transform.setRotation(q);
br.sendTransform(tf::StampedTransform(transform,ros::Time::now(),”world”,”turtle1″));
这三句话,直接用RPY(分别对应绕XYZ轴旋转角度)来设置旋转变换了

934 还有一种使用静态变换:
static_transform_publisher工具的功能是发布两个参考系之间的静态坐标变换,两个参考系一般不发生相对位置变化。
static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms
static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period_in_ms
以上两种命令格式,需要设置坐标的偏移和旋转参数。
偏移参数都使用相对于xyz三轴的坐标位移。
而旋转参数,第一种命令格式使用以弧度为单位的 yaw/pitch/roll三个角度,第二种命令格式使用四元数表达旋转角度。
发布频率以ms为单位,一般100ms比较合适。
Publish a static coordinate transform to tf using an x/y/z offset in meters and yaw/pitch/roll in radians. (yaw is rotation about Z, pitch is rotation about Y, and roll is rotation about X). The period, in milliseconds, specifies how often to send a transform. 100ms (10hz) is a good value.

935 br.sendTransform(tf::StampedTransform(transform,ros::Time::now(), “world”, “turtle1”)
这种发布都是完成一个工作, 表明t1坐标系相对于world坐标系的位置关系,是旋转角度或四元数所描述的那样。
这样,如果t1坐标系里面有激光或里程计发布数据, 位于world和t1坐标系之外的其他坐标系,即可获得任何可能的坐标系下面的激光或历程数据。

智能机器人(71):ROS的TF-transform(01)

PART I ====== 变换矩阵
PART II ====== 欧拉角
PART III ====== 四元数
PART IV ====== 坐标系:空间描述与变换

PART I ====== 变换矩阵

1. 二维的平移操作

一般,可以将平移、旋转、缩放操作用矩阵表示。但是,使用2×2的变换矩阵是没有办法描述平移、旋转变换中的二维平移操作的;同样,3×3矩阵也没法描述三维的平移操作。
所以,为了统一描述二维中的平移、旋转、缩放操作,需要引入3×3矩阵形式;同理,使用4×4的矩阵才能统一描述三维的变换。
因此,用齐次坐标(Homogeneous coordinates)描述点和向量。

对于二维平移,如下图所示:

P点经过x和y方向的平移到P’点,可以得到:
x′=x+tx
y′=y+ty
由于引入了齐次坐标,在描述二维坐标的时候,使用(x,y,w)的方式(一般w=1)。
于是,可以写成下面矩阵形式:
x′=1,0,tx—–x
y′=0,1,ty—–y
w’=0,0,1—–w
也就是说平移矩阵是
1,0,tx
0,1,ty
0,0,1

2. 二维的绕原点旋转操作

首先明确,在二维中,旋转是绕着一个点进行,在三维中,旋转是绕着某一个轴进行。

最简单的,二维中的旋转是绕着坐标原点进行的旋转,如下图所示,点v 绕坐标原点旋转θ 角,得到点v’:

假设,v点的坐标是(x, y) ,那么经过推导可以得到,v’点的坐标(x’, y’)
增加一些中间变量: 设原点到v点的距离为r,设原点到v点的向量与x轴的夹角为ϕ,则有:
x=rcosϕ
y=rsinϕ

x′=rcos(θ+ϕ)
y′=rsin(θ+ϕ)
通过三角函数展开得到
x′=rcosθcosϕ−rsinθsinϕ
y′=rsinθcosϕ+rcosθsinϕ
带入x和y的表达,得到:
x′=xcosθ−ysinθ
y′=xsinθ+ycosθ
写成矩阵形式,为:
x′ = [cosθ, -sinθ]—-x
y′ = [sinθ, cosθ]—–y
引入了齐次坐标,扩展为3×3形式,则绕原点旋转的齐次矩阵为:
cosθ, -sinθ,0
sinθ, cosθ,0
0,0,1

3. 二维的绕任意点旋转操作

绕原点旋转,是二维旋转最基本的情况。当需要进行绕任意点旋转时,可以转换到这种基本情况的绕原点旋转,思路如下:
1. 首先将这任意旋转点平移过来,到坐标原点处;
2. 执行最简单的绕坐标原点的旋转;
3. 最后将这任意旋转点平移回去,到原来的位置。
也就是说在处理绕任意点旋转的情况下,需要额外在开头和末尾执行两次平移的操作,中间才是真正的旋转。

假设平移的矩阵是T(x,y),也就是说我们需要得到的坐标 v’ = T(x,y)*R*T(-x,-y)
(采用列坐标描述点的坐标,因此是左乘:首先执行T(-x,-y)… 依次向左进行。)
这样就很容易得出二维中绕任意点旋转操作的旋转矩阵了,即只需要把三个矩阵乘起来即可:
M=
⎡⎣⎢100010txty1⎤⎦⎥∗⎡⎣⎢cosθsinθ0−sinθcosθ0001⎤⎦⎥∗⎡⎣⎢100010−tx−ty1⎤⎦⎥=⎡⎣⎢cosθsinθ0−sinθcosθ0(1−cosθ)tx+ty∗sinθ(1−cosθ)ty−tx∗sinθ1⎤⎦⎥

对照平移和旋转的矩阵可以看出:
这个3×3矩阵的前2×2部分是和旋转相关的,
第三列是与平移相关。

4. 三维的基本旋转

首先明确,在二维中旋转是绕着一个点进行,在三维中就是绕着某一个轴进行。
三维的方向,可以采用右手坐标系:同时旋转角度的正负,也遵循右手坐标系:如下图所示:

一个三维的旋转,可以转换为绕基本坐标轴的旋转。
因此,首先要讨论一下绕三个坐标值x、y、z的旋转。

4.1. 绕X轴的旋转
在三维中,一个点P(x,y,z)绕x轴旋转θ角,到点P’(x’,y’,z’)。
由于是绕x轴进行的旋转,因此x坐标保持不变,在y和z组成的yoz平面上进行一个二维旋转(y轴类似于二维旋转中的x轴,z轴类似于二维旋转中的y轴),于是降维后有:
x′=x
y′=ycosθ−zsinθ
z′=ysinθ+zcosθ

4.2. 绕Y轴旋转
绕Y轴的旋转和绕X轴的旋转类似,Y坐标保持不变,除Y轴之外,ZOX组成的平面进行一次二维的旋转(Z轴类似于二维旋转的X轴,X轴类似于二维旋转中的Y轴),同样有:
x′=zsinθ+xcosθ
y′=y
z′=zcosθ−xsinθ
注意这里是ZOX,而不是XOZ,观察右手系的图片可以了解到这一点。

4.3. 绕Z轴旋转
与上面类似,绕Z轴旋转,Z坐标保持不变,xoy组成的平面内正好进行一次二维旋转
(和上面旋转的情况完全一样)自由度

4.4. 三维旋转操作总结
可以将绕X、Y和Z坐标轴的旋转矩阵分别记为 Rx(α),Ry(β),Rz(θ),则有:

5. 三维的绕任意轴旋转

绕任意轴的三维旋转,可以使用类似二维的绕任意点旋转一样,将旋转分解为一些列基本的旋转。
对于点P,绕任意向量u,旋转角度θ,得到点Q,如果已知P点和向量u如何求Q点的坐标?如下图所示:

可以把向量u进行一些旋转,让它与z轴重合,之后旋转P到Q就作了一次绕Z轴的三维基本旋转,然后,再执行反向的旋转,将向量u变回到它原来的方向,也就是说需要进行的操作如下:
1. 将旋转轴u绕x轴旋转至xoz平面
2. 将旋转轴u绕y轴旋转至于z轴重合
3. 绕z轴旋转θ角 !
4. 执行步骤2的逆过程
5. 执行步骤1的逆过程

5.0. 原始的旋转轴u如下图所示:

5.1. 第1、2、3步骤如下图所示:



5.2.分步解析
步骤1将向量u旋转至xoz平面的操作是一个绕x轴的旋转操作,步骤2将向量u旋转到与z轴重合,
第1、2步骤的示意图如下:

作点P在yoz平面的投影点q,q的坐标是(0, b, c),原点o与q点的连线oq和z轴的夹角就是u绕x轴旋转的角度。通过这次旋转使得u向量旋转到xoz平面(图中的or向量)
【步骤1】
过r点作z轴的垂线,or与z轴的夹角为β, 这个角度就是绕Y轴旋转的角度,通过这次旋转使得u向量旋转到与z轴重合
【步骤2】

步骤1中绕x轴旋转的是一次基本的绕x轴的三维旋转,旋转矩阵是:(注意α角度是绕x旋转的正向的角度)
旋转矩阵(记作 Rx(α))为:
在完成步骤1之后,向量u被变换到了r的位置,继续步骤2的操作,绕y轴旋转负向的β角,经过这次变换之后向量u与z轴完全重合,这一步也是执行的一次绕Y轴的基本旋转,
旋转矩阵(记作 Ry(−β))为:

在完成前面两个步骤之后,u方向和z轴完全重合,因此执行旋转θ角,执行的是一次绕z轴的基本三维旋转(记作 R(θ))。

最后两步骤,是前面1和2的逆操作,也就是绕Y轴旋转β,和,绕X轴旋转−α,这两个矩阵分别记作 Ry(β) 和 Rx(−α)。

最终得到绕任意轴u旋转的旋转矩阵是:
M=Rx(−α)Ry(β)Rz(θ)Ry(−β)Rx(α)
(因为使用的列向量,因此执行的是左乘,从右往左)

(注意:上面的(u,v,w),对应向量(a,b,c) 。)

如果向量是经过单位化的(单位向量),那么有a2+b2+c2=1,可以简化上述的公式,得到:

PART II ====== 欧拉角

6. 欧拉角

上面讨论了绕三条坐标轴旋转的旋转矩阵,旋转矩阵C 一般形式为:
【c11,c21,c31】
【c12,c22.c32】
【c13,c23,c33】
(这里没有用齐次坐标)
(直角坐标系的三个坐标轴方向的单位向量,实际上是一组标准正交基,旋转矩阵C 是一个正交矩阵。
所以, 旋转矩阵表面上看起来有 9 个参数,实际上只有三个是独立的,另外6个有约束。)

该旋转矩阵C 的三个列向量,实际对应着,原坐标系三个坐标轴方向的单位向量在旋转后的新坐标系下的坐标。

为了更直接地指出这三个独立参数,欧拉(Euler)证明了如下事实:
任何一个旋转都可以由连续施行的三次绕轴旋转来实现,这三次绕轴旋转的旋转角就是三个独立参数,称为欧拉角。
欧拉角之所以可以用来描述旋转是来自于欧拉旋转定理:任何一个旋转都可以用三个绕轴旋转的参数来表示。

定义一个欧拉角,需要明确的内容包括:
1. 三个旋转角的组合方式(是xyz还是yzx还是zxy)
2. 旋转角度的参考坐标系统(旋转是相对于固定的坐标系 还是相对于自身的坐标系)
3. 使用旋转角度是左手系还是右手系
4. 三个旋转角的记法
不同人描述的欧拉角的旋转轴和旋转的顺序都可能是不一样的。
当使用其他人提供的欧拉角的实现时,需要首先搞清楚他用的是那种约定。
根据绕轴旋转的顺序不同,欧拉角的表示也不同。

关于描述坐标系{B}相对于参考坐标系{A}的姿态有两种方式。
* 第一种是绕固定(参考)坐标轴旋转:
假设开始两个坐标系重合,先将{B}绕{A}的X轴旋转γ,然后绕{A}的Y轴旋转β,最后绕{A}的Z轴旋转α,就能旋转到当前姿态。
可以称其为X-Y-Z fixed angles或RPY角(Roll, Pitch, Yaw)。
* 另一种姿态描述方式是绕自身坐标轴旋转:
假设开始两个坐标系重合,先将{B}绕自身的Z轴旋转α,然后绕Y轴旋转β,最后绕X轴旋转γ,就能旋转到当前姿态。
称其为Z-Y-X欧拉角,由于是绕自身坐标轴进行旋转。

ROS的TF是前者

6.1 常见的欧拉角表示有 Yaw-Pitch-Roll (Y-X-Z顺序),通过下面的图片可以形象地进行理解。
Yaw(偏航):欧拉角向量的y轴
Pitch(俯仰):欧拉角向量的x轴
Roll(翻滚): 欧拉角向量的z轴

6.2 ROS的TF-frame里,
采用欧拉角RPY,RPY指的是绕固定坐标系xyz旋转。
Roll(滚转角)Pitch(俯仰角)Yaw(偏航角)分别对应绕XYZ轴旋转。

Roll:横滚

Pitch: 俯仰

Yaw: 偏航

设Roll、Yaw 、Pitch 三个角度分别为 φ、ψ 、θ,那么利用欧拉角进行旋转对应的旋转变换矩阵为:
【cosψ cosθ−sinψ cosφ sinθcosψ sinθ+sinψ cosφ】
【cosθsinψ sinφ−sinψ cosθ−cosψ cosφ sinθ−sinψ sinθ+cosψ 】
【cosφ cosθcosψ sinφsinφ sinθ−sinφ cosθcosφ】
实际上 Roll/Pitch/Yaw的旋转就分别对应着前面给出的旋转矩阵 Rx(),Ry(),Rz(),上面矩阵就是这三个矩阵的复合。

6.3
旋转角的记法
顺序——-飞行器———-望远镜——符号——角速度
第一——heading——-azimuth——–θ——–yaw
第二——attitude——elevation——ϕ——–pitch
第三——bank———–tilt————-ψ——–roll

6.4
欧拉角的好处是简单、容易理解,但使用它作为旋转的工具有严重的缺陷—万向节死锁(Gimbal Lock)。万向节死锁是指物体的两个旋转轴指向同一个方向。
实际上,当两个旋转轴平行时,万向节锁现象发生了,换句话说,绕一个轴旋转可能会覆盖住另一个轴的旋转,从而失去一维自由度。

PART III ====== 四元数

7. 连续的旋转

假设对物体进行一次欧拉角描述的旋转,三个欧拉角分别是(a1,a2,a3);之后再进行一次旋转,三个欧拉角描述是(b1,b2,b3);那么能否只用一次旋转(欧拉角描述为(c1,c2,c3)),来达到这两次旋转相同的效果呢?

这样是非常困难的,不能够仅仅使用(a1+b1,a2+b2,b3+b3)来得到这三个角度。
一般来说,需要将欧拉角转换成前面的旋转矩阵或者后面的四元数来进行连续旋转的叠加计算,之后再转换回欧拉角。
但是这样做的次数多了可能会引入很大的误差导致旋转结果出错。比较好的方案是直接使用旋转矩阵或四元数来计算这类问题。

四元数的一个重要应用是用它来描述三维旋转,四元数从某种意义上来说是四维空间的旋转,难以想象,了解它的结论和使用场景更加重要。

7.1
四元数的由来和复数很很大的关系,因此首先讨论一下关于复数的内容。复数中一个比较重要的概念是共轭复数,将复数的虚部取相反数,得到它的共轭复数:
z=a+biz∗=a−bi

当使用i去乘以一个复数时,把得到的结果绘制在复平面上时,发现得到的位置正好是绕原点旋转90度的效果。

于是可以猜测,复数的乘法,和,旋转之间应该有某些关系,例如:
定义一个复数q , 使用q作为一个旋转的因子
q=cosθ+isinθ

写成矩阵的形式是:
a′–[cosθsinθ]—–[a]
b′–[−sinθcosθ]—-[b]
这个公式正好是二维空间的旋转公式,当把新的到的(a′+b′i)绘制在复平面上时,得到的正好是原来的点(a+bi)旋转θ角之后的位置

7.2
既然使用复数的乘法可以描述二维的旋转,那么拓展一个维度是否能表示三维旋转呢?这个也正是四元数发明者William Hamilton最初的想法,也就是说使用
z=a+ib+jc
i2=j2=−1
但是很遗憾 三维的复数的乘法并不是闭合的。也就是说有可能两个值相乘得到的结果并不是三维的复数。
William Hamilton终于意识到自己所需要的运算在三维空间中是不可能实现的,但在四维空间中是可以的。

四元数是另一种描述三维旋转的方式,四元数使用4个分量来描述旋转,四元数可以写成下面的方式:
q=xi+yj+zk +w
为了方便表示为
q=(x,y,z,w)=(v ,w)
其中v是向量,w是实数。
模为1的四元数称为单位四元数(Unit quaternions)。

注意:
这里四元数的表示形式和齐次坐标一样,但是它们之间没什么关系。
四元数常常用来表示旋转,将其理解为“w表示旋转角度,v表示旋转轴”是错误的,应“w与旋转角度有关,v与旋转轴有关”。

7.3
两四元数相加
A(a+bi+cj+dk) + B(e + fi + gj + hk) = C【 (a+e) + (b+f)i + (c+g)j + (d+h)k 】
两个四元数相减
(sa,va) – (sb,vb) = (sa-sb,va-vb)

7.4 构造四元数
欧拉定理告诉任意三维旋转都可以使用一个旋转向量和旋转角度来描述。因此四元数往往是使用旋转轴和旋转角来构造的:

a)绕向量u,旋转角度θ,构造四元数
u = (ux,uy,uz)=uxi+uyj+uzk
q = exp[θ/2(uxi+uyj+uzk)]
= cosθ/2 + (uxi+uyj+uzk)sinθ/2
所以,可以用一个四元数q=((x,y,z)sinθ/2, cosθ/2) 来执行一个旋转。

或者表述为,
如果有单位四元数 q = (u ⋅sinθ/2, cosθ/2) 的形式,那么该单位四元数可以表示绕轴 u 进行 θ 角的旋转。

b)从一个向量旋转到另一个向量,构造四元数

c)从四元数获取旋转矩阵和旋转角
设四元数是q = xi+yj+zk+w,那么旋转角度angle和旋转轴(a,b,c):
angle = 2 * acos(w)
a = x / sqrt(1-w*w)
b = y / sqrt(1-w*w)
c = z / sqrt(1-w*w)

PART IV ====== 坐标系:空间描述与变换

8. 刚体的姿态描述

刚体在空间中具有6个自由度,因此可以用6个变量描述一个刚体在空间中的位姿:
(x,y,z,alpha,beta,gamma)

这牵扯到两个坐标系:全局坐标系 和 固连在刚体上的本地坐标系。
而对应的坐标变换,也就是指同一空间向量相对于这两个坐标系的坐标之间的相互转换关系。

旋转矩阵与坐标系之间的坐标变换没有任何关系。
旋转矩阵所描述的,是坐标系的旋转运动,也就是怎样把全局坐标系旋转到本地坐标系上去的。
或者说,怎样把一个向量(坐标系其实就是三个向量)旋转到新的位置。
注意,这里说的向量旋转,是发生在一个坐标系下的事情。

坐标系旋转角度θ, 则等同于将目标点围绕坐标原点反方向旋转同样的角度θ。

8.1 可以推导两个坐标系之间坐标变换的方法。

对于空间向量P,在全局坐标系下坐标为(x0,y0,z0), 在局部坐标系下坐标为(x1,y1,z1),那么:
P = (i,j,k)(x0,y0,z0) = (i′,j′,k′)(x1,y1,z1) = R∗(i,j,k)(x1,y1,z1) = (i,j,k)∗R(x1,y1,z1)

对比左右两边,可以得出结论:
(x0,y0,z0)T = R∗(x1,y1,z1)T
POS_global = R_g−>l ∗ POS_local

即,点在全局的坐标,等于全局坐标系到局部坐标系的转换矩阵,乘以点在局部的坐标。

8.2 通用的空间描述与变换
更广泛的,有两个坐标系A和B,B坐标系中有一个点P,如何把B坐标系中的P映射到A坐标系呢,这涉及到空间描述与变换。
Ap表示p在A坐标系中的表达,Bp表示p在坐标系B中的表达。Aborig表达B坐标原点orig在A坐标系, 是平移量。
要想将Bp转换为A坐标系中的表达Ap,就需要乘以旋转矩阵R_A->B,是旋转量。
将B坐标系中的p点在A坐标系中进行表达:
Ap = R_A->B * Bp + Aboirg
中间的表达式可以成为旋转算子。
则各旋转矩阵可以里哟写成齐次坐标的形式如下
Ap = M * Bp

即,点在A的坐标,等于A坐标系到B坐标系的转换矩阵,乘以点在B的坐标。

8.3 具体到ROS的tf
有三个坐标系,一个世界坐标系world,已知坐标系known,一个未知坐标系query

要求得未知坐标系在世界坐标系当中的表达,可以用旋转算子来表示:

就说是: 未知坐标系在世界坐标系中的旋转算子 = 未知坐标系在已知坐标系中的旋转算子 * 已知坐标系在世界坐标系中的旋转算子