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

[RST-2784] Only allow exact timestamp transformations #123

Merged
merged 1 commit into from
Dec 10, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 0 additions & 18 deletions fuse_models/include/fuse_models/common/sensor_proc.h
Original file line number Diff line number Diff line change
Expand Up @@ -193,34 +193,16 @@ template <typename T>
bool transformMessage(const tf2_ros::Buffer& tf_buffer, const T& input, T& output)
{
geometry_msgs::TransformStamped trans;

bool have_transform = false;

if (tf_buffer.canTransform(output.header.frame_id, input.header.frame_id, input.header.stamp))
{
try
{
trans = tf_buffer.lookupTransform(output.header.frame_id, input.header.frame_id, input.header.stamp);
have_transform = true;
}
catch (const tf2::TransformException& ex)
{
ROS_WARN_STREAM_THROTTLE(5.0, "Could not transform message from " << input.header.frame_id << " to " <<
output.header.frame_id << ". Error was " << ex.what() << " Will attempt to use latest transform instead.");
}
}

if (!have_transform)
{
try
{
trans = tf_buffer.lookupTransform(output.header.frame_id, input.header.frame_id, ros::Time(0));
}
catch (const tf2::TransformException& ex)
{
ROS_ERROR_STREAM_THROTTLE(5.0, "Could not transform message from " << input.header.frame_id << " to " <<
output.header.frame_id << ". Error was " << ex.what());

return false;
}
}
Expand Down