-
Notifications
You must be signed in to change notification settings - Fork 527
Initial benchmark tests for rclcpp::init/shutdown create/destroy node #1411
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from all commits
544cdf1
2d2b969
45ec412
181e859
d29ae73
48c27ea
df156e1
7e1e39a
5304998
87d4af0
94bc919
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,69 @@ | ||
| 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 TEST_OPTIONS) | ||
| cmake_parse_arguments( | ||
| RCLCPP_BENCHMARK | ||
| "" | ||
| "" | ||
| "${multiValueArgs}" | ||
| "${ARGN}") | ||
| if(RCLCPP_BENCHMARK_UNPARSED_ARGUMENTS) | ||
| message( | ||
| FATAL_ERROR | ||
| "Unrecognized arguments for 'add_rclcpp_benchmark'" | ||
| " (${RCLCPP_BENCHMARK_UNPARSED_ARGUMENTS})") | ||
| return() | ||
| endif() | ||
| find_package(${rmw_implementation} REQUIRED) | ||
| message(STATUS "Adding ${NAME} for '${rmw_implementation}'") | ||
| set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) | ||
|
|
||
| set(full_benchmark_name ${NAME}${target_suffix}) | ||
| 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}) | ||
| endif() | ||
| 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_init_shutdown benchmark_init_shutdown.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}) | ||
| endmacro() | ||
|
|
||
| call_for_each_rmw_implementation(rclcpp_benchmarks) | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,53 @@ | ||
| // Copyright 2020 Open Source Robotics Foundation, Inc. | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #include "performance_test_fixture/performance_test_fixture.hpp" | ||
|
|
||
| #include "rclcpp/rclcpp.hpp" | ||
|
|
||
| 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); | ||
|
|
||
| state.PauseTiming(); | ||
| rclcpp::shutdown(); | ||
| state.ResumeTiming(); | ||
| benchmark::ClobberMemory(); | ||
| } | ||
| } | ||
|
|
||
| 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); | ||
| state.ResumeTiming(); | ||
|
|
||
| rclcpp::shutdown(); | ||
| benchmark::ClobberMemory(); | ||
| } | ||
| } |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,77 @@ | ||
| // Copyright 2020 Open Source Robotics Foundation, Inc. | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #include <memory> | ||
| #include <string> | ||
|
|
||
| #include "performance_test_fixture/performance_test_fixture.hpp" | ||
| #include "rclcpp/rclcpp.hpp" | ||
|
|
||
| using performance_test_fixture::PerformanceTest; | ||
|
|
||
| class NodePerformanceTest : public PerformanceTest | ||
| { | ||
| public: | ||
| void SetUp(benchmark::State & state) | ||
| { | ||
| rclcpp::init(0, nullptr); | ||
| performance_test_fixture::PerformanceTest::SetUp(state); | ||
| } | ||
|
|
||
| void TearDown(benchmark::State & state) | ||
| { | ||
| performance_test_fixture::PerformanceTest::TearDown(state); | ||
| rclcpp::shutdown(); | ||
| } | ||
| }; | ||
|
|
||
| BENCHMARK_F(NodePerformanceTest, create_node)(benchmark::State & state) | ||
| { | ||
| // Warmup and prime caches | ||
| auto outer_node = std::make_shared<rclcpp::Node>("node"); | ||
| outer_node.reset(); | ||
|
|
||
| reset_heap_counters(); | ||
| for (auto _ : state) { | ||
| // Using pointer to separate construction and destruction in timing | ||
| auto node = std::make_shared<rclcpp::Node>("node"); | ||
| benchmark::DoNotOptimize(node); | ||
| benchmark::ClobberMemory(); | ||
|
Comment on lines
+49
to
+50
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I could never observe any change in behavior when I used these. Could you share the results with/without it?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The difficult thing about comparing results with this is that Here are two simple examples which shows what gets optimized and what doesn't. A little more context: |
||
|
|
||
| // Ensure destruction of node is not counted toward timing | ||
| state.PauseTiming(); | ||
| node.reset(); | ||
| state.ResumeTiming(); | ||
| } | ||
| } | ||
|
|
||
| BENCHMARK_F(NodePerformanceTest, destroy_node)(benchmark::State & state) | ||
| { | ||
| // Warmup and prime caches | ||
| auto outer_node = std::make_shared<rclcpp::Node>("node"); | ||
| outer_node.reset(); | ||
|
|
||
| reset_heap_counters(); | ||
| for (auto _ : state) { | ||
| // Using pointer to separate construction and destruction in timing | ||
| state.PauseTiming(); | ||
| auto node = std::make_shared<rclcpp::Node>("node"); | ||
| state.ResumeTiming(); | ||
|
|
||
| benchmark::DoNotOptimize(node); | ||
| benchmark::ClobberMemory(); | ||
|
|
||
| node.reset(); | ||
| } | ||
| } | ||
Uh oh!
There was an error while loading. Please reload this page.