Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

tf_py.BufferCore not respecting cache_time argument #540

Open
MechatronixX opened this issue Aug 25, 2022 · 2 comments
Open

tf_py.BufferCore not respecting cache_time argument #540

MechatronixX opened this issue Aug 25, 2022 · 2 comments

Comments

@MechatronixX
Copy link

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))
@tfoote
Copy link
Member

tfoote commented Oct 6, 2022

It's read here:

if (!PyArg_ParseTuple(args, "|O&", rosduration_converter, &cache_time))

It uses PyArg_ParseTuple and would need to be extended to use

PyArg_ParseTupleAndKeywords to be able to use the keywords as well.

If this would be valuable to you a PR would be appreciated.

@MechatronixX
Copy link
Author

I see. Maybe just disabling named arguments in the concerned function would be fine for now? https://deepsource.io/blog/python-positional-only-arguments/

Not planning to create a PR currently.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

2 participants