diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index c6d5b519c4..2aa749fc9b 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1270,10 +1270,6 @@ void JointTrajectoryController::compute_error_for_joint( { error.accelerations[index] = desired.accelerations[index] - current.accelerations[index]; } - if (has_effort_command_interface_) - { - error.effort[index] = desired.effort[index]; - } } void JointTrajectoryController::fill_partial_goal(