Skip to content

Commit b951a5f

Browse files
mhubiigithub-actions[bot]
authored andcommitted
throttle warn stream (#292)
(cherry picked from commit 01e60f6)
1 parent 540b72d commit b951a5f

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

lbr_ros2_control/src/system_interface.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -208,11 +208,11 @@ hardware_interface::return_type SystemInterface::read(const rclcpp::Time & /*tim
208208
lbr_state_ = async_client_ptr_->get_state_interface()->get_state();
209209

210210
if (period.seconds() - lbr_state_.sample_time * 0.2 > lbr_state_.sample_time) {
211-
RCLCPP_WARN_STREAM(get_node()->get_logger(),
212-
lbr_fri_ros2::ColorScheme::WARNING
213-
<< "Increase update_rate parameter for controller_manager to "
214-
<< std::to_string(static_cast<int>(1. / lbr_state_.sample_time))
215-
<< " Hz or more" << lbr_fri_ros2::ColorScheme::ENDC);
211+
RCLCPP_WARN_STREAM_THROTTLE(get_node()->get_logger(), *(get_node()->get_clock()), 500 /*ms*/,
212+
lbr_fri_ros2::ColorScheme::WARNING
213+
<< "Increase update_rate parameter for controller_manager to "
214+
<< std::to_string(static_cast<int>(1. / lbr_state_.sample_time))
215+
<< " Hz or more" << lbr_fri_ros2::ColorScheme::ENDC);
216216
}
217217

218218
// exit once robot exits COMMANDING_ACTIVE (for safety)

0 commit comments

Comments
 (0)