From 075208a23b50a4429406937412b2756738ed144e Mon Sep 17 00:00:00 2001 From: Steven Macenski <stevenmacenski@gmail.com> Date: Tue, 4 Feb 2020 15:37:00 -0800 Subject: [PATCH] Fix CI (#1488) * fix tests and remove unnecessarily flaky test * fixing recoveries tests: 3/4 * fix flakyness of recoveries tests * adding setup complete message * flake8 bringup * unflaky the recoveries test * fixing action tests, part 2 * more prints, because why not --- .../bringup/launch/nav2_bringup_launch.py | 1 - .../launch/nav2_localization_launch.py | 7 -- .../bringup/launch/nav2_navigation_launch.py | 6 -- .../lifecycle_manager_client.hpp | 2 +- .../include/nav2_recoveries/recovery.hpp | 6 +- nav2_recoveries/test/test_recoveries.cpp | 49 ++++----- nav2_util/test/test_actions.cpp | 101 ++++++++++++------ 7 files changed, 94 insertions(+), 78 deletions(-) diff --git a/nav2_bringup/bringup/launch/nav2_bringup_launch.py b/nav2_bringup/bringup/launch/nav2_bringup_launch.py index 3701d0b9..cf7f6211 100644 --- a/nav2_bringup/bringup/launch/nav2_bringup_launch.py +++ b/nav2_bringup/bringup/launch/nav2_bringup_launch.py @@ -22,7 +22,6 @@ from launch.actions import (DeclareLaunchArgument, GroupAction, from launch.conditions import IfCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration -from launch_ros.actions import Node from launch_ros.actions import PushRosNamespace diff --git a/nav2_bringup/bringup/launch/nav2_localization_launch.py b/nav2_bringup/bringup/launch/nav2_localization_launch.py index 83d0a02b..b5b825d4 100644 --- a/nav2_bringup/bringup/launch/nav2_localization_launch.py +++ b/nav2_bringup/bringup/launch/nav2_localization_launch.py @@ -18,7 +18,6 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable -from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node from nav2_common.launch import RewrittenYaml @@ -33,10 +32,8 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time') autostart = LaunchConfiguration('autostart') params_file = LaunchConfiguration('params_file') - use_remappings = LaunchConfiguration('use_remappings') lifecycle_nodes = ['map_server', 'amcl'] - # Map fully qualified names to relative ones so the node's namespace can be prepended. # In case of the transforms (tf), currently, there doesn't seem to be a better alternative # https://github.com/ros/geometry2/issues/32 @@ -83,10 +80,6 @@ def generate_launch_description(): default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'), description='Full path to the ROS2 parameters file to use'), - DeclareLaunchArgument( - 'use_remappings', default_value='false', - description='Arguments to pass to all nodes launched by the file'), - Node( package='nav2_map_server', node_executable='map_server', diff --git a/nav2_bringup/bringup/launch/nav2_navigation_launch.py b/nav2_bringup/bringup/launch/nav2_navigation_launch.py index e5156a10..4105586a 100644 --- a/nav2_bringup/bringup/launch/nav2_navigation_launch.py +++ b/nav2_bringup/bringup/launch/nav2_navigation_launch.py @@ -18,7 +18,6 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable -from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node from nav2_common.launch import RewrittenYaml @@ -33,7 +32,6 @@ def generate_launch_description(): autostart = LaunchConfiguration('autostart') params_file = LaunchConfiguration('params_file') bt_xml_file = LaunchConfiguration('bt_xml_file') - use_remappings = LaunchConfiguration('use_remappings') map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local') lifecycle_nodes = ['controller_server', @@ -92,10 +90,6 @@ def generate_launch_description(): 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'), description='Full path to the behavior tree xml file to use'), - DeclareLaunchArgument( - 'use_remappings', default_value='false', - description='Arguments to pass to all nodes launched by the file'), - DeclareLaunchArgument( 'map_subscribe_transient_local', default_value='false', description='Whether to set the map subscriber QoS to transient local'), diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp index 5554c6e3..6fb69981 100644 --- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp +++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp @@ -45,7 +45,7 @@ public: /** * @brief A constructor for LifeCycleMangerClient */ - LifecycleManagerClient(const std::string & name); + explicit LifecycleManagerClient(const std::string & name); // Client-side interface to the Nav2 lifecycle manager /** diff --git a/nav2_recoveries/include/nav2_recoveries/recovery.hpp b/nav2_recoveries/include/nav2_recoveries/recovery.hpp index 404fd9ba..efce9033 100644 --- a/nav2_recoveries/include/nav2_recoveries/recovery.hpp +++ b/nav2_recoveries/include/nav2_recoveries/recovery.hpp @@ -97,7 +97,7 @@ public: node_->get_parameter("cycle_frequency", cycle_frequency_); - action_server_ = std::make_unique<ActionServer>(node_, recovery_name_, + action_server_ = std::make_shared<ActionServer>(node_, recovery_name_, std::bind(&Recovery::execute, this)); collision_checker_ = collision_checker; @@ -116,6 +116,8 @@ public: void activate() override { + RCLCPP_INFO(node_->get_logger(), "Activating %s", recovery_name_.c_str()); + vel_pub_->on_activate(); enabled_ = true; } @@ -130,7 +132,7 @@ protected: rclcpp_lifecycle::LifecycleNode::SharedPtr node_; std::string recovery_name_; rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr vel_pub_; - std::unique_ptr<ActionServer> action_server_; + std::shared_ptr<ActionServer> action_server_; std::shared_ptr<nav2_costmap_2d::CollisionChecker> collision_checker_; std::shared_ptr<tf2_ros::Buffer> tf_; diff --git a/nav2_recoveries/test/test_recoveries.cpp b/nav2_recoveries/test/test_recoveries.cpp index 45258a80..ed8fd101 100644 --- a/nav2_recoveries/test/test_recoveries.cpp +++ b/nav2_recoveries/test/test_recoveries.cpp @@ -17,6 +17,7 @@ #include <chrono> #include <iostream> #include <future> +#include <thread> #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" @@ -70,13 +71,10 @@ public: return Status::FAILED; } - // Fake getting the robot state, calculate and send control output - std::this_thread::sleep_for(2ms); - // For testing, pretend the robot takes some fixed // amount of time to complete the motion. auto current_time = std::chrono::system_clock::now(); - auto motion_duration = 5s; + auto motion_duration = 1s; if (current_time - start_time_ >= motion_duration) { // Movement was completed @@ -120,18 +118,18 @@ protected: std::string costmap_topic, footprint_topic; node_lifecycle_->get_parameter("costmap_topic", costmap_topic); node_lifecycle_->get_parameter("footprint_topic", footprint_topic); - std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_ = - std::make_unique<nav2_costmap_2d::CostmapSubscriber>( + std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_ = + std::make_shared<nav2_costmap_2d::CostmapSubscriber>( node_lifecycle_, costmap_topic); - std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_ = - std::make_unique<nav2_costmap_2d::FootprintSubscriber>( + std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_ = + std::make_shared<nav2_costmap_2d::FootprintSubscriber>( node_lifecycle_, footprint_topic, 1.0); std::shared_ptr<nav2_costmap_2d::CollisionChecker> collision_checker_ = std::make_shared<nav2_costmap_2d::CollisionChecker>( *costmap_sub_, *footprint_sub_, *tf_buffer_, node_lifecycle_->get_name(), "odom"); - recovery_ = std::make_unique<DummyRecovery>(); + recovery_ = std::make_shared<DummyRecovery>(); recovery_->configure(node_lifecycle_, "Recovery", tf_buffer_, collision_checker_); recovery_->activate(); @@ -140,6 +138,7 @@ protected: node_lifecycle_->get_node_graph_interface(), node_lifecycle_->get_node_logging_interface(), node_lifecycle_->get_node_waitables_interface(), "Recovery"); + std::cout << "Setup complete." << std::endl; } void TearDown() override {} @@ -151,7 +150,9 @@ protected: return false; } - auto future_goal = getGoal(command); + auto goal = RecoveryAction::Goal(); + goal.command.data = command; + auto future_goal = client_->async_send_goal(goal); if (rclcpp::spin_until_future_complete(node_lifecycle_, future_goal) != rclcpp::executor::FutureReturnCode::SUCCESS) @@ -172,13 +173,6 @@ protected: return true; } - std::shared_future<ClientGoalHandle::SharedPtr> getGoal(const std::string & command) - { - auto goal = RecoveryAction::Goal(); - goal.command.data = command; - return client_->async_send_goal(goal); - } - Status getOutcome() { if (getResult().code == rclcpp_action::ResultCode::SUCCEEDED) { @@ -190,18 +184,16 @@ protected: ClientGoalHandle::WrappedResult getResult() { + std::cout << "Getting async result..." << std::endl; auto future_result = client_->async_get_result(goal_handle_); - rclcpp::executor::FutureReturnCode frc; - - do { - frc = rclcpp::spin_until_future_complete(node_lifecycle_, future_result); - } while (frc != rclcpp::executor::FutureReturnCode::SUCCESS); - + std::cout << "Waiting on future..." << std::endl; + rclcpp::spin_until_future_complete(node_lifecycle_, future_result); + std::cout << "future received!" << std::endl; return future_result.get(); } std::shared_ptr<rclcpp_lifecycle::LifecycleNode> node_lifecycle_; - std::unique_ptr<DummyRecovery> recovery_; + std::shared_ptr<DummyRecovery> recovery_; std::shared_ptr<rclcpp_action::Client<RecoveryAction>> client_; std::shared_ptr<rclcpp_action::ClientGoalHandle<RecoveryAction>> goal_handle_; std::shared_ptr<tf2_ros::Buffer> tf_buffer_; @@ -214,27 +206,28 @@ TEST_F(RecoveryTest, testingSuccess) { ASSERT_TRUE(sendCommand("Testing success")); EXPECT_EQ(getOutcome(), Status::SUCCEEDED); + SUCCEED(); } TEST_F(RecoveryTest, testingFailureOnRun) { ASSERT_TRUE(sendCommand("Testing failure on run")); EXPECT_EQ(getOutcome(), Status::FAILED); + SUCCEED(); } TEST_F(RecoveryTest, testingFailureOnInit) { ASSERT_TRUE(sendCommand("Testing failure on init")); EXPECT_EQ(getOutcome(), Status::FAILED); + SUCCEED(); } TEST_F(RecoveryTest, testingSequentialFailures) { - ASSERT_TRUE(sendCommand("Testing failure on init")); - EXPECT_EQ(getOutcome(), Status::FAILED); - ASSERT_TRUE(sendCommand("Testing failure on run")); EXPECT_EQ(getOutcome(), Status::FAILED); + SUCCEED(); } int main(int argc, char ** argv) @@ -242,7 +235,7 @@ int main(int argc, char ** argv) ::testing::InitGoogleTest(&argc, argv); // initialize ROS - rclcpp::init(0, nullptr); + rclcpp::init(argc, argv); bool all_successful = RUN_ALL_TESTS(); diff --git a/nav2_util/test/test_actions.cpp b/nav2_util/test/test_actions.cpp index a306832e..97add822 100644 --- a/nav2_util/test/test_actions.cpp +++ b/nav2_util/test/test_actions.cpp @@ -42,7 +42,7 @@ public: void on_init() { - action_server_ = std::make_unique<nav2_util::SimpleActionServer<Fibonacci>>( + action_server_ = std::make_shared<nav2_util::SimpleActionServer<Fibonacci>>( shared_from_this(), "fibonacci", std::bind(&FibonacciServerNode::execute, this)); @@ -122,7 +122,7 @@ preempted: } private: - std::unique_ptr<nav2_util::SimpleActionServer<Fibonacci>> action_server_; + std::shared_ptr<nav2_util::SimpleActionServer<Fibonacci>> action_server_; rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr deactivate_subs_; rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr activate_subs_; rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr omit_preempt_subs_; @@ -135,14 +135,16 @@ class RclCppFixture public: RclCppFixture() { - rclcpp::init(0, nullptr); + } + + void Setup() + { server_thread_ = - std::make_unique<std::thread>(std::bind(&RclCppFixture::server_thread_func, this)); + std::make_shared<std::thread>(std::bind(&RclCppFixture::server_thread_func, this)); } ~RclCppFixture() { - rclcpp::shutdown(); server_thread_->join(); } @@ -155,7 +157,7 @@ public: node.reset(); } - std::unique_ptr<std::thread> server_thread_; + std::shared_ptr<std::thread> server_thread_; }; RclCppFixture g_rclcppfixture; @@ -215,8 +217,11 @@ protected: void TearDown() override { + std::cout << " Teardown" << std::endl; node_->on_term(); + std::cout << " Teardown..." << std::endl; node_.reset(); + std::cout << " Teardown complete" << std::endl; } std::shared_ptr<ActionTestNode> node_; @@ -230,19 +235,19 @@ TEST_F(ActionTest, test_simple_action) // Send the goal auto future_goal_handle = node_->action_client_->async_send_goal(goal); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); auto goal_handle = future_goal_handle.get(); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, future_result), + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); // The final result rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get(); - ASSERT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); // Sum all of the values in the requested fibonacci series int sum = 0; @@ -250,7 +255,8 @@ TEST_F(ActionTest, test_simple_action) sum += number; } - ASSERT_EQ(sum, 376); + EXPECT_EQ(sum, 376); + SUCCEED(); } TEST_F(ActionTest, test_simple_action_with_feedback) @@ -274,19 +280,19 @@ TEST_F(ActionTest, test_simple_action_with_feedback) // Send the goal auto future_goal_handle = node_->action_client_->async_send_goal(goal, send_goal_options); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); auto goal_handle = future_goal_handle.get(); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); // The final result rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get(); - ASSERT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); // Sum all of the values in the requested fibonacci series int sum = 0; @@ -294,8 +300,9 @@ TEST_F(ActionTest, test_simple_action_with_feedback) sum += number; } - ASSERT_EQ(sum, 143); - ASSERT_GE(feedback_sum, 0); // We should have received *some* feedback + EXPECT_EQ(sum, 143); + EXPECT_GE(feedback_sum, 0); // We should have received *some* feedback + SUCCEED(); } TEST_F(ActionTest, test_simple_action_activation_cycling) @@ -310,7 +317,8 @@ TEST_F(ActionTest, test_simple_action_activation_cycling) // Send the goal auto future_goal_handle = node_->action_client_->async_send_goal(goal); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + std::cout << "Sent goal, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); // Deactivate while running @@ -320,11 +328,12 @@ TEST_F(ActionTest, test_simple_action_activation_cycling) // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, future_result), + std::cout << "Getting result, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); // The action should be reported as aborted. - ASSERT_EQ(future_result.get().code, rclcpp_action::ResultCode::ABORTED); + EXPECT_EQ(future_result.get().code, rclcpp_action::ResultCode::ABORTED); // Cycle back to active node_->activate_server(); @@ -333,18 +342,21 @@ TEST_F(ActionTest, test_simple_action_activation_cycling) // Send the goal future_goal_handle = node_->action_client_->async_send_goal(goal); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + std::cout << "Sent goal, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); goal_handle = future_goal_handle.get(); // Wait for the result future_result = node_->action_client_->async_get_result(goal_handle); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, future_result), + std::cout << "Getting result, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); // Now the action should have been successfully executed. - ASSERT_EQ(future_result.get().code, rclcpp_action::ResultCode::SUCCEEDED); + EXPECT_EQ(future_result.get().code, rclcpp_action::ResultCode::SUCCEEDED); + SUCCEED(); } TEST_F(ActionTest, test_simple_action_preemption) @@ -357,7 +369,8 @@ TEST_F(ActionTest, test_simple_action_preemption) // Send the goal auto future_goal_handle = node_->action_client_->async_send_goal(goal); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + std::cout << "Sent goal, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); // Preempt the goal @@ -366,19 +379,21 @@ TEST_F(ActionTest, test_simple_action_preemption) // Send the goal future_goal_handle = node_->action_client_->async_send_goal(preemption_goal); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + std::cout << "Sent goal, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); auto goal_handle = future_goal_handle.get(); // Wait for the result auto future_result = node_->action_client_->async_get_result(goal_handle); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, future_result), + std::cout << "Getting result, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); // The final result rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get(); - ASSERT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); // Sum all of the values in the requested fibonacci series int sum = 0; @@ -386,7 +401,8 @@ TEST_F(ActionTest, test_simple_action_preemption) sum += number; } - ASSERT_EQ(sum, 1); + EXPECT_EQ(sum, 1); + SUCCEED(); } TEST_F(ActionTest, test_simple_action_preemption_after_succeeded) @@ -400,26 +416,32 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded) // Send the goal auto future_goal_handle = node_->action_client_->async_send_goal(goal); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + std::cout << "Sent goal, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); + std::cout << "Sending first goal" << std::endl; node_->omit_server_preemptions(); auto future_preempt_handle = node_->action_client_->async_send_goal(preemption); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, + std::cout << "Sending preemption, spinning til complete..." << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS); + std::cout << "Sent preempt" << std::endl; // Get the results auto goal_handle = future_goal_handle.get(); // Wait for the result of initial goal auto future_result = node_->action_client_->async_get_result(goal_handle); - ASSERT_EQ(rclcpp::spin_until_future_complete(node_, future_result), + std::cout << "Getting result, spinning until available" << std::endl; + EXPECT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); + std::cout << "Got initial goal result" << std::endl; // The final result rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get(); - ASSERT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); // Sum all of the values in the requested fibonacci series int sum = 0; @@ -427,19 +449,21 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded) sum += number; } - ASSERT_EQ(sum, 17710); + EXPECT_EQ(sum, 17710); // Now get the preemption result goal_handle = future_preempt_handle.get(); // Wait for the result of initial goal future_result = node_->action_client_->async_get_result(goal_handle); + std::cout << "Geting result" << std::endl; ASSERT_EQ(rclcpp::spin_until_future_complete(node_, future_result), rclcpp::executor::FutureReturnCode::SUCCESS); + std::cout << "Got result" << std::endl; // The final result result = future_result.get(); - ASSERT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); // Sum all of the values in the requested fibonacci series sum = 0; @@ -447,5 +471,16 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded) sum += number; } - ASSERT_EQ(sum, 1); + EXPECT_EQ(sum, 1); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + g_rclcppfixture.Setup(); + ::testing::InitGoogleTest(&argc, argv); + auto result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + rclcpp::Rate(1).sleep(); + return result; } -- GitLab