From dcda1c3fd2dff4ab01ac65c4491806b1581a79ad Mon Sep 17 00:00:00 2001 From: "Dr. Denis" Date: Tue, 6 Feb 2024 17:18:37 +0100 Subject: [PATCH] Update joint_trajectory_controller.cpp --- .../src/joint_trajectory_controller.cpp | 32 ------------------- 1 file changed, 32 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index aced70703f..9fb9c0d997 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -134,38 +134,6 @@ controller_interface::return_type JointTrajectoryController::update( } } -<<<<<<< HEAD - auto compute_error_for_joint = [&]( - JointTrajectoryPoint & error, int index, - const JointTrajectoryPoint & current, - const JointTrajectoryPoint & desired) - { - // error defined as the difference between current and desired - if (joints_angle_wraparound_[index]) - { - // if desired, the shortest_angular_distance is calculated, i.e., the error is - // normalized between -pi>>>>>> 833ed7f ([JTC] Convert lambda to class functions (#945)) // don't update goal after we sampled the trajectory to avoid any racecondition const auto active_goal = *rt_active_goal_.readFromRT();