Skip to content

Commit 12d46f2

Browse files
tingelstbmagyar
authored andcommitted
Compute velocity errors when using an effort command interface (#679)
(cherry picked from commit 2e0da5d)
1 parent ff6e81d commit 12d46f2

File tree

2 files changed

+5
-3
lines changed

2 files changed

+5
-3
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,9 @@ controller_interface::return_type JointTrajectoryController::update(
133133
{
134134
error.positions[index] = desired.positions[index] - current.positions[index];
135135
}
136-
if (has_velocity_state_interface_ && has_velocity_command_interface_)
136+
if (
137+
has_velocity_state_interface_ &&
138+
(has_velocity_command_interface_ || has_effort_command_interface_))
137139
{
138140
error.velocities[index] = desired.velocities[index] - current.velocities[index];
139141
}

joint_trajectory_controller/test/test_trajectory_actions.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -304,7 +304,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal
304304
/**
305305
* Makes sense with position command interface only,
306306
* because no integration to position state interface is implemented
307-
*/
307+
*/
308308
TEST_F(TestTrajectoryActions, test_goal_tolerances_single_point_success)
309309
{
310310
// set tolerance parameters
@@ -349,7 +349,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_single_point_success)
349349
/**
350350
* Makes sense with position command interface only,
351351
* because no integration to position state interface is implemented
352-
*/
352+
*/
353353
TEST_F(TestTrajectoryActions, test_goal_tolerances_multi_point_success)
354354
{
355355
// set tolerance parameters

0 commit comments

Comments
 (0)