Skip to content

Commit

Permalink
[JTC] Improve update methods for tests (#858)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 27, 2023
1 parent 2854a0b commit b853228
Show file tree
Hide file tree
Showing 3 changed files with 565 additions and 561 deletions.
16 changes: 8 additions & 8 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Expand Up @@ -242,7 +242,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_single_point_sendgoa
EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the last position goal
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -298,7 +298,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal
EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the last position goal
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -350,7 +350,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_single_point_success)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the last position goal
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -409,7 +409,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_multi_point_success)
control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the last position goal
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -460,7 +460,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_state_tolerances_fail)
common_action_result_code_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the position (being the initial one)
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -509,7 +509,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_goal_tolerances_fail)
common_action_result_code_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the position (being the initial one)
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -555,7 +555,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_no_time_from_start_state_tol
common_action_result_code_);

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the position (being the initial one)
// i.e., active but trivial trajectory (one point only)
Expand Down Expand Up @@ -603,7 +603,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_cancel_hold_position)
std::vector<double> cancelled_position{joint_pos_[0], joint_pos_[1], joint_pos_[2]};

// run an update
updateController(rclcpp::Duration::from_seconds(0.01));
updateControllerAsync(rclcpp::Duration::from_seconds(0.01));

// it should be holding the last position,
// i.e., active but trivial trajectory (one point only)
Expand Down

0 comments on commit b853228

Please sign in to comment.