File tree Expand file tree Collapse file tree 1 file changed +9
-6
lines changed Expand file tree Collapse file tree 1 file changed +9
-6
lines changed Original file line number Diff line number Diff line change @@ -2147,6 +2147,15 @@ controller_interface::return_type ControllerManager::update(
2147
2147
run_controller_at_cm_rate ? period
2148
2148
: rclcpp::Duration::from_seconds ((1.0 / controller_update_rate));
2149
2149
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
+
2150
2159
bool controller_go =
2151
2160
(time ==
2152
2161
rclcpp::Time (0 , 0 , this ->get_node_clock_interface ()->get_clock ()->get_clock_type ())) ||
@@ -2182,12 +2191,6 @@ controller_interface::return_type ControllerManager::update(
2182
2191
controller_ret = controller_interface::return_type::ERROR;
2183
2192
}
2184
2193
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
- }
2191
2194
*loaded_controller.next_update_cycle_time += controller_period;
2192
2195
2193
2196
if (controller_ret != controller_interface::return_type::OK)
You can’t perform that action at this time.
0 commit comments