diff --git a/controller_manager/src/ros2_control_node.cpp b/controller_manager/src/ros2_control_node.cpp index b8468318ac..ff91342940 100644 --- a/controller_manager/src/ros2_control_node.cpp +++ b/controller_manager/src/ros2_control_node.cpp @@ -62,8 +62,9 @@ int main(int argc, char ** argv) // for calculating sleep time auto const period = std::chrono::nanoseconds(1'000'000'000 / cm->get_update_rate()); - std::chrono::system_clock::time_point next_iteration_time = - std::chrono::system_clock::time_point(std::chrono::nanoseconds(cm->now().nanoseconds())); + auto const cm_now = std::chrono::nanoseconds(cm->now().nanoseconds()); + std::chrono::time_point + next_iteration_time{cm_now}; // for calculating the measured period of the loop rclcpp::Time previous_time = cm->now();