diff --git a/rclcpp/test/benchmark/CMakeLists.txt b/rclcpp/test/benchmark/CMakeLists.txt index 91c28705b2..5d0a3f5afb 100644 --- a/rclcpp/test/benchmark/CMakeLists.txt +++ b/rclcpp/test/benchmark/CMakeLists.txt @@ -1,11 +1,21 @@ -# Give cppcheck hints about macro definitions coming from outside this package -get_target_property( - ament_cmake_cppcheck_ADDITIONAL_INCLUDE_DIRS - performance_test_fixture::performance_test_fixture - INTERFACE_INCLUDE_DIRECTORIES) +find_package(performance_test_fixture REQUIRED) +# +# Add a rmw-specific performance benchmark test from performance_test_fixture +# +# :param NAME: the target name which will also be used as the test name +# :type NAME: string +# :param SOURCE: the benchmark test target's source file +# :type SOURCE: string +# :param AMENT_DEPENDS: the ament dependincies for the benchmark test target +# :type list of strings +# :param LIBRARIES: the additional libraries the target needs to be linked +# against +# :type list of strings +# :param TEST_OPTIONS: arguments to pass directly to add_performance_test +# :type list of strings function(add_rclcpp_benchmark NAME SOURCE) - set(multiValueArgs AMENT_DEPENDS LIBRARIES) + set(multiValueArgs AMENT_DEPENDS LIBRARIES TEST_OPTIONS) cmake_parse_arguments( RCLCPP_BENCHMARK "" @@ -24,20 +34,37 @@ function(add_rclcpp_benchmark NAME SOURCE) set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) set(full_benchmark_name ${NAME}${target_suffix}) - add_performance_test(${full_benchmark_name} ${SOURCE} ENV ${rmw_implementation_env_var}) + add_performance_test( + ${full_benchmark_name} + ${SOURCE} + ${RCLCPP_BENCHMARK_TEST_OPTIONS} + ENV ${rmw_implementation_env_var}) if(TARGET ${full_benchmark_name}) if(RCLCPP_BENCHMARK_AMENT_DEPENDS) - ament_target_dependencies(${full_benchmark_name} ${RCLCPP_BENCHMARK_AMENT_DEPENDS}) + ament_target_dependencies( + ${full_benchmark_name} + ${RCLCPP_BENCHMARK_AMENT_DEPENDS}) endif() - target_link_libraries(${full_benchmark_name} ${PROJECT_NAME} ${RCLCPP_BENCHMARK_LIBRARIES}) + target_link_libraries( + ${full_benchmark_name} + ${PROJECT_NAME} + ${RCLCPP_BENCHMARK_LIBRARIES}) endif() endfunction() # Add new benchmarks inside this macro macro(rclcpp_benchmarks) - add_rclcpp_benchmark(benchmark_executor benchmark_executor.cpp AMENT_DEPENDS test_msgs) add_rclcpp_benchmark(benchmark_init_shutdown benchmark_init_shutdown.cpp) - add_rclcpp_benchmark(benchmark_node benchmark_node.cpp) + + set(SKIP_TEST "") + if(${rmw_implementation} MATCHES "(.*)connext(.*)") + set(SKIP_TEST "SKIP_TEST") + endif() + add_rclcpp_benchmark( + benchmark_node + benchmark_node.cpp + TEST_OPTIONS ${SKIP_TEST}) + add_rclcpp_benchmark(benchmark_executor benchmark_executor.cpp AMENT_DEPENDS test_msgs) endmacro() call_for_each_rmw_implementation(rclcpp_benchmarks) diff --git a/rclcpp/test/benchmark/benchmark_init_shutdown.cpp b/rclcpp/test/benchmark/benchmark_init_shutdown.cpp index e4b0f0bc87..6c3ae8b72e 100644 --- a/rclcpp/test/benchmark/benchmark_init_shutdown.cpp +++ b/rclcpp/test/benchmark/benchmark_init_shutdown.cpp @@ -20,6 +20,11 @@ using performance_test_fixture::PerformanceTest; BENCHMARK_F(PerformanceTest, rclcpp_init)(benchmark::State & state) { + // Warmup and prime caches + rclcpp::init(0, nullptr); + rclcpp::shutdown(); + + reset_heap_counters(); for (auto _ : state) { rclcpp::init(0, nullptr); @@ -32,6 +37,11 @@ BENCHMARK_F(PerformanceTest, rclcpp_init)(benchmark::State & state) BENCHMARK_F(PerformanceTest, rclcpp_shutdown)(benchmark::State & state) { + // Warmup and prime caches + rclcpp::init(0, nullptr); + rclcpp::shutdown(); + + reset_heap_counters(); for (auto _ : state) { state.PauseTiming(); rclcpp::init(0, nullptr); diff --git a/rclcpp/test/benchmark/benchmark_node.cpp b/rclcpp/test/benchmark/benchmark_node.cpp index c3f173c082..945b8f1122 100644 --- a/rclcpp/test/benchmark/benchmark_node.cpp +++ b/rclcpp/test/benchmark/benchmark_node.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include "performance_test_fixture/performance_test_fixture.hpp" #include "rclcpp/rclcpp.hpp" @@ -22,13 +23,13 @@ using performance_test_fixture::PerformanceTest; class NodePerformanceTest : public PerformanceTest { public: - void SetUp(::benchmark::State & state) + void SetUp(benchmark::State & state) { rclcpp::init(0, nullptr); performance_test_fixture::PerformanceTest::SetUp(state); } - void TearDown(::benchmark::State & state) + void TearDown(benchmark::State & state) { performance_test_fixture::PerformanceTest::TearDown(state); rclcpp::shutdown(); @@ -37,6 +38,11 @@ class NodePerformanceTest : public PerformanceTest BENCHMARK_F(NodePerformanceTest, create_node)(benchmark::State & state) { + // Warmup and prime caches + auto outer_node = std::make_unique("node"); + outer_node.reset(); + + reset_heap_counters(); for (auto _ : state) { // Using pointer to separate construction and destruction in timing auto node = std::make_unique("node"); @@ -52,6 +58,11 @@ BENCHMARK_F(NodePerformanceTest, create_node)(benchmark::State & state) BENCHMARK_F(NodePerformanceTest, destroy_node)(benchmark::State & state) { + // Warmup and prime caches + auto outer_node = std::make_unique("node"); + outer_node.reset(); + + reset_heap_counters(); for (auto _ : state) { // Using pointer to separate construction and destruction in timing state.PauseTiming(); diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index fa85dc94ba..7575f7cb3a 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -115,9 +115,9 @@ class ExecutorTypeNames } }; -// TYPED_TEST_CASE is deprecated as of gtest 1.9, use TYPED_TEST_SUITE when gtest dependency +// TYPED_TEST_SUITE is deprecated as of gtest 1.9, use TYPED_TEST_SUITE when gtest dependency // is updated. -TYPED_TEST_CASE(TestExecutors, ExecutorTypes, ExecutorTypeNames); +TYPED_TEST_SUITE(TestExecutors, ExecutorTypes, ExecutorTypeNames); // StaticSingleThreadedExecutor is not included in these tests for now, due to: // https://github.com/ros2/rclcpp/issues/1219 @@ -125,7 +125,7 @@ using StandardExecutors = ::testing::Types< rclcpp::executors::SingleThreadedExecutor, rclcpp::executors::MultiThreadedExecutor>; -TYPED_TEST_CASE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames); +TYPED_TEST_SUITE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames); // Make sure that executors detach from nodes when destructing TYPED_TEST(TestExecutors, detachOnDestruction) { diff --git a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp index d8f4076f56..5c63fd5962 100644 --- a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp +++ b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp @@ -79,7 +79,7 @@ class ExecutorTypeNames } }; -TYPED_TEST_CASE(TestAddCallbackGroupsToExecutor, ExecutorTypes, ExecutorTypeNames); +TYPED_TEST_SUITE(TestAddCallbackGroupsToExecutor, ExecutorTypes, ExecutorTypeNames); /* * Test adding callback groups. diff --git a/rclcpp/test/rclcpp/test_publisher.cpp b/rclcpp/test/rclcpp/test_publisher.cpp index 26aeb6975c..15390bd274 100644 --- a/rclcpp/test/rclcpp/test_publisher.cpp +++ b/rclcpp/test/rclcpp/test_publisher.cpp @@ -184,7 +184,7 @@ static std::vector invalid_qos_profiles() return parameters; } -INSTANTIATE_TEST_CASE_P( +INSTANTIATE_TEST_SUITE_P( TestPublisherThrows, TestPublisherInvalidIntraprocessQos, ::testing::ValuesIn(invalid_qos_profiles()), ::testing::PrintToStringParamName()); diff --git a/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp b/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp index 0a59ebe100..9e009acb95 100644 --- a/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp +++ b/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp @@ -192,7 +192,7 @@ using AllTestDescriptions = ::testing::Types< TwoSubscriptionsInTwoContextsWithIntraprocessComm, TwoSubscriptionsInTwoContextsWithoutIntraprocessComm >; -TYPED_TEST_CASE(TestPublisherSubscriptionCount, AllTestDescriptions, PrintTestDescription); +TYPED_TEST_SUITE(TestPublisherSubscriptionCount, AllTestDescriptions, PrintTestDescription); using test_msgs::msg::Empty; diff --git a/rclcpp/test/rclcpp/test_subscription.cpp b/rclcpp/test/rclcpp/test_subscription.cpp index ef43fc051c..2788b97bea 100644 --- a/rclcpp/test/rclcpp/test_subscription.cpp +++ b/rclcpp/test/rclcpp/test_subscription.cpp @@ -506,7 +506,7 @@ static std::vector invalid_qos_profiles() return parameters; } -INSTANTIATE_TEST_CASE_P( +INSTANTIATE_TEST_SUITE_P( TestSubscriptionThrows, TestSubscriptionInvalidIntraprocessQos, ::testing::ValuesIn(invalid_qos_profiles()), ::testing::PrintToStringParamName()); diff --git a/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp b/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp index 8da31f3060..1e71e28c5e 100644 --- a/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp +++ b/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp @@ -129,7 +129,7 @@ struct TwoContextsPerTest }; using AllTestDescriptions = ::testing::Types; -TYPED_TEST_CASE(TestSubscriptionPublisherCount, AllTestDescriptions, PrintTestDescription); +TYPED_TEST_SUITE(TestSubscriptionPublisherCount, AllTestDescriptions, PrintTestDescription); using test_msgs::msg::Empty;