Skip to content

Commit

Permalink
Use throttled output
Browse files Browse the repository at this point in the history
Co-authored-by: Felix Exner (fexner) <[email protected]>
  • Loading branch information
christophfroehlich and fmauch authored Dec 3, 2024
1 parent 9fd84f5 commit ec46577
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2382,10 +2382,11 @@ controller_interface::return_type ControllerManager::update(
else
{
// this can happen with use_sim_time=true until the /clock is received
RCLCPP_WARN(
get_logger(),
rclcpp::Clock clock = rclcpp::Clock();
RCLCPP_WARN_THROTTLE(
get_logger(), clock, 1000,
"No clock received, using time argument instead! Check your node's clock "
"configuration (use_sim_time parameter) and if a valid clock source is available.");
"configuration (use_sim_time parameter) and if a valid clock source is available");
current_time = time;
}
if (
Expand Down

0 comments on commit ec46577

Please sign in to comment.