From d62be07e9ce94bd2b6f529d27dca075bedff822f Mon Sep 17 00:00:00 2001 From: Takashi Sato Date: Thu, 12 Dec 2024 17:03:36 +0900 Subject: [PATCH] Suppress unnecessary warnings in clock received validation (#1935) --- controller_manager/src/controller_manager.cpp | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index d4b4076bb3..9f20e2b584 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -2367,17 +2367,16 @@ controller_interface::return_type ControllerManager::update( update_loop_counter_ %= update_rate_; // Check for valid time - if ( - !get_clock()->started() && - time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) - { - throw std::runtime_error( - "No clock received, and time argument is zero. Check your controller_manager node's " - "clock configuration (use_sim_time parameter) and if a valid clock source is " - "available. Also pass a proper time argument to the update method."); - } - else + if (!get_clock()->started()) { + if (time == rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) + { + throw std::runtime_error( + "No clock received, and time argument is zero. Check your controller_manager node's " + "clock configuration (use_sim_time parameter) and if a valid clock source is " + "available. Also pass a proper time argument to the update method."); + } + // this can happen with use_sim_time=true until the /clock is received rclcpp::Clock clock = rclcpp::Clock(); RCLCPP_WARN_THROTTLE(