Skip to content

Commit 9f0af3b

Browse files
authored
Use main function instead of global variable to setup the test environment. (#4948)
* Use the main function to setup the test environment. Signed-off-by: ChenYing Kuo <evshary@gmail.com> * Apply the modification to all the tests. Signed-off-by: ChenYing Kuo <evshary@gmail.com> * Refactor the test_remove_in_collision_goals_action. Signed-off-by: ChenYing Kuo <evshary@gmail.com> * Add the missing test items. Signed-off-by: ChenYing Kuo <evshary@gmail.com> * Revert "Refactor the test_remove_in_collision_goals_action." This reverts commit 3d0e468. Signed-off-by: ChenYing Kuo <evshary@gmail.com> * Reset failure_server_ Signed-off-by: ChenYing Kuo <evshary@gmail.com> --------- Signed-off-by: ChenYing Kuo <evshary@gmail.com>
1 parent ec4481a commit 9f0af3b

File tree

72 files changed

+871
-543
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

72 files changed

+871
-543
lines changed

nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,7 @@ class RemoveInCollisionGoalsTestFixture : public ::testing::Test
106106
config_ = nullptr;
107107
node_.reset();
108108
success_server_.reset();
109+
failure_server_.reset();
109110
factory_.reset();
110111
}
111112

nav2_behavior_tree/test/test_bt_utils.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -470,4 +470,6 @@ TEST(deconflictPortAndParamFrameTest, test_correct_syntax)
470470
node, "test", tree.rootNode());
471471

472472
EXPECT_EQ(value, 1);
473+
474+
rclcpp::shutdown();
473475
}

nav2_collision_monitor/test/kinematics_test.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -29,14 +29,6 @@ using namespace std::chrono_literals;
2929

3030
static constexpr double EPSILON = std::numeric_limits<float>::epsilon();
3131

32-
class RclCppFixture
33-
{
34-
public:
35-
RclCppFixture() {rclcpp::init(0, nullptr);}
36-
~RclCppFixture() {rclcpp::shutdown();}
37-
};
38-
RclCppFixture g_rclcppfixture;
39-
4032
TEST(KinematicsTest, testTransformPoints)
4133
{
4234
// Transform: move frame to (2.0, 1.0) coordinate and rotate it on 30 degrees
@@ -96,3 +88,16 @@ TEST(KinematicsTest, testProjectState)
9688
EXPECT_NEAR(vel.y, std::sin(rotated_vel_angle), EPSILON);
9789
EXPECT_NEAR(vel.tw, M_PI / 4.0, EPSILON); // should be the same
9890
}
91+
92+
int main(int argc, char **argv)
93+
{
94+
::testing::InitGoogleTest(&argc, argv);
95+
96+
rclcpp::init(0, nullptr);
97+
98+
int result = RUN_ALL_TESTS();
99+
100+
rclcpp::shutdown();
101+
102+
return result;
103+
}

nav2_controller/plugins/test/goal_checker.cpp

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -239,7 +239,13 @@ TEST(StoppedGoalChecker, get_tol_and_dynamic_params)
239239

240240
int main(int argc, char ** argv)
241241
{
242+
::testing::InitGoogleTest(&argc, argv);
243+
242244
rclcpp::init(argc, argv);
243-
testing::InitGoogleTest(&argc, argv);
244-
return RUN_ALL_TESTS();
245+
246+
int result = RUN_ALL_TESTS();
247+
248+
rclcpp::shutdown();
249+
250+
return result;
245251
}

nav2_controller/plugins/test/progress_checker.cpp

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,13 @@ TEST(PoseProgressChecker, unit_tests)
238238

239239
int main(int argc, char ** argv)
240240
{
241+
::testing::InitGoogleTest(&argc, argv);
242+
241243
rclcpp::init(argc, argv);
242-
testing::InitGoogleTest(&argc, argv);
243-
return RUN_ALL_TESTS();
244+
245+
int result = RUN_ALL_TESTS();
246+
247+
rclcpp::shutdown();
248+
249+
return result;
244250
}

nav2_controller/test/test_dynamic_parameters.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -51,14 +51,6 @@ class ControllerShim : public nav2_controller::ControllerServer
5151
}
5252
};
5353

54-
class RclCppFixture
55-
{
56-
public:
57-
RclCppFixture() {rclcpp::init(0, nullptr);}
58-
~RclCppFixture() {rclcpp::shutdown();}
59-
};
60-
RclCppFixture g_rclcppfixture;
61-
6254
TEST(WPTest, test_dynamic_parameters)
6355
{
6456
auto controller = std::make_shared<ControllerShim>();
@@ -86,3 +78,16 @@ TEST(WPTest, test_dynamic_parameters)
8678
EXPECT_EQ(controller->get_parameter("min_theta_velocity_threshold").as_double(), 100.0);
8779
EXPECT_EQ(controller->get_parameter("failure_tolerance").as_double(), 5.0);
8880
}
81+
82+
int main(int argc, char **argv)
83+
{
84+
::testing::InitGoogleTest(&argc, argv);
85+
86+
rclcpp::init(0, nullptr);
87+
88+
int result = RUN_ALL_TESTS();
89+
90+
rclcpp::shutdown();
91+
92+
return result;
93+
}

