diff --git a/tf2_ros/include/tf2_ros/message_filter.hpp b/tf2_ros/include/tf2_ros/message_filter.hpp index b1ed106f5..2f0633365 100644 --- a/tf2_ros/include/tf2_ros/message_filter.hpp +++ b/tf2_ros/include/tf2_ros/message_filter.hpp @@ -703,8 +703,11 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi const MConstPtr & message = evt.getMessage(); std::string frame_id = stripSlash(mt::FrameId::value(*message)); rclcpp::Time stamp = mt::TimeStamp::value(*message); - RCLCPP_INFO( + auto clock = node_clock_->get_clock(); + RCLCPP_INFO_THROTTLE( node_logging_->get_logger(), + *clock, + 2500, "Message Filter dropping message: frame '%s' at time %.3f for reason '%s'", frame_id.c_str(), stamp.seconds(), get_filter_failure_reason_string(reason).c_str()); }