Skip to content

Commit

Permalink
this simple fix should fix the goal time violated issue (#882) (#1000)
Browse files Browse the repository at this point in the history
Co-authored-by: Lennart Nachtigall <[email protected]>
(cherry picked from commit 3f423ed)

Co-authored-by: Lennart Nachtigall <[email protected]>
  • Loading branch information
mergify[bot] and firesurfer authored May 22, 2024
1 parent 3e35864 commit 57a207f
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ur_controllers/src/scaled_joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
// time_difference is
// - negative until first point is reached
// - counting from zero to time_from_start of next point
double time_difference = time.seconds() - segment_time_from_start.seconds();
const double time_difference = time_data.uptime.seconds() - segment_time_from_start.seconds();
bool tolerance_violated_while_moving = false;
bool outside_goal_tolerance = false;
bool within_goal_time = true;
Expand Down

0 comments on commit 57a207f

Please sign in to comment.