-
Notifications
You must be signed in to change notification settings - Fork 39
Added benchmark test to rcl_logging_spdlog #52
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
Merged
Merged
Changes from 5 commits
Commits
Show all changes
9 commits
Select commit
Hold shift + click to select a range
6998cfc
Added benchmark test to rcl_logging_spdlog
ahcorde 5aa9600
Added dependencies
ahcorde d34392b
Fixed type
ahcorde 93902fd
reset heap counters
ahcorde 7058f68
Added feedback
ahcorde 0ddc7f6
added feedback
ahcorde 4bf7cf8
Change init/shutdown tests to be consistent
cottsay 8e9f07d
Fix heap allocation statistics
cottsay 72e44cc
Drop an unnecessary include directive
cottsay File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
117 changes: 117 additions & 0 deletions
117
rcl_logging_spdlog/test/benchmark/benchmark_logging_interface.cpp
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,117 @@ | ||
| // 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 <rcutils/allocator.h> | ||
| #include <rcutils/logging.h> | ||
|
|
||
| #include <rcl_logging_interface/rcl_logging_interface.h> | ||
|
|
||
| #include <string> | ||
|
|
||
| #include "performance_test_fixture/performance_test_fixture.hpp" | ||
|
|
||
| using performance_test_fixture::PerformanceTest; | ||
|
|
||
| namespace | ||
| { | ||
| constexpr const uint64_t kSize = 4096; | ||
| } | ||
|
|
||
| const int logger_levels[] = | ||
| { | ||
| RCUTILS_LOG_SEVERITY_UNSET, | ||
| RCUTILS_LOG_SEVERITY_DEBUG, | ||
| RCUTILS_LOG_SEVERITY_INFO, | ||
| RCUTILS_LOG_SEVERITY_WARN, | ||
| RCUTILS_LOG_SEVERITY_ERROR, | ||
| RCUTILS_LOG_SEVERITY_FATAL, | ||
| }; | ||
|
|
||
| class LoggingBenchmarkPerformance : public PerformanceTest | ||
| { | ||
| public: | ||
| void SetUp(benchmark::State & st) | ||
| { | ||
| allocator = rcutils_get_default_allocator(); | ||
|
|
||
| rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, allocator); | ||
| if (ret != RCL_LOGGING_RET_OK) { | ||
| st.SkipWithError(rcutils_get_error_string().str); | ||
| } | ||
|
|
||
| data = std::string(kSize, '0'); | ||
| PerformanceTest::SetUp(st); | ||
| } | ||
| void TearDown(benchmark::State & st) | ||
| { | ||
| PerformanceTest::TearDown(st); | ||
| rcl_logging_ret_t ret = rcl_logging_external_shutdown(); | ||
| if (ret != RCL_LOGGING_RET_OK) { | ||
| st.SkipWithError(rcutils_get_error_string().str); | ||
| } | ||
| } | ||
|
|
||
| static void setLogLevel(int logger_level, benchmark::State & st) | ||
| { | ||
| rcl_logging_ret_t ret = rcl_logging_external_set_logger_level(nullptr, logger_level); | ||
| if (ret != RCL_LOGGING_RET_OK) { | ||
| st.SkipWithError(rcutils_get_error_string().str); | ||
| } | ||
| } | ||
|
|
||
| rcutils_allocator_t allocator; | ||
ahcorde marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| std::string data; | ||
| }; | ||
|
|
||
| BENCHMARK_DEFINE_F(LoggingBenchmarkPerformance, log_level_hit)(benchmark::State & st) | ||
| { | ||
| setLogLevel(RCUTILS_LOG_SEVERITY_INFO, st); | ||
| for (auto _ : st) { | ||
| rcl_logging_external_log(RCUTILS_LOG_SEVERITY_INFO, nullptr, data.c_str()); | ||
| } | ||
| } | ||
| BENCHMARK_REGISTER_F(LoggingBenchmarkPerformance, log_level_hit); | ||
ahcorde marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
|
||
| BENCHMARK_DEFINE_F(LoggingBenchmarkPerformance, log_level_miss)(benchmark::State & st) | ||
| { | ||
| setLogLevel(RCUTILS_LOG_SEVERITY_INFO, st); | ||
| for (auto _ : st) { | ||
| rcl_logging_external_log(RCUTILS_LOG_SEVERITY_DEBUG, nullptr, data.c_str()); | ||
| } | ||
| } | ||
| BENCHMARK_REGISTER_F(LoggingBenchmarkPerformance, log_level_miss); | ||
|
|
||
| BENCHMARK_DEFINE_F(PerformanceTest, logging_initialize)(benchmark::State & st) | ||
| { | ||
| rcutils_allocator_t allocator = rcutils_get_default_allocator(); | ||
| for (auto _ : st) { | ||
| rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, allocator); | ||
| if (ret != RCL_LOGGING_RET_OK) { | ||
| st.SkipWithError(rcutils_get_error_string().str); | ||
| } | ||
| } | ||
| } | ||
| BENCHMARK_REGISTER_F(PerformanceTest, logging_initialize); | ||
|
|
||
| BENCHMARK_DEFINE_F(PerformanceTest, logging_shutdown)(benchmark::State & st) | ||
| { | ||
| for (auto _ : st) { | ||
| rcl_logging_ret_t ret = rcl_logging_external_shutdown(); | ||
| if (ret != RCL_LOGGING_RET_OK) { | ||
| st.SkipWithError(rcutils_get_error_string().str); | ||
| } | ||
| } | ||
| } | ||
| BENCHMARK_REGISTER_F(PerformanceTest, logging_shutdown); | ||
cottsay marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.