Skip to content

Commit 5af4779

Browse files
committed
No need to spam the logs
1 parent d536d33 commit 5af4779

File tree

1 file changed

+6
-2
lines changed

1 file changed

+6
-2
lines changed

nav2_costmap_2d/src/layered_costmap.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,8 @@
4444
#include <vector>
4545
#include <limits>
4646

47+
#include <rclcpp/clock.hpp>
48+
4749
#include "nav2_costmap_2d/footprint.hpp"
4850

4951

@@ -146,9 +148,11 @@ void LayeredCostmap::updateMap(double robot_x, double robot_y, double robot_yaw)
146148
}
147149

148150
if (isOutofBounds(robot_x, robot_y)) {
149-
RCLCPP_WARN(
151+
rclcpp::Clock clock{RCL_ROS_TIME};
152+
RCLCPP_WARN_THROTTLE(
150153
rclcpp::get_logger("nav2_costmap_2d"),
151-
"Robot is out of bounds of the costmap!");
154+
clock, 5000,
155+
"Robot is out of bounds of the costmap");
152156
}
153157

154158
if (plugins_.size() == 0 && filters_.size() == 0) {

0 commit comments

Comments
 (0)