diff --git a/src/ros_filter.cpp b/src/ros_filter.cpp index 73b7cce9..73a9252d 100644 --- a/src/ros_filter.cpp +++ b/src/ros_filter.cpp @@ -2178,30 +2178,29 @@ void RosFilter::periodicUpdate() if (filtered_position->header.frame_id == odom_frame_id_) { world_transform_broadcaster_->sendTransform(world_base_link_trans_msg_); } else if (filtered_position->header.frame_id == map_frame_id_) { - try { - tf2::Transform world_base_link_trans; - tf2::fromMsg( - world_base_link_trans_msg_.transform, - world_base_link_trans); - - tf2::Transform base_link_odom_trans; - tf2::fromMsg( - tf_buffer_ - ->lookupTransform( - base_link_frame_id_, - odom_frame_id_, - tf2::TimePointZero) - .transform, - base_link_odom_trans); - + tf2::Transform world_base_link_trans; + tf2::fromMsg( + world_base_link_trans_msg_.transform, + world_base_link_trans); + + tf2::Transform base_link_odom_trans; + bool can_transform_odom = ros_filter_utilities::lookupTransformSafe( + tf_buffer_.get(), + base_link_frame_id_, + odom_frame_id_, + filtered_position->header.stamp, + tf_timeout_, + base_link_odom_trans); + + if(can_transform_odom) { /* * First, see these two references: * http://wiki.ros.org/tf/Overview/Using%20Published%20Transforms#lookupTransform * http://wiki.ros.org/geometry/CoordinateFrameConventions#Transform_Direction * We have a transform from map_frame_id_->base_link_frame_id_, but * it would actually transform a given pose from - * base_link_frame_id_->map_frame_id_. We then used lookupTransform, - * whose first two arguments are target frame and source frame, to + * base_link_frame_id_->map_frame_id_. We then used lookupTransformSafe, + * whose second and third arguments are target frame and source frame, to * get a transform from base_link_frame_id_->odom_frame_id_. * However, this transform would actually transform data from * odom_frame_id_->base_link_frame_id_. Now imagine that we have a @@ -2227,7 +2226,7 @@ void RosFilter::periodicUpdate() map_odom_trans_msg.child_frame_id = odom_frame_id_; world_transform_broadcaster_->sendTransform(map_odom_trans_msg); - } catch (...) { + } else { RCLCPP_ERROR_STREAM_SKIPFIRST_THROTTLE( get_logger(), *get_clock(),