diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index a0b63f2a0a..1fca832c82 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -285,7 +285,7 @@ controller_interface::return_type JointTrajectoryController::update( { size_t index_cmd_joint = map_cmd_to_joints_[i]; tmp_command_[index_cmd_joint] = - (state_desired_.velocities[index_cmd_joint] * ff_velocity_scale_[index_cmd_joint]) + + (state_desired_.velocities[index_cmd_joint] * ff_velocity_scale_[i]) + pids_[i]->computeCommand( state_error_.positions[index_cmd_joint], state_error_.velocities[index_cmd_joint], (uint64_t)period.nanoseconds());