From fd9d14b08b55ffea1589e63073df15d5cbf6bc5f Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Tue, 14 Nov 2023 14:41:56 +0000 Subject: [PATCH 1/2] Renamed normalize_joint_error_ to joints_angle_wraparound_ --- 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 e7cee27de..114dad9b9 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -90,7 +90,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const auto compute_error_for_joint = [&](JointTrajectoryPoint& error, size_t index, const JointTrajectoryPoint& current, const JointTrajectoryPoint& desired) { // error defined as the difference between current and desired - if (normalize_joint_error_[index]) { + if (joints_angle_wraparound_[index]) { // if desired, the shortest_angular_distance is calculated, i.e., the error is // normalized between -pi Date: Thu, 16 Nov 2023 12:53:32 +0000 Subject: [PATCH 2/2] Update read_state_from_hardware This has been renamed to read_state_from_state_interfaces --- 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 114dad9b9..d1a19b70d 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -129,7 +129,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const // current state update state_current_.time_from_start.set__sec(0); - read_state_from_hardware(state_current_); + read_state_from_state_interfaces(state_current_); // currently carrying out a trajectory if (has_active_trajectory()) {