Skip to content

Commit f63c7ae

Browse files
authored
Warning Message Intervals for canTransform (#663)
Signed-off-by: CursedRock17 <[email protected]>
1 parent 0ea2ad3 commit f63c7ae

File tree

2 files changed

+5
-2
lines changed

2 files changed

+5
-2
lines changed

tf2/include/tf2/buffer_core.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,11 +46,11 @@
4646

4747
#include "LinearMath/Transform.h"
4848
#include "geometry_msgs/msg/transform_stamped.hpp"
49+
#include "rcutils/logging_macros.h"
4950
#include "tf2/buffer_core_interface.h"
5051
#include "tf2/exceptions.h"
5152
#include "tf2/transform_storage.h"
5253
#include "tf2/visibility_control.h"
53-
#include "rcutils/logging_macros.h"
5454

5555
namespace tf2
5656
{

tf2/src/buffer_core.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,10 @@ void fillOrWarnMessageForInvalidFrame(
8989
if (error_msg != nullptr) {
9090
*error_msg = s;
9191
} else {
92-
RCUTILS_LOG_WARN("%s", s.c_str());
92+
static constexpr std::chrono::milliseconds warning_interval =
93+
std::chrono::milliseconds(2500);
94+
95+
RCUTILS_LOG_WARN_THROTTLE(RCUTILS_STEADY_TIME, warning_interval.count(), "%s", s.c_str());
9396
}
9497
}
9598

0 commit comments

Comments
 (0)