Skip to content

Commit 338a974

Browse files
committed
Throttle the overrun logs
1 parent c19997a commit 338a974

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

controller_manager/src/ros2_control_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -161,8 +161,8 @@ int main(int argc, char ** argv)
161161
1.e6;
162162
const double cm_period = 1.e3 / static_cast<double>(cm->get_update_rate());
163163
const int overrun_count = static_cast<int>(std::ceil(time_diff / cm_period));
164-
RCLCPP_WARN(
165-
cm->get_logger(),
164+
RCLCPP_WARN_THROTTLE(
165+
cm->get_logger(), *cm->get_clock(), 1000,
166166
"Overrun detected! The controller manager missed its desired rate of %d Hz. The loop "
167167
"took %f ms (missed cycles : %d).",
168168
cm->get_update_rate(), time_diff + cm_period, overrun_count + 1);

0 commit comments

Comments
 (0)