ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Why is inverse transform tf so wrong?

asked 2018-10-29 10:21:53 -0500

123aa gravatar image

updated 2018-10-30 07:22:31 -0500

While trying to get the base_link footprint of the robot in utm coordinates, we discovered hughe jumps in the utm position. But in the simulation, the real change was only in the millimeter range.

We finally found the issue to be that we asked the inverse transform instead of the transform as it was published. Why is the inverse transform so wrong and not precise at all?

Below are the two transforms

$ rosrun tf tf_echo utm base_footprint
At time 6573.400
- Translation: [-691212.171, -5333943.315, -0.000]
- Rotation: in Quaternion [-0.000, -0.000, 0.036, 0.999]
            in RPY (radian) [-0.000, -0.000, 0.071]
            in RPY (degree) [-0.000, -0.000, 4.076]
At time 6574.400
- Translation: [-691212.169, -5333943.315, 0.000]
- Rotation: in Quaternion [-0.000, -0.000, 0.036, 0.999]
            in RPY (radian) [-0.000, -0.000, 0.071]
            in RPY (degree) [-0.000, -0.000, 4.076]
At time 6575.400
- Translation: [-691212.168, -5333943.315, 0.000]
- Rotation: in Quaternion [-0.000, -0.000, 0.036, 0.999]
            in RPY (radian) [-0.000, -0.000, 0.071]
            in RPY (degree) [-0.000, -0.000, 4.076]


$ rosrun tf tf_echo base_footprint utm
At time 6578.400
- Translation: [1068621.327, 5271316.154, 0.000]
- Rotation: in Quaternion [0.000, -0.000, -0.036, 0.999]
            in RPY (radian) [0.000, 0.000, -0.071]
            in RPY (degree) [0.000, 0.000, -4.076]
At time 6579.400
- Translation: [1068617.849, 5271316.859, -0.000]
- Rotation: in Quaternion [-0.000, 0.000, -0.036, 0.999]
            in RPY (radian) [-0.000, 0.000, -0.071]
            in RPY (degree) [-0.000, 0.000, -4.076]
At time 6580.400
- Translation: [1068614.338, 5271317.570, -0.000]
- Rotation: in Quaternion [-0.000, 0.000, -0.036, 0.999]
            in RPY (radian) [-0.000, 0.000, -0.071]
            in RPY (degree) [-0.000, 0.000, -4.076]

The same issue persists when using f2_tools echo.py.

Any ideas how to fix this?

EDIT

Afer checking the ideas in the comments of @lucaw, I got these results:

$ rosrun tf2_ros static_transform_publisher -691212.171 -5333943.5 -0.000 -0.000 -0.000 0.036 0.999 a b

$ rosrun tf tf_echo a b
At time 0.000
- Translation: [-691212.171, -5333943.500, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.036, 0.999]
            in RPY (radian) [0.000, -0.000, 0.072]
            in RPY (degree) [0.000, -0.000, 4.128]
$ rosrun tf tf_echo b a
At time 0.000
- Translation: [1072594.515, 5266650.647, 0.000]
- Rotation: in Quaternion [0.000, 0.000, -0.036, 0.999]
            in RPY (radian) [0.000, 0.000, -0.072]
            in RPY (degree) [0.000, 0.000, -4.128]


And using euler:

$ rosrun tf2_ros static_transform_publisher -691212.171 -5333943.5 -0.000 -0.000 -0.000 0.036 a b
$ rosrun tf tf_echo a b
At time 0.000
- Translation: [-691212.171, -5333943.500, 0.000]
- Rotation: in Quaternion [0 ...
(more)
edit retag flag offensive close merge delete

Comments

Can you duplicate the issue with a static transform publisher like:

rosrun tf2_ros static_transform_publisher -691212.171 -5333943.5 -0.000 -0.000 -0.000 0.036 0.999 a b
rosrun tf2_tools echo.py a b
rosrun tf2_tools echo.py b a
lucasw gravatar image lucasw  ( 2018-10-29 11:37:09 -0500 )edit

When I enter the transform as rpy it seems fine (the echoed quaternion is -0.035 0 0 0.999 instead though), but using a quaternion as you have gets results like yours.

lucasw gravatar image lucasw  ( 2018-10-29 11:44:19 -0500 )edit

1 Answer

Sort by » oldest newest most voted
4

answered 2018-10-31 13:24:23 -0500

robustify gravatar image

The results of the inverse transform after rosrun tf tf_echo base_footprint utm are actually correct. When you invert a transform, the translation component isn't simply negated. Rather, the translation component of an inverse transform is:

t2 = -transpose(R) * t1

where R is the rotation matrix describing the orientation difference between frame 1 and 2, t1 is the translation component of the forward transform, and t2 is the translation component of the inverse transform.

If your quaternion were [0 0 0 1], then you would see a simple negation in the translation. However, because of the nonzero quaternion, the translation vector gets rotated as well as negated. The reason for this is because after the inverse transform, the translation vector is relative to a different reference frame that has a different orientation.

Also, the reason you are getting different results for the Euler angle test is because you are inputting a roll angle instead of a yaw angle. The sequence of the Euler angle arguments to the static_transform_publisher is yaw, pitch, roll.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2018-10-29 10:21:53 -0500

Seen: 3,522 times

Last updated: Oct 31 '18