From 57a207f1b1cd597047cfaaa4f0ad853684d2a9d8 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Wed, 22 May 2024 18:46:02 +0200 Subject: [PATCH] this simple fix should fix the goal time violated issue (#882) (#1000) Co-authored-by: Lennart Nachtigall (cherry picked from commit 3f423ed18e6a6adc139b3395d23867b26a3f5632) Co-authored-by: Lennart Nachtigall --- ur_controllers/src/scaled_joint_trajectory_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index d1a19b70d..93ffa0a94 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -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;