Skip to content

Commit bb047c8

Browse files
committed
Cleanup unit tests
- Unify move_to.launch.py and test_task_model.launch.py - Rename them to test.launch.py as they are independent of the executable - Move Node creation to the fixture constructor - Replace Task::setRobotModel(loadModel()) with Task::loadRobotModel()
1 parent a9ddbe1 commit bb047c8

File tree

8 files changed

+22
-35
lines changed

8 files changed

+22
-35
lines changed

core/test/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,8 @@ if (BUILD_TESTING)
5454
mtc_add_gmock(test_cost_queue.cpp)
5555
mtc_add_gmock(test_interface_state.cpp)
5656

57-
mtc_add_gtest(test_move_to.cpp move_to.launch.py)
58-
mtc_add_gtest(test_move_relative.cpp move_to.launch.py)
57+
mtc_add_gtest(test_move_to.cpp test.launch.py)
58+
mtc_add_gtest(test_move_relative.cpp test.launch.py)
5959
mtc_add_gtest(test_pipeline_planner.cpp)
6060

6161
# building these integration tests works without moveit config packages

core/test/models.cpp

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,3 @@ RobotModelPtr getModel() {
1717
builder.addEndEffector("eef", "link2", "group", "eef_group");
1818
return builder.build();
1919
}
20-
21-
moveit::core::RobotModelPtr loadModel(const rclcpp::Node::SharedPtr& node) {
22-
robot_model_loader::RobotModelLoader loader(node);
23-
return loader.getModel();
24-
}

core/test/models.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,3 @@ MOVEIT_CLASS_FORWARD(RobotModel);
1111

1212
// get a hard-coded model
1313
moveit::core::RobotModelPtr getModel();
14-
15-
// load a model from robot_description
16-
moveit::core::RobotModelPtr loadModel(const rclcpp::Node::SharedPtr& node);
File renamed without changes.

core/test/test_move_relative.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,18 +26,18 @@ struct PandaMoveRelative : public testing::Test
2626
Task t;
2727
stages::MoveRelative* move;
2828
PlanningScenePtr scene;
29-
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("panda_move_relative");
29+
rclcpp::Node::SharedPtr node;
3030

3131
const JointModelGroup* group;
3232

3333
PandaMoveRelative() {
34-
t.setRobotModel(loadModel(node));
34+
t.loadRobotModel(rclcpp::Node::make_shared("panda_move_relative"));
3535

3636
group = t.getRobotModel()->getJointModelGroup("panda_arm");
3737

3838
scene = std::make_shared<PlanningScene>(t.getRobotModel());
3939
scene->getCurrentStateNonConst().setToDefaultValues();
40-
scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"), "ready");
40+
scene->getCurrentStateNonConst().setToDefaultValues(group, "ready");
4141
t.add(std::make_unique<stages::FixedState>("start", scene));
4242

4343
auto move_relative = std::make_unique<stages::MoveRelative>("move", std::make_shared<solvers::CartesianPath>());

core/test/test_move_to.cpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -34,20 +34,22 @@ struct PandaMoveTo : public testing::Test
3434
Task t;
3535
stages::MoveTo* move_to;
3636
PlanningScenePtr scene;
37-
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("panda_move_to");
37+
rclcpp::Node::SharedPtr node;
3838

3939
PandaMoveTo() {
40+
node = rclcpp::Node::make_shared("panda_move_to");
4041
t.loadRobotModel(node);
4142

43+
auto group = t.getRobotModel()->getJointModelGroup("panda_arm");
44+
4245
scene = std::make_shared<PlanningScene>(t.getRobotModel());
4346
scene->getCurrentStateNonConst().setToDefaultValues();
44-
scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"),
45-
"extended");
47+
scene->getCurrentStateNonConst().setToDefaultValues(group, "extended");
4648
t.add(std::make_unique<stages::FixedState>("start", scene));
4749

4850
auto move = std::make_unique<stages::MoveTo>("move", std::make_shared<solvers::JointInterpolationPlanner>());
4951
move_to = move.get();
50-
move_to->setGroup("panda_arm");
52+
move_to->setGroup(group->getName());
5153
t.add(std::move(move));
5254
}
5355
};
@@ -162,7 +164,7 @@ TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) {
162164
// will strongly deviate from the joint-space goal.
163165
TEST(Panda, connectCartesianBranchesFails) {
164166
Task t;
165-
t.setRobotModel(loadModel(rclcpp::Node::make_shared("panda_move_to")));
167+
t.loadRobotModel(rclcpp::Node::make_shared("panda_move_to"));
166168
auto scene = std::make_shared<PlanningScene>(t.getRobotModel());
167169
scene->getCurrentStateNonConst().setToDefaultValues();
168170
scene->getCurrentStateNonConst().setToDefaultValues(t.getRobotModel()->getJointModelGroup("panda_arm"), "ready");

visualization/motion_planning_tasks/test/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,6 @@ if (BUILD_TESTING)
1919
ament_add_gtest_executable(${PROJECT_NAME}-test-task_model test_task_model.cpp)
2020
target_link_libraries(${PROJECT_NAME}-test-task_model
2121
motion_planning_tasks_rviz_plugin)
22-
add_launch_test(test_task_model.launch.py
23-
ARGS "test_binary_dir:=$<TARGET_FILE_DIR:${PROJECT_NAME}-test-task_model>")
22+
add_launch_test(test.launch.py
23+
ARGS "test_binary:=$<TARGET_FILE:${PROJECT_NAME}-test-task_model>")
2424
endif()

visualization/motion_planning_tasks/test/test_task_model.launch.py renamed to visualization/motion_planning_tasks/test/test.launch.py

Lines changed: 8 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -13,36 +13,29 @@
1313

1414
@pytest.mark.launch_test
1515
def generate_test_description():
16-
test_task_model = GTest(
17-
path=[
18-
PathJoinSubstitution(
19-
[
20-
LaunchConfiguration("test_binary_dir"),
21-
"moveit_task_constructor_visualization-test-task_model",
22-
]
23-
)
24-
],
16+
test_exec = GTest(
17+
path=[LaunchConfiguration("test_binary")],
2518
output="screen",
2619
)
2720
return (
2821
LaunchDescription(
2922
[
3023
DeclareLaunchArgument(
31-
name="test_binary_dir",
32-
description="Binary directory of package containing test executables",
24+
name="test_binary",
25+
description="Test executable",
3326
),
34-
test_task_model,
27+
test_exec,
3528
KeepAliveProc(),
3629
ReadyToTest(),
3730
]
3831
),
39-
{"test_task_model": test_task_model},
32+
{"test_exec": test_exec},
4033
)
4134

4235

4336
class TestTerminatingProcessStops(unittest.TestCase):
44-
def test_gtest_run_complete(self, proc_info, test_task_model):
45-
proc_info.assertWaitForShutdown(process=test_task_model, timeout=4000.0)
37+
def test_gtest_run_complete(self, proc_info, test_exec):
38+
proc_info.assertWaitForShutdown(process=test_exec, timeout=4000.0)
4639

4740

4841
@launch_testing.post_shutdown_test()

0 commit comments

Comments
 (0)