Skip to content

Commit ab80113

Browse files
Fix the initialization of the next update time
1 parent 181cda0 commit ab80113

File tree

1 file changed

+9
-6
lines changed

1 file changed

+9
-6
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2147,6 +2147,15 @@ controller_interface::return_type ControllerManager::update(
21472147
run_controller_at_cm_rate ? period
21482148
: rclcpp::Duration::from_seconds((1.0 / controller_update_rate));
21492149

2150+
if (
2151+
*loaded_controller.next_update_cycle_time ==
2152+
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
2153+
{
2154+
// it is zero after activation
2155+
RCLCPP_DEBUG(get_logger(), "Set next_update_cycle_time to %fs", time.seconds());
2156+
*loaded_controller.next_update_cycle_time = time;
2157+
}
2158+
21502159
bool controller_go =
21512160
(time ==
21522161
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type())) ||
@@ -2182,12 +2191,6 @@ controller_interface::return_type ControllerManager::update(
21822191
controller_ret = controller_interface::return_type::ERROR;
21832192
}
21842193

2185-
if (
2186-
*loaded_controller.next_update_cycle_time ==
2187-
rclcpp::Time(0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type()))
2188-
{
2189-
*loaded_controller.next_update_cycle_time = time;
2190-
}
21912194
*loaded_controller.next_update_cycle_time += controller_period;
21922195

21932196
if (controller_ret != controller_interface::return_type::OK)

0 commit comments

Comments
 (0)