[ros-users] pr2 odometry tf relationship backwards?

Tully Foote tfoote at willowgarage.com
Fri Dec 2 05:42:27 UTC 2011


Hi Ross,

This would be better asked on answers.ros.org we're transitioning ros-users
to being an announce and discussion list and trying to keep focused
questions on the QA site where it's easier for future people with the same
question to find the answers.

But as I'm mailing the list anyway here's your answer.  If you'd ask it
again on answers.ros.org I or someone else can fill it in there.

You are right that /odom is generally the parent of base_footprint.  The
standard is codified in REP 105.   http://www.ros.org/reps/rep-0105.html

The discrepancy in the pr2 is a bit of legacy thing where we learned from
the PR2 that we should do it differently, but don't want to break peoples
code so we haven't changed it.  The reason that odom is a child of
base_link is that there is odom_combined which is now the parent.  The
original version of robot_pose_ekf it used the "odom" frame to compute the
"odom_combined" frame by including the imu information. And to have both
frames one had to become a child, so the less accurate one was pushed
there.  By the time we realized that it wasn't needed anymore a lot of the
pr2 code had assumptions about "odom_combined"  We've worked hard to scrub
that out of pr2 independent packages but have not made the effort to remove
it from the pr2 specific packages yet.

Tully




On Thu, Dec 1, 2011 at 5:07 PM, Ross Knepper <rak at csail.mit.edu> wrote:

> Hi all,
>
> I am using the controller Pr2Odometry from the pr2_mechanism_controllers
> package to do simulated odometry for the KUKA YouBot in Gazebo.  I am
> seeing an oddity in the tf tree, and I'd like to find out whether it's
> something I'm doing.  It seems to me that there is a reversed parent/child
> relationship in the tf links published by Pr2Odometry.  The documentation
> for it at
>
>    http://www.ros.org/wiki/pr2_**mechanism_controllers/**
> Pr2Odometry#ROS_API<http://www.ros.org/wiki/pr2_mechanism_controllers/Pr2Odometry#ROS_API>
>
> says
>
>    /tf (tf/tfMessage)
>    Two transforms are published to tf, a constant transform from the
> base_footprint frame to the base_link frame and the transform from the odom
> frame to the base footprint frame.
>
> This conforms to my expectation, which is that /odom is the parent of
> /base_footprint.  Thus, if global localization drops out, you can still
> continue on odometry alone for as long as your dead reckoning will allow.
>  This expected behavior is also compatible with fake_localization, which
> publishes a transform from /map to /odom.
>
> By contrast, examining tf on the running system shows me a tree in which
> /base_footprint is at the root.  /odom is a leaf and a sibling of
> /base_link, which connects to the rest of the tree.  The code at
>
>    /opt/ros/electric/stacks/pr2_**controllers/pr2_mechanism_**
> controllers/src/pr2_odometry.**cpp
>
> is clear:
>
>      out.header.frame_id =  tf::resolve(tf_prefix_,base_**
> footprint_frame_);
>      out.child_frame_id = tf::resolve(tf_prefix_,odom_**frame_);
>
> So /odom is the child here.  This behavior seems to contradict intuition
> and the (admittedly terse) documentation online.  However, since I am using
> this pr2 code on the YouBot, I wonder if there is something different about
> how the PR2 operates?
>
> Thanks!
>
>  -ross
> ______________________________**_________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/**listinfo/ros-users<https://code.ros.org/mailman/listinfo/ros-users>
>



-- 
Tully Foote
Systems Engineer
Willow Garage, Inc.
tfoote at willowgarage.com
(650) 475-2827
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20111201/a28f7862/attachment-0004.html>


More information about the ros-users mailing list