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

specific odom frame responsibility

asked 2015-12-15 08:24:35 -0500

codenotes gravatar image

updated 2015-12-15 10:36:51 -0500

lucasw gravatar image

I am trying to understand the responsibility I have with regards to publishing the odom TF frame. Specifically, we have a mobile robotic system that is intended to (and does) operate via ROS and are finalizing complete robotic control stack.

There is a lot written (and have read/reread) about the map --> odom --> base_link relationship. I understand that the odom frame is 1) where the robot starts in a map and 2) can "drift." But what I would like to understand is what, specifically, needs to be/should be done programatically to move the odom frame as my robot progresses. It seems to be my responsibility to translate what is going on into this "drift", and thus, I should publish a map->odom->base_link transform tree and should be "drifting" the odom frame? But how should this be done? Move it where and by how much relative to the uncertainty? Or am I not understanding: I often read that it is the localization nodes that publish the map->odom relationship.

(it also seems strange to me that, if I understand correctly, I am to drift the odom transform which is where the robot starts as opposed to base_link, where it is presently)

I understand that wheel odometry error and uncertainty accumulates as the robot moves and I too understand how calculate and keep track of that uncertainty. Again, seeking clarification on what one is supposed to do with that knowledge with regards to moving the odom frame? Where do I move it and by how much?

(Most of what is written on the subject [and there is a fair amount] is helpful if you are writing a client or trying to get a platform performing SLAM in gazebo, but it isn't clear how it is supposed to work if you are authoring the actual controlling components and stack. Have read rep 105, and all postings I can find on ROS answers, but would greatly appreciate some clarification.)

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
7

answered 2015-12-15 22:23:09 -0500

demmeln gravatar image

I'll try to answer your remaining question from your comment:

The only question that remains is this; a localizer will reposition/move the odom->base_link tree branch by placing it in the "correct" position in the map...but how does it position this branch exactly? Does it place the base_link on top of the corrected pose and odom shifts accordingly?

So a localization node like amcl typically localizes the base_link frame (or internally possibly directly a sensor frame such as laser_link instead), so lets assume for a time-stamp t (e.g. the laser message time stamp) it has computed the transformation map -> base_link. It then can look up the corresponding odometry estimate from tf as the odom -> base_link transformation at time t. By computing map -> odom = (map -> base_link) x inverse(odom -> base_link) it knows what to publish to tf as the map -> odom transformation.

You can think of map -> odom as the correction of the dirft of the odometry. Initially, when the robot is just starting and odom -> base_link is 0 (identity transformation), it simply corresponds to the starting position of the robot, which is the initial offset of odometry (which typically always starts with 0). As the robot moves, the odometry computed e.g. from wheel encoders accumulates error over time, i.e. odom -> base_link does not correctly estimate the robot position relative to the starting position, but rather drifts away from the correct value more and more. Localization algorithms such as amcl that reference the robot absolutely with respect to a map do not have this unbound dirft, so in each step they correct for the odometry drift by adjusting map -> odom a little more. In other words, map -> odom changes in correspondance to your odometry drift. The overall result is that combined transformation map -> odom -> base_link corresponds to the correct robot pose with respect to the map. The intermediate frame odom may drift away more and more, but until you eventually run into numerical issues, it does not matter, since any other nodes that want to know the true position of your robot will look up map -> base_link from TF and nodes that need a smooth relative estimate of the robot motion can observe how odom -> base_link changes over time.

edit flag offensive delete link more

Comments

Got it, have complete understanding now. Thank you sincerely.

codenotes gravatar image codenotes  ( 2015-12-16 10:29:19 -0500 )edit

Sure thing. Maybe you could mark one of the answers as accepted, such that it is clear to everyone that this is solved?

demmeln gravatar image demmeln  ( 2015-12-16 16:55:53 -0500 )edit

Better summary than the tutorials, I think.

Will Chamberlain gravatar image Will Chamberlain  ( 2017-03-19 23:46:17 -0500 )edit
6

answered 2015-12-15 14:11:48 -0500

codenotes gravatar image

I got an answer, thanks to Brian Gerkey for clarifying for me...posting here for reference of others.

In the map->odom->base_link relationship, it is the localization package's responsibility to publish a map->odom frame and NOT the robot controller's responsibility as I had thought. A robot stack builder's responsibility is to publish the odom->base_link, and the laser scan data. The localization engine (amcl or what have you) will consume /map (presuming a map_server instance is running), /scan (you are publishing laser scans) and the odom->base_link (where you think you are) TF. Amcl will then attempt to place the robot in the map and will place/move the odom frame accodingly in the map by publishing the map->odom transform.

odom frame may jump and move non-continuously, but base_link should move continuously within that odom->base_link frame. So the frame may jump, but the robot is always moving smoothing relative to the odom frame within odom->base_link.

The odom->base_link relationship is where one might be applying a kalman filter or other means to create the best possible guess of where the robot is relative to where it started. The localization engine will shift the entire relationship...I am guessing (and want to confirm) that it will align the base_link TF to where it localizes the robot to actually be on the map based on laser scans data. On rviz you'd see a shift or jump of the whole odom->base_link frame.

edit flag offensive delete link more

Comments

I think this is a fair summary. Does that answer all your questions, or are things still unclear?

demmeln gravatar image demmeln  ( 2015-12-15 16:57:45 -0500 )edit
1

Clear now. I would add that amcl will adjust the map<>odom branch and place such that base_link of odom<>base_link will align exactly in position and pose of its determination of where the robot is in the map. Further, it publishies amcl_pose as a separate message which will also align w base_link.

codenotes gravatar image codenotes  ( 2015-12-15 17:51:44 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2015-12-15 08:24:35 -0500

Seen: 2,684 times

Last updated: Dec 15 '15