Skip to content

Commit 80374f5

Browse files
authored
Merge branch 'main' into seng/robot-trajectory-velocities
2 parents 8e24296 + 2f93d82 commit 80374f5

File tree

1 file changed

+4
-7
lines changed

1 file changed

+4
-7
lines changed

moveit_ros/planning/planning_request_adapter_plugins/test/test_check_start_state_bounds.cpp

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,6 @@ class TestCheckStartStateBounds : public testing::Test
5050
protected:
5151
void SetUp() override
5252
{
53-
rclcpp::init(0, nullptr);
5453
node_ = std::make_shared<rclcpp::Node>("test_check_start_state_bounds_adapter", "");
5554

5655
// Load a robot model and place it in a planning scene.
@@ -65,11 +64,6 @@ class TestCheckStartStateBounds : public testing::Test
6564
adapter_->initialize(node_, "");
6665
}
6766

68-
void TearDown() override
69-
{
70-
rclcpp::shutdown();
71-
}
72-
7367
std::shared_ptr<rclcpp::Node> node_;
7468
std::shared_ptr<planning_scene::PlanningScene> planning_scene_;
7569
std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlanningRequestAdapter>> plugin_loader_;
@@ -158,6 +152,9 @@ TEST_F(TestCheckStartStateBounds, TestContinuousJointFixedBounds)
158152

159153
int main(int argc, char** argv)
160154
{
155+
rclcpp::init(argc, argv);
161156
::testing::InitGoogleTest(&argc, argv);
162-
return RUN_ALL_TESTS();
157+
const int result = RUN_ALL_TESTS();
158+
rclcpp::shutdown();
159+
return result;
163160
}

0 commit comments

Comments
 (0)