Skip to content

Commit 1ebee52

Browse files
Reset both sec and nanosec in time_from_start (backport #1709) (#1710)
Co-authored-by: Arnav Kapoor <[email protected]>
1 parent 236c895 commit 1ebee52

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -193,7 +193,8 @@ controller_interface::return_type JointTrajectoryController::update(
193193
};
194194

195195
// current state update
196-
state_current_.time_from_start.set__sec(0);
196+
state_current_.time_from_start.sec = 0;
197+
state_current_.time_from_start.nanosec = 0;
197198
read_state_from_state_interfaces(state_current_);
198199

199200
// currently carrying out a trajectory

0 commit comments

Comments
 (0)