Skip to content

Commit

Permalink
Suppress unnecessary warnings in clock received validation (#1935)
Browse files Browse the repository at this point in the history
  • Loading branch information
TakashiSato authored Dec 12, 2024
1 parent c37b9d9 commit d62be07
Showing 1 changed file with 9 additions and 10 deletions.
19 changes: 9 additions & 10 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down

0 comments on commit d62be07

Please sign in to comment.