[ros-users] REP-105, base_footprint and odom_combined

Wim Meeussen meeussen at willowgarage.com
Tue Sep 13 03:03:13 UTC 2011


> REP-105 [1] states that the coordinate frames for navigation should look
> like this:
>
>    map --> odom --> base_link
>
> ... where base_link can be an arbitrary link and does not have to lie in the
> ground plane.
>
> However, the PR2 specifies an additional virtual link, base_footprint, which
> lies below base_link in the ground plane. Moreover, robot_pose_ekf publishes
> transforms from odom_combined to base_footprint. All in all, the PR2's
> frames look like this (on Diamondback):
>
>    map --> odom_combined --> base_footprint --> base_link
>
> So, what is the best way to resolve this inconsistency when creating an own
> URDF model?
>   - Follow the REP? This unfortunately means that robot_pose_ekf cannot be
> used, since the transform from odom_combined to base_footprint is hard
> coded.
>   - Follow PR2's model? In that case, the REP should probably be updated.

The PR2 indeed does not follow the REP, which is unfortunate. We were
concerned that changing the name from odom_combined to odom would
break the code of many people.  For setting up your own robot, I'd
recommend following the REP and not the PR2.  Also note that the robot
pose ekf has a parameter called "output_frame" which allows you to
change the name of the 'odom_combined' frame.


> Also, what is the semantical meaning of odom_combined? From my experience,
> I'd say that the pure odometry publishes "odom -> base_link" (or
> base_footprint), and the EKF publishes "odom_combined -> base_link".
> However, since base_link can only have one parent, one has to switch off all
> but one of those TF publishers via a parameter. In that case, why not just
> call all of them "odom" (or "odom_combined")?

According to the REP:
"
The coordinate frame called odom is a world-fixed frame. The pose of a
mobile platform in the odom frame can drift over time, without any
bounds. This drift makes the odom frame useless as a long-term global
reference. 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.
In a typical setup the odom frame is computed based on an odometry
source, such as wheel odometry, visual odometry or an inertia
measurement unit.
The odom frame is useful as an accurate, short-term local reference,
but drift makes is a poor frame for long-term reference.
"

So it does not really matter what the source of the odometry
information is. It does not need to be limited to wheel-odometry only,
it could come from camera images, IMU, etc.  The only requirement is
that the odometry frame needs to be locally consistent and continuous.

Hope this helps,

Wim



-- 
--
Wim Meeussen
Willow Garage Inc.
<http://www.willowgarage.com)



More information about the ros-users mailing list