Skip to content

Commit 7df20f6

Browse files
Reset both sec and nanosec in time_from_start (backport #1709) (#1711)
Co-authored-by: Arnav Kapoor <[email protected]>
1 parent 080299a commit 7df20f6

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
@@ -167,7 +167,8 @@ controller_interface::return_type JointTrajectoryController::update(
167167
}
168168

169169
// current state update
170-
state_current_.time_from_start.set__sec(0);
170+
state_current_.time_from_start.sec = 0;
171+
state_current_.time_from_start.nanosec = 0;
171172
read_state_from_state_interfaces(state_current_);
172173

173174
// currently carrying out a trajectory

0 commit comments

Comments
 (0)