forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathbenchmark_init_shutdown.cpp
More file actions
53 lines (44 loc) · 1.42 KB
/
benchmark_init_shutdown.cpp
File metadata and controls
53 lines (44 loc) · 1.42 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
// 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();
}
}