[ros-users] exception in transform listener

Tully Foote tfoote at willowgarage.com
Wed Jul 7 18:48:47 UTC 2010


Michal,
Thanks for you persistence, I have updated the tutorial to be more explicit
about this.

Tully

On Wed, Jul 7, 2010 at 4:24 AM, <Michal.Stolba at cis.strath.ac.uk> wrote:

> Hi Tully,
>
> well that's probably the problem, I've used it in a callback function, so
> it obviously didn't have any history.
>
> Meanwhile, I've solved the problem using this:
>
> if(transform_listener.waitForTransform ("map","base_footprint",
> ros::Time(0), ros::Duration(1.0))){
>
>  transform_listener.lookupTransform("map","base_footprint",ros::Time(0),
> base_footprint);
> }
>
> but I guess it would be better just to make the listener a member
> variable. Maybe it would be good idea to explicitly note this in the
> tutorial or description of the listener? I didn't have any idea that the
> listener works this way.
>
> Thanks very much for your help,
>
> Michal
>
> > Michal,
> > I have two more guesses for you.
> >
> > Most likely I think it could be a code issue.  Are you keeping the
> > TransformListener object in scope?  The TransformListener aggregates data
> > over time.  Immediately after you construct it it has zero data history.
> > It
> > relies on this history to build the tree and allow you to query it.  In
> > general it should be outside of any loops, and it is common practice to
> > make
> > the TransformListener a member variable of a class.
> >
> > It also could be a connectivity issue.  Are you running on multiple
> > computers? Could you run view_frames with the argument --node=FOO where
> > FOO
> > is the name of the node giving you the errors.
> >
> > Tully
> >
> > On Mon, Jul 5, 2010 at 8:02 AM, <Michal.Stolba at cis.strath.ac.uk> wrote:
> >
> >> Hi,
> >>
> >> thank you both.
> >>
> >> So far, I have tried roswtf and it found no problems:
> >>
> >> "running tf checks, this will take a second...
> >> ... tf checks complete"
> >>
> >> I'll try the second approach as well.
> >>
> >> Actually it's the other way round - the transform is rarely received
> >> correctly.
> >>
> >> Could the problem be in my code, something like asking for the transform
> >> when it's not available?
> >>
> >> Thanks very much,
> >>
> >> Michal
> >>
> >> > Michal,
> >> > I'd also suggest that you try running roswtf when things are running
> >> with
> >> > problems.  That has a tf plugin to try to help detect common problems.
> >> >
> >> > Tully
> >> >
> >> > On Fri, Jul 2, 2010 at 9:29 AM, Brian Gerkey
> >> > <gerkey at willowgarage.com>wrote:
> >> >
> >> >> hi Michal,
> >> >>
> >> >> The fact that it's only rarely received incorrectly is peculiar.
> >> >> Sounds like part of the system is occasionally, or slowly, publishing
> >> >> a conflicting transform.  I would log all the tf data during a run:
> >> >>  rosbag record tf
> >> >> Then search through the resulting bag for the problem.  Something
> >> like
> >> >> this will pull out all the messages that declare a transform with
> >> >> base_footprint as the child:
> >> >>  rosbag filter in.bag out.bag 'topic == "tf" and
> >> >> m.transforms[0].header.frame_id == "base_footprint"'
> >> >> (where in.bag should be replaced by the name of bag created by the
> >> >> record step).  You can examine the filtered data with rostopic:
> >> >>  rostopic echo -b out.bag tf
> >> >> Presumably, in that data stream, you'll see occasional conflicting
> >> >> declarations of the parent of base_footprint.
> >> >>
> >> >>        brian.
> >> >>
> >> >> On Fri, Jul 2, 2010 at 3:42 AM,  <Michal.Stolba at cis.strath.ac.uk>
> >> wrote:
> >> >> > Hi,
> >> >> >
> >> >> > thanks for the reply. Gmapping is configured with <param
> >> >> name="odom_frame"
> >> >> > value="odom_combined"/>
> >> >> >
> >> >> > i'm launching this configuration:
> >> >> >
> >> >> > <launch>
> >> >> >  <include file="$(find pr2_machine)/$(env ROBOT).machine" />
> >> >> >  <include file="$(find
> >> hi_level_navigation)/launch/slam_gmapping.xml"
> >> >> />
> >> >> >  <include file="$(find pr2_navigation_teleop)/teleop.xml" />
> >> >> >  <include file="$(find
> >> >> pr2_navigation_perception)/lasers_and_filters.xml"
> >> >> />
> >> >> >  <include file="$(find pr2_navigation_perception)/ground_plane.xml"
> >> />
> >> >> >  <include file="$(find pr2_navigation_slam)/move_base.xml" />
> >> >> > </launch>
> >> >> >
> >> >> > where slam_gmapping.xml is:
> >> >> >
> >> >> > <launch>
> >> >> >    <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping"
> >> >> > output="screen">
> >> >> >      <remap from="scan" to="base_scan"/>
> >> >> >      <param name="odom_frame" value="odom_combined"/>
> >> >> >      <param name="map_update_interval" value="5.0"/>
> >> >> >      <param name="maxUrange" value="16.0"/>
> >> >> >      <param name="sigma" value="0.05"/>
> >> >> >      <param name="kernelSize" value="1"/>
> >> >> >      <param name="lstep" value="0.05"/>
> >> >> >      <param name="astep" value="0.05"/>
> >> >> >      <param name="iterations" value="5"/>
> >> >> >      <param name="lsigma" value="0.075"/>
> >> >> >      <param name="ogain" value="3.0"/>
> >> >> >      <param name="lskip" value="0"/>
> >> >> >      <param name="srr" value="0.01"/>
> >> >> >      <param name="srt" value="0.02"/>
> >> >> >      <param name="str" value="0.01"/>
> >> >> >      <param name="stt" value="0.02"/>
> >> >> >      <param name="linearUpdate" value="1.0"/>
> >> >> >      <param name="angularUpdate" value="0.436"/>
> >> >> >      <param name="temporalUpdate" value="5.0"/>
> >> >> >      <param name="resampleThreshold" value="0.5"/>
> >> >> >      <param name="particles" value="80"/>
> >> >> >      <param name="xmin" value="-50.0"/>
> >> >> >      <param name="ymin" value="-50.0"/>
> >> >> >      <param name="xmax" value="50.0"/>
> >> >> >      <param name="ymax" value="50.0"/>
> >> >> >      <param name="delta" value="0.05"/>
> >> >> >      <param name="llsamplerange" value="0.01"/>
> >> >> >      <param name="llsamplestep" value="0.01"/>
> >> >> >      <param name="lasamplerange" value="0.005"/>
> >> >> >      <param name="lasamplestep" value="0.005"/>
> >> >> >    </node>
> >> >> > </launch>
> >> >> >
> >> >> > sometimes (quite rarely) the transform is received correctly.
> >> >> >
> >> >> > Thanks very much,
> >> >> >
> >> >> > Michal
> >> >> >
> >> >> >> Perhaps gmapping is configured with odom_frame == base_footprint?
> >> >> >>
> >> >> >>       brian.
> >> >> >>
> >> >> >> On Fri, Jun 25, 2010 at 10:32 AM, Wim Meeussen
> >> >> >> <meeussen at willowgarage.com> wrote:
> >> >> >>> Michal,
> >> >> >>>
> >> >> >>>> RESULTS: for /map to /base_footprint
> >> >> >>>> Chain is: /map -> /base_footprint -> /odom_combined
> >> >> >>>> Net delay     avg = 0.020768: max = 0.064
> >> >> >>>
> >> >> >>> [...]
> >> >> >>>
> >> >> >>>> the only weird thing is, that in rviz the transform arrows shows
> >> >> like
> >> >> >>>> this: /base_footprint -> /odom_combined -> /map
> >> >> >>>> might this be a sign of some problem?
> >> >> >>>
> >> >> >>> Yes, This is most likely your problem. It appears that you have a
> >> tf
> >> >> >>> publisher from map to base_footprint, and another publisher from
> >> >> >>> odom_combined to base_footprint. So the base_footprint frame has
> >> two
> >> >> >>> parents.  In our setup we have amcl publish the transform from
> >> map
> >> >> to
> >> >> >>> odom combined, and the robot pose ekf publish the transform from
> >> >> >>> odom_combined to base_footprint.  What setup are you running? Did
> >> >> you
> >> >> >>> reconfigure amcl to publish a different tf transform?
> >> >> >>>
> >> >> >>> Wim
> >> >> >>>
> >> >> >>>
> >> >> >>>
> >> >> >>>
> >> >> >>>
> >> >> >>> --
> >> >> >>> Wim Meeussen
> >> >> >>> Willow Garage Inc.
> >> >> >>> <http://www.willowgarage.com)
> >> >> >>> _______________________________________________
> >> >> >>> ros-users mailing list
> >> >> >>> ros-users at code.ros.org
> >> >> >>> https://code.ros.org/mailman/listinfo/ros-users
> >> >> >>>
> >> >> >> _______________________________________________
> >> >> >> ros-users mailing list
> >> >> >> ros-users at code.ros.org
> >> >> >> https://code.ros.org/mailman/listinfo/ros-users
> >> >> >>
> >> >> >
> >> >> >
> >> >> > _______________________________________________
> >> >> > ros-users mailing list
> >> >> > ros-users at code.ros.org
> >> >> > https://code.ros.org/mailman/listinfo/ros-users
> >> >> >
> >> >> _______________________________________________
> >> >> ros-users mailing list
> >> >> ros-users at code.ros.org
> >> >> https://code.ros.org/mailman/listinfo/ros-users
> >> >>
> >> >
> >> >
> >> >
> >> > --
> >> > Tully Foote
> >> > Systems Engineer
> >> > Willow Garage, Inc.
> >> > tfoote at willowgarage.com
> >> > (650) 475-2827
> >> > _______________________________________________
> >> > ros-users mailing list
> >> > ros-users at code.ros.org
> >> > https://code.ros.org/mailman/listinfo/ros-users
> >> >
> >>
> >>
> >> _______________________________________________
> >> ros-users mailing list
> >> ros-users at code.ros.org
> >> https://code.ros.org/mailman/listinfo/ros-users
> >>
> >
> >
> >
> > --
> > Tully Foote
> > Systems Engineer
> > Willow Garage, Inc.
> > tfoote at willowgarage.com
> > (650) 475-2827
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org
> > https://code.ros.org/mailman/listinfo/ros-users
> >
>
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> 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/20100707/2e478f15/attachment-0003.html>


More information about the ros-users mailing list