Skip to content

Commit 043963f

Browse files
firesurferLennart Nachtigall
authored andcommitted
this simple fix should fix the goal time violated issue (#882)
Co-authored-by: Lennart Nachtigall <[email protected]> (cherry picked from commit 3f423ed)
1 parent 9ba91ed commit 043963f

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
173173
// time_difference is
174174
// - negative until first point is reached
175175
// - counting from zero to time_from_start of next point
176-
double time_difference = time.seconds() - segment_time_from_start.seconds();
176+
const double time_difference = time_data.uptime.seconds() - segment_time_from_start.seconds();
177177
bool tolerance_violated_while_moving = false;
178178
bool outside_goal_tolerance = false;
179179
bool within_goal_time = true;

0 commit comments

Comments
 (0)