You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
For ROS Noetic on Ubuntu 20.04 and Python 3.8.10. When loading a tf.py.BufferCore with transforms, it seems it does not respect the cache_time argument when setting it as a named argument in Python. Running the below code should generate an exception with a message along the lines of
Lookup would require extrapolation 9.999000000s into the past. Requested time 0.001000000 but the earliest data is at time 10.000000000, when looking up transform from frame [frame_b] to frame [frame_a]
The error message is consistent with an hypothesis that using the cache_time named argument makes the constructor use the default argument. The default argument is as far as I can tell from scattered sources online a duration of 10 seconds.
import geometry_msgs.msg
import rospy
import tf2_py
TIME_RANGE = 20
CACHE_DURATION = rospy.Duration(float(TIME_RANGE*2))
# This works fine:
#t = tf2_py.BufferCore(CACHE_DURATION)
# Using the cache_time named argument makes it default to a cache of 10 seconds!
t = tf2_py.BufferCore(cache_time=CACHE_DURATION)
# Generate dummy synthetic data
FRAMES = ["frame_a", "frame_b"]
for time in range(TIME_RANGE+1):
for parent_frame, child_frame in zip(FRAMES[:-1], FRAMES[1:]):
m = geometry_msgs.msg.TransformStamped()
m.header.frame_id = parent_frame
m.header.stamp = rospy.Time.from_sec(float(time))
m.child_frame_id = child_frame
m.transform.translation.x = 1.0
m.transform.rotation.w = 1.0
t.set_transform(m, "default_authority")
# Do lookups over the whole time range except for the last second, make sure it works.
for time_ms in range((TIME_RANGE-1)*1000):
tf = t.lookup_transform_core(target_frame=FRAMES[0],
source_frame=FRAMES[-1], time=rospy.Time.from_sec(time_ms/1000))
The text was updated successfully, but these errors were encountered:
For ROS Noetic on Ubuntu 20.04 and Python 3.8.10. When loading a
tf.py.BufferCore
with transforms, it seems it does not respect thecache_time
argument when setting it as a named argument in Python. Running the below code should generate an exception with a message along the lines ofThe error message is consistent with an hypothesis that using the
cache_time
named argument makes the constructor use the default argument. The default argument is as far as I can tell from scattered sources online a duration of 10 seconds.The text was updated successfully, but these errors were encountered: