Skip to content

Commit

Permalink
Fix action tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Aug 24, 2023
1 parent 291453c commit e33892e
Showing 1 changed file with 20 additions and 4 deletions.
24 changes: 20 additions & 4 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,12 +68,12 @@ class TestTrajectoryActions : public TrajectoryControllerTest

void SetUpExecutor(
const std::vector<rclcpp::Parameter> & parameters = {},
bool separate_cmd_and_state_values = false)
bool separate_cmd_and_state_values = false, double kp = 0.0)
{
setup_executor_ = true;

SetUpAndActivateTrajectoryController(
executor_, true, parameters, separate_cmd_and_state_values);
executor_, true, parameters, separate_cmd_and_state_values, kp);

SetUpActionClient();

Expand Down Expand Up @@ -248,7 +248,15 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_single_point_sendgoa
// it should be holding the last position goal
// i.e., active but trivial trajectory (one point only)
// note: the action goal also is a trivial trajectory
expectHoldingPoint(point_positions);
if (traj_controller_->has_position_command_interface())
{
expectHoldingPoint(point_positions);
}
else
{
// no integration to position state interface from velocity/acceleration
expectHoldingPoint(INITIAL_POS_JOINTS);
}
}

TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal)
Expand Down Expand Up @@ -295,7 +303,15 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal

// it should be holding the last position goal
// i.e., active but trivial trajectory (one point only)
expectHoldingPoint(points_positions.at(1));
if (traj_controller_->has_position_command_interface())
{
expectHoldingPoint(points_positions.at(1));
}
else
{
// no integration to position state interface from velocity/acceleration
expectHoldingPoint(INITIAL_POS_JOINTS);
}
}

/**
Expand Down

0 comments on commit e33892e

Please sign in to comment.