Skip to content

Commit

Permalink
Warning Message Intervals for canTransform (#663)
Browse files Browse the repository at this point in the history
Signed-off-by: CursedRock17 <mtglucas1@gmail.com>
  • Loading branch information
CursedRock17 committed Apr 4, 2024
1 parent 0ea2ad3 commit f63c7ae
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
2 changes: 1 addition & 1 deletion tf2/include/tf2/buffer_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
5 changes: 4 additions & 1 deletion tf2/src/buffer_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
}

Expand Down

0 comments on commit f63c7ae

Please sign in to comment.