From 0defc6c87e4a5666c35b49fc0bd0c265de00a1fd Mon Sep 17 00:00:00 2001 From: Arnav Kapoor Date: Tue, 27 May 2025 13:24:37 +0530 Subject: [PATCH] Reset both sec and nanosec in time_from_start (#1709) (cherry picked from commit 483d6ac8fb3626615796b5cf781b5594dcca7679) --- .../src/joint_trajectory_controller.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 6890cea55e..71425da399 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -167,7 +167,8 @@ controller_interface::return_type JointTrajectoryController::update( } // current state update - state_current_.time_from_start.set__sec(0); + state_current_.time_from_start.sec = 0; + state_current_.time_from_start.nanosec = 0; read_state_from_state_interfaces(state_current_); // currently carrying out a trajectory