Skip to content

Commit

Permalink
Compute velocity errors when using an effort command interface (#679)
Browse files Browse the repository at this point in the history
(cherry picked from commit 2e0da5d)
(cherry picked from commit 12d46f2)
  • Loading branch information
tingelst authored and mergify[bot] committed Jul 17, 2023
1 parent c80c899 commit 7ca381b
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,9 @@ 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
4 changes: 2 additions & 2 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -312,7 +312,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal
/**
* Makes sense with position command interface only,
* because no integration to position state interface is implemented
*/
*/
TEST_F(TestTrajectoryActions, test_goal_tolerances_single_point_success)
{
// set tolerance parameters
Expand Down Expand Up @@ -357,7 +357,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_single_point_success)
/**
* Makes sense with position command interface only,
* because no integration to position state interface is implemented
*/
*/
TEST_F(TestTrajectoryActions, test_goal_tolerances_multi_point_success)
{
// set tolerance parameters
Expand Down

0 comments on commit 7ca381b

Please sign in to comment.