[ros-users] Future-dating tf transforms by more than 10 minutes?
Patrick Bouffard
bouffard at eecs.berkeley.edu
Tue May 25 19:21:33 UTC 2010
Tully,
Actually what I'm doing right now is similar to the second scenario
you describe, but I broadcast the transform twice, once with a
ros::Time::now() timestamp, and immediately following I broadcast with
a ros::Time::now() + ros::Duration(600) timestamp. Doing that, my
frame appears in the right spot in rviz for the duration of the
session (which is a playback of recorded data, that does not include
the transform I'm talking about). So what you're saying is that what's
happening is that rviz is seeing the present-dated transform, and
using that for the duration of the session, while my second
future-dated transform is actually not being used. The problem is, if
I comment out the second, future-dated transform broadcast, I get the
"No transform from [/grey/camera] to frame [/enu]" message again.
Could it be that rviz actually is using both the present and the
future dated transforms and 'interpolating' for the time in between?
I do appreciate that the 1 Hz publishing is not a big hit, but there
could be systems where this doesn't make sense, if the number of
static transforms is large. Suppose for example you have frames that
represent the locations of all the airports in the world. That's a few
tens of thousands of frames. Not a huge amount of data, really,
compared with say point clouds or image streams. But it still doesn't
make sense to have it broadcast out at 1 Hz when it never changes.
Suppose there were an alternative to static_transform_publisher, which
implemented a node that could be told about any and all truly static
transforms in the system (i.e. once told about a particular transform,
that transform is considered immutable), and which is contacted by
other nodes when they come online to get those static transforms
(maybe as an optional part of tf::TransformListener's constructor). I
guess there would need to be some way for tf to have a concept of
frames that are 'eternal' as far as its cache is concerned.
The use case above is hypothetical but not so far off of the type of
thing we might want to do in our lab.
Cheers,
Pat
On Tue, May 25, 2010 at 11:40 AM, Tully Foote <tfoote at willowgarage.com> wrote:
> Pat,
> The future stamping is a neat trick to get around network latency it's not
> good enough for "static transforms" without communication.
> The best way to look at it is through an example. Think of sending things
> one minute in the future. First, as tf only keeps 10 seconds of data per
> frame it will never be able to traverse that link for it won't have a common
> time between the future frame and the regular frames.
> Also, say you have a big enough buffer or you cut down the future stamping
> to 9 seconds. It will take any node starting 9 seconds to be able to
> transform for it won't have information about the time it started up only
> about time in the future until the amount of time has passed by which you
> future stamped.
> I would suggest publishing at ~ 1Hz. It's only a few lines of code to add
> it to any node and the computational and network overhead is very low.
> Tully
>
> On Tue, May 25, 2010 at 10:35 AM, Patrick Bouffard
> <bouffard at eecs.berkeley.edu> wrote:
>>
>> I have one transform that is determined at run-time, during startup, and
>> never changes. It's only used for visualization, and I'd rather not trouble
>> the node that determines it with having to rebroadcast it periodically, a la
>> static_transform_publisher, nor have to communicate it to another node to do
>> that job.
>>
>> Pat
>>
>> On Tue, May 25, 2010 at 10:29 AM, Josh Faust <jfaust at willowgarage.com>
>> wrote:
>>>
>>> If transforms are also being broadcast at the current time, it's going to
>>> be limited by whatever the cache time is on the TransformListener being
>>> used. rviz uses 10 minutes (which is probably a bit high), but anything
>>> using the default time will be limited to 10 seconds.
>>>
>>> 10 minutes was chosen as "arbitrarily high", so that rviz would always
>>> work over spotty wireless. It should probably be lowered to a minute or
>>> so. The downside to a large cache time is that it can negatively affect
>>> performance.
>>>
>>> Why are you trying to future date transforms?
>>>
>>> Josh
>>>
>>> On Mon, May 24, 2010 at 10:33 PM, Patrick Bouffard
>>> <bouffard at eecs.berkeley.edu> wrote:
>>>>
>>>> Is there a limitation on how far in the future the timestamp of a
>>>> transform broadcast by a tf::TransformBroadcaster can be? If there was I
>>>> would have expected it to be perhaps the default tf cache time of 10.0
>>>> seconds, but my experimentation (this is with boxturtle) seems to indicate
>>>> it is 600 seconds. In particular, I'm looking at the frame in rviz, and if I
>>>> set the timestamp to ros::Time::now() + ros::Duration(600.1), then I get the
>>>> following warning in rviz, and the frame does not have the right data:
>>>>
>>>> No transform from [/grey/camera] to frame [/enu]
>>>>
>>>> ... however if I simply change the 600.1 to 600, there is no warning..
>>>>
>>>> It looks like the constructor in rviz's frame_manager.cpp is where this
>>>> happens:
>>>>
>>>> FrameManager::FrameManager()
>>>> {
>>>> tf_ = new tf::TransformListener(ros::NodeHandle(), ros::Duration(10 *
>>>> 60), false);
>>>> }
>>>>
>>>> It looks like this is unchanged in trunk as well. Is there is some
>>>> reason why ten minutes was chosen? Are there drawbacks to making this
>>>> longer? Or configurable? Ten minutes is fine for my present application but
>>>> it seems to be somewhat arbitrary.
>>>>
>>>> Thanks,
>>>> Pat
>>>>
>>>> _______________________________________________
>>>> 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
>
>
More information about the ros-users
mailing list