From 153f4657cb0b916da80aaf1969af4c78edec8651 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 27 Jun 2023 14:27:29 -0700 Subject: [PATCH 1/2] Fix smoother server tests --- nav2_smoother/test/test_smoother_server.cpp | 42 ++++++++++----------- 1 file changed, 20 insertions(+), 22 deletions(-) diff --git a/nav2_smoother/test/test_smoother_server.cpp b/nav2_smoother/test/test_smoother_server.cpp index f14934af06..a84b1cdc32 100644 --- a/nav2_smoother/test/test_smoother_server.cpp +++ b/nav2_smoother/test/test_smoother_server.cpp @@ -158,8 +158,8 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber DummyFootprintSubscriber( nav2_util::LifecycleNode::SharedPtr node, const std::string & topic_name, - tf2_ros::Buffer & tf) - : FootprintSubscriber(node, topic_name, tf) + tf2_ros::Buffer & tf_) + : FootprintSubscriber(node, topic_name, tf_) { auto footprint = std::make_shared(); footprint->header.frame_id = "base_link"; // global frame = robot frame to avoid tf lookup @@ -223,21 +223,16 @@ class DummySmootherServer : public nav2_smoother::SmootherServer }; // Define a test class to hold the context for the tests - -class SmootherConfigTest : public ::testing::Test -{ -}; - class SmootherTest : public ::testing::Test { -protected: - SmootherTest() {SetUp();} +public: + SmootherTest() {} ~SmootherTest() {} - void SetUp() + void SetUp() override { - node_lifecycle_ = - std::make_shared( + node_ = + std::make_shared( "LifecycleSmootherTestNode", rclcpp::NodeOptions()); smoother_server_ = std::make_shared(); @@ -252,10 +247,10 @@ class SmootherTest : public ::testing::Test smoother_server_->activate(); client_ = rclcpp_action::create_client( - node_lifecycle_->get_node_base_interface(), - node_lifecycle_->get_node_graph_interface(), - node_lifecycle_->get_node_logging_interface(), - node_lifecycle_->get_node_waitables_interface(), "smooth_path"); + node_->get_node_base_interface(), + node_->get_node_graph_interface(), + node_->get_node_logging_interface(), + node_->get_node_waitables_interface(), "smooth_path"); std::cout << "Setup complete." << std::endl; } @@ -264,6 +259,9 @@ class SmootherTest : public ::testing::Test smoother_server_->deactivate(); smoother_server_->cleanup(); smoother_server_->shutdown(); + smoother_server_.reset(); + client_.reset(); + node_.reset(); } bool sendGoal( @@ -291,7 +289,7 @@ class SmootherTest : public ::testing::Test auto future_goal = client_->async_send_goal(goal); - if (rclcpp::spin_until_future_complete(node_lifecycle_, future_goal) != + if (rclcpp::spin_until_future_complete(node_, future_goal) != rclcpp::FutureReturnCode::SUCCESS) { std::cout << "failed sending goal" << std::endl; @@ -315,12 +313,12 @@ class SmootherTest : public ::testing::Test std::cout << "Getting async result..." << std::endl; auto future_result = client_->async_get_result(goal_handle_); std::cout << "Waiting on future..." << std::endl; - rclcpp::spin_until_future_complete(node_lifecycle_, future_result); + rclcpp::spin_until_future_complete(node_, future_result); std::cout << "future received!" << std::endl; return future_result.get(); } - std::shared_ptr node_lifecycle_; + std::shared_ptr node_; std::shared_ptr smoother_server_; std::shared_ptr> client_; std::shared_ptr> goal_handle_; @@ -387,7 +385,7 @@ TEST_F(SmootherTest, testingCollisionCheckDisabled) SUCCEED(); } -TEST_F(SmootherConfigTest, testingConfigureSuccessWithValidSmootherPlugin) +TEST(SmootherConfigTest, testingConfigureSuccessWithValidSmootherPlugin) { auto smoother_server = std::make_shared(); smoother_server->set_parameter( @@ -402,7 +400,7 @@ TEST_F(SmootherConfigTest, testingConfigureSuccessWithValidSmootherPlugin) SUCCEED(); } -TEST_F(SmootherConfigTest, testingConfigureFailureWithInvalidSmootherPlugin) +TEST(SmootherConfigTest, testingConfigureFailureWithInvalidSmootherPlugin) { auto smoother_server = std::make_shared(); smoother_server->set_parameter( @@ -417,7 +415,7 @@ TEST_F(SmootherConfigTest, testingConfigureFailureWithInvalidSmootherPlugin) SUCCEED(); } -TEST_F(SmootherConfigTest, testingConfigureSuccessWithDefaultPlugin) +TEST(SmootherConfigTest, testingConfigureSuccessWithDefaultPlugin) { auto smoother_server = std::make_shared(); auto state = smoother_server->configure(); From 96b6d8ea031564e9a98bdcfbc974d5122683845c Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 27 Jun 2023 14:32:07 -0700 Subject: [PATCH 2/2] Update test_smoother_server.cpp --- nav2_smoother/test/test_smoother_server.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nav2_smoother/test/test_smoother_server.cpp b/nav2_smoother/test/test_smoother_server.cpp index a84b1cdc32..08e475de8e 100644 --- a/nav2_smoother/test/test_smoother_server.cpp +++ b/nav2_smoother/test/test_smoother_server.cpp @@ -158,8 +158,8 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber DummyFootprintSubscriber( nav2_util::LifecycleNode::SharedPtr node, const std::string & topic_name, - tf2_ros::Buffer & tf_) - : FootprintSubscriber(node, topic_name, tf_) + tf2_ros::Buffer & tf) + : FootprintSubscriber(node, topic_name, tf) { auto footprint = std::make_shared(); footprint->header.frame_id = "base_link"; // global frame = robot frame to avoid tf lookup