nav2_costmap_2d/test/integration/dyn_params_tests.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -21,14 +21,6 @@
2121
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
2222
#include "tf2_ros/transform_broadcaster.h"
2323

24-
class RclCppFixture
25-
{
26-
public:
27-
RclCppFixture() {rclcpp::init(0, nullptr);}
28-
~RclCppFixture() {rclcpp::shutdown();}
29-
};
30-
RclCppFixture g_rclcppfixture;
31-
3224
class DynParamTestNode
3325
{
3426
public:
@@ -105,3 +97,16 @@ TEST(DynParamTestNode, testDynParamsSet)
10597
costmap->on_cleanup(rclcpp_lifecycle::State());
10698
costmap->on_shutdown(rclcpp_lifecycle::State());
10799
}
100+
101+
int main(int argc, char **argv)
102+
{
103+
::testing::InitGoogleTest(&argc, argv);
104+
105+
rclcpp::init(0, nullptr);
106+
107+
int result = RUN_ALL_TESTS();
108+
109+
rclcpp::shutdown();
110+
111+
return result;
112+
}

nav2_costmap_2d/test/integration/footprint_tests.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -44,14 +44,6 @@
4444
#include "tf2_ros/transform_listener.h"
4545
#include "nav2_costmap_2d/footprint.hpp"
4646

47-
class RclCppFixture
48-
{
49-
public:
50-
RclCppFixture() {rclcpp::init(0, nullptr);}
51-
~RclCppFixture() {rclcpp::shutdown();}
52-
};
53-
RclCppFixture g_rclcppfixture;
54-
5547
class FootprintTestNode
5648
{
5749
public:
@@ -202,3 +194,16 @@ TEST_F(TestNode, footprint_from_same_level_param)
202194
EXPECT_EQ(6.0f, footprint[2].y);
203195
EXPECT_EQ(0.0f, footprint[2].z);
204196
}
197+
198+
int main(int argc, char **argv)
199+
{
200+
::testing::InitGoogleTest(&argc, argv);
201+
202+
rclcpp::init(0, nullptr);
203+
204+
int result = RUN_ALL_TESTS();
205+
206+
rclcpp::shutdown();
207+
208+
return result;
209+
}

nav2_costmap_2d/test/integration/inflation_tests.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -51,14 +51,6 @@
5151
using geometry_msgs::msg::Point;
5252
using nav2_costmap_2d::CellData;
5353

54-
class RclCppFixture
55-
{
56-
public:
57-
RclCppFixture() {rclcpp::init(0, nullptr);}
58-
~RclCppFixture() {rclcpp::shutdown();}
59-
};
60-
RclCppFixture g_rclcppfixture;
61-
6254
class TestNode : public ::testing::Test
6355
{
6456
public:
@@ -639,3 +631,16 @@ TEST_F(TestNode, testDynParamsSet)
639631
costmap->on_cleanup(rclcpp_lifecycle::State());
640632
costmap->on_shutdown(rclcpp_lifecycle::State());
641633
}
634+
635+
int main(int argc, char **argv)
636+
{
637+
::testing::InitGoogleTest(&argc, argv);
638+
639+
rclcpp::init(0, nullptr);
640+
641+
int result = RUN_ALL_TESTS();
642+
643+
rclcpp::shutdown();
644+
645+
return result;
646+
}

nav2_costmap_2d/test/integration/obstacle_tests.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -52,14 +52,6 @@ using std::none_of;
5252
using std::pair;
5353
using std::string;
5454

55-
class RclCppFixture
56-
{
57-
public:
58-
RclCppFixture() {rclcpp::init(0, nullptr);}
59-
~RclCppFixture() {rclcpp::shutdown();}
60-
};
61-
RclCppFixture g_rclcppfixture;
62-
6355
class TestLifecycleNode : public nav2_util::LifecycleNode
6456
{
6557
public:
@@ -625,3 +617,16 @@ TEST_F(TestNodeWithoutUnknownOverwrite, testMaxWithoutUnknownOverwriteCombinatio
625617

626618
ASSERT_EQ(unknown_count, 100);
627619
}
620+
621+
int main(int argc, char **argv)
622+
{
623+
::testing::InitGoogleTest(&argc, argv);
624+
625+
rclcpp::init(0, nullptr);
626+
627+
int result = RUN_ALL_TESTS();
628+
629+
rclcpp::shutdown();
630+
631+
return result;
632+
}

0 commit comments

Comments
 (0)