Skip to content

Commit

Permalink
Use correct ff_velocity_scale parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Nov 7, 2023
1 parent 3bb68d9 commit 80e370e
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,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());
Expand Down

0 comments on commit 80e370e

Please sign in to comment.