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

Do the /odom topic and odom->base_link tf provide duplicate information?

asked 2016-11-24 14:36:38 -0500

tsbertalan gravatar image

updated 2016-11-25 14:33:03 -0500

I'm making a differential-drive rover with wheel encoders and planar LIDAR, but at the moment no other sensors. I understand why it's useful to have separate map and odom frames--if my wheel odometry was perfect, the transform between the two would be zero, but it's not, so mapping (gmapping at the moment) is needed to find ithe correcting transform. I've implemented a publisher of both nav_msgs.msg.Odometry as topic /odom and tf.TransformBroadcaster as a transform between odom and base_link, according to this tutorial.

However, it doesn't seem that the odom -> base_link transformation provides any information that isn't already present in my /odom topic. Are there other cases in which these would be different, and I'm just not very imaginative? Is the separate existence of the tf just for the (perhaps significant) convenience of having a homogeneous way to transform between odom and map frames? In that case, maybe it would be possible not to publish the /odom topic, since the only extra thing it has is velocities, which I just approximate as the difference from the last message over time increment.

FWIW, my code is here, and in particular this script contains the publisher of both the /odom topic and the broadcaster of the odom -> base_link transformation. I might later solicit comments on the larger project, but at the moment it's a bit disorganized because of a relatively recent jettisoning of Arduino as a bridge to hardware.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2016-11-25 08:44:32 -0500

lucasw gravatar image

updated 2017-12-01 07:58:47 -0500

http://wiki.ros.org/navigation/Tutori... says that tf doesn't provide velocity so the navigation stack also wants the Odometry message. tf does provide a lookupTwist function but it either is averaging the velocity over a time period or computing velocity from the last two position updates- the averaging could have a lot of latency or smooth over short duration velocities of interest, and only using the last updates could be noisy. So neither method can recover the instantaneous velocity of the odom message. http://answers.ros.org/question/12894...

It doesn't mention it but the Odom message also has position and velocity uncertainty information in the pose and twist covariance matrices- it is said to be optional but but a pose filtering scheme would make use of that when fusing odometry with imu or other sensor data. (There is an unmaintained tf version that propagates uncertainty http://wiki.ros.org/uncertain_tf , it would be great if this was revived in the future, and then later support multiple tf parents as well...)

If you have no current or potential subscribers to /odom in your project (doesn't gmapping want it or is it using only sensors?) then it could be eliminated, or made optional (Maybe someone else will want to hook your robot up to the nav stack- and does it really cost you much resources to keep publishing it?).

edit flag offensive delete link more

Comments

I see. In that case, maybe I should change the way I report vx, vy, vtheta. At the moment, they're indistinguishable from what you might get from tf, but I it might be useful to get the full noisy signal from within my encoder interrupt functions.

tsbertalan gravatar image tsbertalan  ( 2016-11-25 14:24:58 -0500 )edit

So in that case, is the being sent over the tf broadcaster redundant. I'm saying this as the the nav_msgs/odometry seems to have all the required information (velocity and the pose of the robot with covariance in the odom frame).

Karthikey97 gravatar image Karthikey97  ( 2017-11-30 23:53:59 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-11-24 14:36:38 -0500

Seen: 4,847 times

Last updated: Dec 01 '17