diff --git a/tf2/include/tf2/buffer_core.h b/tf2/include/tf2/buffer_core.h index 6d75127da..cb6f78c44 100644 --- a/tf2/include/tf2/buffer_core.h +++ b/tf2/include/tf2/buffer_core.h @@ -46,11 +46,11 @@ #include "LinearMath/Transform.h" #include "geometry_msgs/msg/transform_stamped.hpp" +#include "rcutils/logging_macros.h" #include "tf2/buffer_core_interface.h" #include "tf2/exceptions.h" #include "tf2/transform_storage.h" #include "tf2/visibility_control.h" -#include "rcutils/logging_macros.h" namespace tf2 { diff --git a/tf2/src/buffer_core.cpp b/tf2/src/buffer_core.cpp index 4c270800e..3da2b2d48 100644 --- a/tf2/src/buffer_core.cpp +++ b/tf2/src/buffer_core.cpp @@ -89,7 +89,10 @@ void fillOrWarnMessageForInvalidFrame( if (error_msg != nullptr) { *error_msg = s; } else { - RCUTILS_LOG_WARN("%s", s.c_str()); + static constexpr std::chrono::milliseconds warning_interval = + std::chrono::milliseconds(2500); + + RCUTILS_LOG_WARN_THROTTLE(RCUTILS_STEADY_TIME, warning_interval.count(), "%s", s.c_str()); } }