Skip to content

Commit

Permalink
Compute velocity errors when using an effort command interface
Browse files Browse the repository at this point in the history
  • Loading branch information
tingelst committed Jun 19, 2023
1 parent 6c97909 commit 2e0da5d
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ controller_interface::return_type JointTrajectoryController::update(
{
error.positions[index] = desired.positions[index] - current.positions[index];
}
if (has_velocity_state_interface_ && has_velocity_command_interface_)
if (has_velocity_state_interface_ && (has_velocity_command_interface_ || has_effort_command_interface_))
{
error.velocities[index] = desired.velocities[index] - current.velocities[index];
}
Expand Down

0 comments on commit 2e0da5d

Please sign in to comment.