Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,7 @@ class RemoveInCollisionGoalsTestFixture : public ::testing::Test
config_ = nullptr;
node_.reset();
success_server_.reset();
failure_server_.reset();
factory_.reset();
}

Expand Down
2 changes: 2 additions & 0 deletions nav2_behavior_tree/test/test_bt_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,4 +470,6 @@ TEST(deconflictPortAndParamFrameTest, test_correct_syntax)
node, "test", tree.rootNode());

EXPECT_EQ(value, 1);

rclcpp::shutdown();
}
21 changes: 13 additions & 8 deletions nav2_collision_monitor/test/kinematics_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,6 @@ using namespace std::chrono_literals;

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

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

TEST(KinematicsTest, testTransformPoints)
{
// Transform: move frame to (2.0, 1.0) coordinate and rotate it on 30 degrees
Expand Down Expand Up @@ -96,3 +88,16 @@ TEST(KinematicsTest, testProjectState)
EXPECT_NEAR(vel.y, std::sin(rotated_vel_angle), EPSILON);
EXPECT_NEAR(vel.tw, M_PI / 4.0, EPSILON); // should be the same
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
10 changes: 8 additions & 2 deletions nav2_controller/plugins/test/goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,13 @@ TEST(StoppedGoalChecker, get_tol_and_dynamic_params)

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(argc, argv);
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
10 changes: 8 additions & 2 deletions nav2_controller/plugins/test/progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,13 @@ TEST(PoseProgressChecker, unit_tests)

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(argc, argv);
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_controller/test/test_dynamic_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,14 +51,6 @@ class ControllerShim : public nav2_controller::ControllerServer
}
};

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

TEST(WPTest, test_dynamic_parameters)
{
auto controller = std::make_shared<ControllerShim>();
Expand Down Expand Up @@ -86,3 +78,16 @@ TEST(WPTest, test_dynamic_parameters)
EXPECT_EQ(controller->get_parameter("min_theta_velocity_threshold").as_double(), 100.0);
EXPECT_EQ(controller->get_parameter("failure_tolerance").as_double(), 5.0);
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_costmap_2d/test/integration/dyn_params_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,6 @@
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
#include "tf2_ros/transform_broadcaster.h"

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

class DynParamTestNode
{
public:
Expand Down Expand Up @@ -105,3 +97,16 @@ TEST(DynParamTestNode, testDynParamsSet)
costmap->on_cleanup(rclcpp_lifecycle::State());
costmap->on_shutdown(rclcpp_lifecycle::State());
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_costmap_2d/test/integration/footprint_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,14 +44,6 @@
#include "tf2_ros/transform_listener.h"
#include "nav2_costmap_2d/footprint.hpp"

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

class FootprintTestNode
{
public:
Expand Down Expand Up @@ -202,3 +194,16 @@ TEST_F(TestNode, footprint_from_same_level_param)
EXPECT_EQ(6.0f, footprint[2].y);
EXPECT_EQ(0.0f, footprint[2].z);
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_costmap_2d/test/integration/inflation_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,14 +51,6 @@
using geometry_msgs::msg::Point;
using nav2_costmap_2d::CellData;

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

class TestNode : public ::testing::Test
{
public:
Expand Down Expand Up @@ -639,3 +631,16 @@ TEST_F(TestNode, testDynParamsSet)
costmap->on_cleanup(rclcpp_lifecycle::State());
costmap->on_shutdown(rclcpp_lifecycle::State());
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_costmap_2d/test/integration/obstacle_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,6 @@ using std::none_of;
using std::pair;
using std::string;

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

class TestLifecycleNode : public nav2_util::LifecycleNode
{
public:
Expand Down Expand Up @@ -625,3 +617,16 @@ TEST_F(TestNodeWithoutUnknownOverwrite, testMaxWithoutUnknownOverwriteCombinatio

ASSERT_EQ(unknown_count, 100);
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_costmap_2d/test/integration/plugin_container_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,14 +33,6 @@ using std::none_of;
using std::pair;
using std::string;

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

class TestLifecycleNode : public nav2_util::LifecycleNode
{
public:
Expand Down Expand Up @@ -686,3 +678,16 @@ TEST_F(TestNode, testDynParamsSetPluginContainerLayer)
costmap->on_cleanup(rclcpp_lifecycle::State());
costmap->on_shutdown(rclcpp_lifecycle::State());
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
29 changes: 13 additions & 16 deletions nav2_costmap_2d/test/integration/range_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,22 +53,6 @@ using std::none_of;
using std::pair;
using std::string;

class RclCppFixture
{
public:
RclCppFixture()
{
rclcpp::init(0, nullptr);
}

~RclCppFixture()
{
rclcpp::shutdown();
}
};

RclCppFixture g_rclcppfixture;

class TestLifecycleNode : public nav2_util::LifecycleNode
{
public:
Expand Down Expand Up @@ -292,3 +276,16 @@ TEST_F(TestNode, testProbabilisticModelDownward) {
ASSERT_EQ(layers.getCostmap()->getCost(3, 6), 0);
ASSERT_EQ(layers.getCostmap()->getCost(3, 7), 254);
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
21 changes: 13 additions & 8 deletions nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,14 +22,6 @@
#include "tf2_ros/transform_listener.h"
#include "nav2_costmap_2d/costmap_2d_ros.hpp"

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;

class CostmapRosLifecycleNode : public nav2_util::LifecycleNode
{
public:
Expand Down Expand Up @@ -178,3 +170,16 @@ TEST_F(CostmapRosTestFixture, costmap_pub_test)

SUCCEED();
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
20 changes: 13 additions & 7 deletions nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,6 @@
#include "nav2_costmap_2d/costmap_2d_publisher.hpp"
#include "nav2_costmap_2d/costmap_subscriber.hpp"

class RclCppFixture
{
public:
RclCppFixture() {rclcpp::init(0, nullptr);}
~RclCppFixture() {rclcpp::shutdown();}
};
RclCppFixture g_rclcppfixture;
class TestCostmapSubscriberShould : public ::testing::Test
{
public:
Expand Down Expand Up @@ -196,3 +189,16 @@ TEST_F(
{
ASSERT_ANY_THROW(costmapSubscriber->getCostmap());
}

int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);

rclcpp::init(0, nullptr);

int result = RUN_ALL_TESTS();

rclcpp::shutdown();

return result;
}
Loading
Loading