Skip to content
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

Initial benchmark tests for rclcpp::init/shutdown create/destroy node #1411

Merged
merged 11 commits into from
Oct 22, 2020
1 change: 1 addition & 0 deletions rclcpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>mimick_vendor</test_depend>
<test_depend>performance_test_fixture</test_depend>
<test_depend>rmw</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>
<test_depend>rosidl_default_generators</test_depend>
Expand Down
1 change: 1 addition & 0 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}_test_msgs
SKIP_INSTALL
)

add_subdirectory(benchmark)
add_subdirectory(rclcpp)

ament_add_gtest(test_rclcpp_gtest_macros utils/test_rclcpp_gtest_macros.cpp)
Expand Down
69 changes: 69 additions & 0 deletions rclcpp/test/benchmark/CMakeLists.txt
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})
ahcorde marked this conversation as resolved.
Show resolved Hide resolved

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)
53 changes: 53 additions & 0 deletions rclcpp/test/benchmark/benchmark_init_shutdown.cpp
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();
}
}
77 changes: 77 additions & 0 deletions rclcpp/test/benchmark/benchmark_node.cpp
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
Copy link
Member

Choose a reason for hiding this comment

The 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?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The difficult thing about comparing results with this is that DoNotOptimize() doesn't remove all optimizations. So sometimes it's important to include and sometimes it makes no difference. Because ultimately the compiler's optimizations will be different depending on the platform and optimization level, I thought it would be better to include it. Even though for this example it doesn't make much difference.

Here are two simple examples which shows what gets optimized and what doesn't.
https://godbolt.org/z/c6aP3d with DoNotOptimize
https://godbolt.org/z/8ee5sT without

A little more context:
google/benchmark#242 (comment)


// 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();
}
}