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

[Issue #223] Add an optional tf_timeout parameter to the sensor models #224

Merged
merged 2 commits into from
Feb 17, 2021

Conversation

svwilliams
Copy link
Contributor

In Issue #223 the sensor model failed to create a constraint due to the lack of an available tf transform. This PR adds an optional tf_timeout to all relevant sensor models. If the timeout is non-zero, the tf lookupTransform() signature with a timeout parameter will be used instead. This allows the user to optionally add a timeout duration, allowing the sensor processing code to wait for a transform is one is not available immediately. Note that this will potentially delay the sensor processing, and may cause dropped messages if the tf frame is not available in a timely fashion.

@svwilliams
Copy link
Contributor Author

@ayrton04 Do you remember any reason why we did not allow the sensor processing to wait for a tf transform to begin with?

@ayrton04
Copy link
Contributor

ayrton04 commented Feb 8, 2021

Almost certainly because it had the potential to mess with the output rate.

auto trans = geometry_msgs::TransformStamped();
if (tf_timeout.isZero())
{
trans = tf_buffer.lookupTransform(output.header.frame_id, input.header.frame_id, input.header.stamp);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm too lazy to look, but does this call just end up calling the other overload with a duration of 0 anyway? What happens if you always just pass tf_timeout, even if it's 0?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It does not. The lookupTransform() method with the timeout calls the canTransform() version with a timeout internally, before calling the base class lookupTransform() method without the timeout.
https://github.com/ros/geometry2/blob/noetic-devel/tf2_ros/src/buffer.cpp#L119

Whereas the non-timeout version of lookupTransform() is the base class version.

There seemed like enough unneeded operations in the canTransform() implementation to make this additional bit of ugliness worthwhile.

ROS_ERROR_STREAM("Cannot create constraint from pose message with stamp " << acceleration.header.stamp);
ROS_ERROR_STREAM_THROTTLE(
10.0,
"Cannot create constraint from pose message with stamp " << acceleration.header.stamp);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

*acceleration message

@svwilliams svwilliams merged commit c86b845 into devel Feb 17, 2021
@svwilliams svwilliams deleted the issue223-tf-timeout branch February 17, 2021 15:14
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants