Skip to content

Commit cba9ce3

Browse files
Change to parameterized test
1 parent 440d7d2 commit cba9ce3

File tree

1 file changed

+5
-15
lines changed

1 file changed

+5
-15
lines changed

joint_trajectory_controller/test/test_trajectory_actions.cpp

Lines changed: 5 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -616,19 +616,14 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_cancel_hold_position)
616616
}
617617
}
618618

619-
TEST_F(TestTrajectoryActions, test_allow_nonzero_velocity_stop_true)
619+
TEST_P(TestTrajectoryActionsTestParameterized, test_allow_nonzero_velocity_stop_true)
620620
{
621-
// set parameter
622-
command_interface_types_ = {"velocity"};
623-
std::vector<rclcpp::Parameter> params = {
624-
rclcpp::Parameter("command_interfaces", "velocity"),
625-
rclcpp::Parameter("allow_nonzero_velocity_stop", true)};
626-
621+
std::vector<rclcpp::Parameter> params = {rclcpp::Parameter("allow_nonzero_velocity_stop", true)};
627622
SetUpExecutor(params);
628623
SetUpControllerHardware();
629624

630625
std::shared_future<typename GoalHandle::SharedPtr> gh_future;
631-
// send goal
626+
// send goal with nonzero last velocities
632627
{
633628
std::vector<JointTrajectoryPoint> points;
634629
JointTrajectoryPoint point1;
@@ -666,13 +661,9 @@ TEST_F(TestTrajectoryActions, test_allow_nonzero_velocity_stop_true)
666661
EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);
667662
}
668663

669-
TEST_F(TestTrajectoryActions, test_allow_nonzero_velocity_stop_false)
664+
TEST_P(TestTrajectoryActionsTestParameterized, test_allow_nonzero_velocity_stop_false)
670665
{
671-
// set parameter
672-
std::vector<rclcpp::Parameter> params = {
673-
rclcpp::Parameter("command_interfaces", "velocity"),
674-
rclcpp::Parameter("allow_nonzero_velocity_stop", false)};
675-
666+
std::vector<rclcpp::Parameter> params = {rclcpp::Parameter("allow_nonzero_velocity_stop", false)};
676667
SetUpExecutor(params);
677668
SetUpControllerHardware();
678669

@@ -745,7 +736,6 @@ TEST_F(TestTrajectoryActions, test_allow_nonzero_velocity_stop_false)
745736
}
746737

747738
EXPECT_TRUE(gh_future.get());
748-
EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);
749739
}
750740

751741
// position controllers

0 commit comments

Comments
 (0)