File tree Expand file tree Collapse file tree 1 file changed +9
-10
lines changed Expand file tree Collapse file tree 1 file changed +9
-10
lines changed Original file line number Diff line number Diff line change @@ -2367,17 +2367,16 @@ controller_interface::return_type ControllerManager::update(
23672367 update_loop_counter_ %= update_rate_;
23682368
23692369 // Check for valid time
2370- if (
2371- !get_clock ()->started () &&
2372- time == rclcpp::Time (0 , 0 , this ->get_node_clock_interface ()->get_clock ()->get_clock_type ()))
2373- {
2374- throw std::runtime_error (
2375- " No clock received, and time argument is zero. Check your controller_manager node's "
2376- " clock configuration (use_sim_time parameter) and if a valid clock source is "
2377- " available. Also pass a proper time argument to the update method." );
2378- }
2379- else
2370+ if (!get_clock ()->started ())
23802371 {
2372+ if (time == rclcpp::Time (0 , 0 , this ->get_node_clock_interface ()->get_clock ()->get_clock_type ()))
2373+ {
2374+ throw std::runtime_error (
2375+ " No clock received, and time argument is zero. Check your controller_manager node's "
2376+ " clock configuration (use_sim_time parameter) and if a valid clock source is "
2377+ " available. Also pass a proper time argument to the update method." );
2378+ }
2379+
23812380 // this can happen with use_sim_time=true until the /clock is received
23822381 rclcpp::Clock clock = rclcpp::Clock ();
23832382 RCLCPP_WARN_THROTTLE (
You can’t perform that action at this time.
0 commit comments