Skip to content

Commit

Permalink
Simplify logic
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 2, 2024
1 parent 5b697fa commit 9fd84f5
Showing 1 changed file with 21 additions and 23 deletions.
44 changes: 21 additions & 23 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2366,30 +2366,27 @@ controller_interface::return_type ControllerManager::update(
run_controller_at_cm_rate ? period
: rclcpp::Duration::from_seconds((1.0 / controller_update_rate));

rclcpp::Time current_time = get_clock()->now();
rclcpp::Duration controller_actual_period(0, 0);
if (
current_time ==
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
rclcpp::Time current_time;
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.");
}
else
{
// this can happen with use_sim_time=true until the /clock is received
RCLCPP_WARN(
get_logger(),
"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");
current_time = time;
}
current_time = get_clock()->now();
}
else 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.");
}
else
{
// this can happen with use_sim_time=true until the /clock is received
RCLCPP_WARN(
get_logger(),
"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.");
current_time = time;
}
if (
*loaded_controller.last_update_cycle_time ==
Expand All @@ -2412,6 +2409,7 @@ controller_interface::return_type ControllerManager::update(
get_logger(), "Setting last_update_cycle_time to %fs for the controller : %s",
loaded_controller.last_update_cycle_time->seconds(), loaded_controller.info.name.c_str());
}
rclcpp::Duration controller_actual_period(0, 0);
if (current_time > *loaded_controller.last_update_cycle_time)
{
// the nominal case
Expand Down

0 comments on commit 9fd84f5

Please sign in to comment.