Skip to content

Commit 583b815

Browse files
[JTC] Renovate action tests (#603)
1 parent 546422d commit 583b815

File tree

2 files changed

+15
-20
lines changed

2 files changed

+15
-20
lines changed

joint_trajectory_controller/CMakeLists.txt

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -80,13 +80,12 @@ if(BUILD_TESTING)
8080
ros2_control_test_assets
8181
)
8282

83-
# TODO(andyz): Disabled due to flakiness
84-
# ament_add_gmock(test_trajectory_actions
85-
# test/test_trajectory_actions.cpp
86-
# )
87-
# target_link_libraries(test_trajectory_actions
88-
# joint_trajectory_controller
89-
# )
83+
ament_add_gmock(test_trajectory_actions
84+
test/test_trajectory_actions.cpp
85+
)
86+
target_link_libraries(test_trajectory_actions
87+
joint_trajectory_controller
88+
)
9089
endif()
9190

9291

joint_trajectory_controller/test/test_trajectory_actions.cpp

Lines changed: 9 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -70,17 +70,13 @@ class TestTrajectoryActions : public TrajectoryControllerTest
7070
{
7171
setup_executor_ = true;
7272

73-
executor_ = std::make_unique<rclcpp::executors::MultiThreadedExecutor>();
74-
75-
SetUpAndActivateTrajectoryController(true, parameters);
76-
77-
executor_->add_node(traj_controller_->get_node()->get_node_base_interface());
73+
SetUpAndActivateTrajectoryController(executor_, true, parameters);
7874

7975
SetUpActionClient();
8076

81-
executor_->add_node(node_->get_node_base_interface());
77+
executor_.add_node(node_->get_node_base_interface());
8278

83-
executor_future_handle_ = std::async(std::launch::async, [&]() -> void { executor_->spin(); });
79+
executor_future_handle_ = std::async(std::launch::async, [&]() -> void { executor_.spin(); });
8480
}
8581

8682
void SetUpControllerHardware()
@@ -132,7 +128,7 @@ class TestTrajectoryActions : public TrajectoryControllerTest
132128
if (setup_executor_)
133129
{
134130
setup_executor_ = false;
135-
executor_->cancel();
131+
executor_.cancel();
136132
executor_future_handle_.wait();
137133
}
138134
}
@@ -169,7 +165,7 @@ class TestTrajectoryActions : public TrajectoryControllerTest
169165
int common_action_result_code_ = control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL;
170166

171167
bool setup_executor_ = false;
172-
rclcpp::executors::MultiThreadedExecutor::UniquePtr executor_;
168+
rclcpp::executors::MultiThreadedExecutor executor_;
173169
std::future<void> executor_future_handle_;
174170

175171
bool setup_controller_hw_ = false;
@@ -417,7 +413,7 @@ TEST_F(TestTrajectoryActions, test_state_tolerances_fail)
417413
common_action_result_code_);
418414

419415
// run an update, it should be holding
420-
traj_controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));
416+
updateController(rclcpp::Duration::from_seconds(0.01));
421417

422418
EXPECT_NEAR(INITIAL_POS_JOINT1, joint_pos_[0], COMMON_THRESHOLD);
423419
EXPECT_NEAR(INITIAL_POS_JOINT2, joint_pos_[1], COMMON_THRESHOLD);
@@ -467,7 +463,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_fail)
467463
common_action_result_code_);
468464

469465
// run an update, it should be holding
470-
traj_controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));
466+
updateController(rclcpp::Duration::from_seconds(0.01));
471467

472468
EXPECT_NEAR(init_pos1, joint_pos_[0], COMMON_THRESHOLD);
473469
EXPECT_NEAR(init_pos2, joint_pos_[1], COMMON_THRESHOLD);
@@ -514,7 +510,7 @@ TEST_F(TestTrajectoryActions, test_no_time_from_start_state_tolerance_fail)
514510
common_action_result_code_);
515511

516512
// run an update, it should be holding
517-
traj_controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));
513+
updateController(rclcpp::Duration::from_seconds(0.01));
518514

519515
EXPECT_NEAR(init_pos1, joint_pos_[0], COMMON_THRESHOLD);
520516
EXPECT_NEAR(init_pos2, joint_pos_[1], COMMON_THRESHOLD);
@@ -563,7 +559,7 @@ TEST_F(TestTrajectoryActions, test_cancel_hold_position)
563559
const double prev_pos3 = joint_pos_[2];
564560

565561
// run an update, it should be holding
566-
traj_controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));
562+
updateController(rclcpp::Duration::from_seconds(0.01));
567563

568564
EXPECT_EQ(prev_pos1, joint_pos_[0]);
569565
EXPECT_EQ(prev_pos2, joint_pos_[1]);

0 commit comments

Comments
 (0)