[ros-users] tf and most recent transform error

Tully Foote tfoote at willowgarage.com
Tue May 4 01:55:12 UTC 2010


Dejan,

Your TransformBroadcaster and TransformListener communicate in another
thread over the network.  Without any delay it is most likely that the data
won't get transfered between sequential calls.

There are two solutions:
You can use a waitForTransform or tf::MessageFilter to wait for the data to
become available.
if you don't care if other instances knowing about this information you can
call setTransform on the TransformListener instance.  Which will inject it
only for that instance of the tf::TransformeListener.

Tully

On Mon, May 3, 2010 at 4:26 PM, Dejan Pangercic
<dejan.pangercic at gmail.com>wrote:

> Dear ROS-itas,
> I am giving tf a try to rotate some PointCloud msgs. In my node's
> constructor I initialize the transform and broadcast it:
> transform1_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
> transform1_.setRotation(tf::Quaternion(tf::Vector3(1, 0, 0),
> angles::from_degrees(-30)));
> br_.sendTransform(tf::StampedTransform(transform1_, ros::Time::now(),
> child_, interim_));
>
> In the cloudCallback function I then renew the broadcast and use
> TransformListener's transformPointCloud for actual rotation:
> void cloud_cb (const sensor_msgs::PointCloudConstPtr& pc)
>    {
>       br_.sendTransform(tf::StampedTransform(transform1_,
> ros::Time::now(), child_, interim_));
>      try
>      {
>        tf_listener_.transformPointCloud(origin_, *pc, cloud_in_);
>      }
>      catch (tf::TransformException ex)
>      {
>        ROS_ERROR("%s",ex.what());
>      }
>      cluster_pub_.publish(cloud_in_);
>    }
>
> The transform however fails with the following error msg:
> """
> [ERROR] [1272928509.572624390]: You requested a transform at time
> 1272928509.567,
>  but the tf buffer only contains a single transform at time 1272928509.122.
>  When trying to transform between /base_link and /RightEyeCalc.
>
> [ERROR] [1272928514.572514949]: You requested a transform that is
> 4.317 miliseconds in the past,
> but the most recent transform in the tf buffer is 5000.070 miliseconds old.
>  When trying to transform between /base_link and /RightEyeCalc.
> """
> It seems that tf is not buffering my transforms, so do I have to do
> this explicitly?
>
> thx and cheers, D.
> --
> MSc. Dejan Pangercic
> PhD Student/Researcher
> Computer Science IX
> Technische Universität München
> Telephone: +49 (89) 289-17780
> E-Mail: dejan.pangercic at in.tum.de
> WWW: http://ias.cs.tum.edu/people/pangercic
> _______________________________________________
> 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/20100503/96106cc9/attachment-0003.html>


More information about the ros-users mailing list