Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: suppress unnecessary warnings in clock received validation #1935

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading