forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathbenchmark_node.cpp
More file actions
81 lines (69 loc) · 2.24 KB
/
benchmark_node.cpp
File metadata and controls
81 lines (69 loc) · 2.24 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
// 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");
#ifndef __clang_analyzer__
benchmark::DoNotOptimize(node);
#endif
benchmark::ClobberMemory();
// 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();
#ifndef __clang_analyzer__
benchmark::DoNotOptimize(node);
#endif
benchmark::ClobberMemory();
node.reset();
}
}