Skip to content

Commit

Permalink
Added benchmark test to rcl_logging_spdlog (#52)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Oct 8, 2020
1 parent 8446c8d commit a473079
Show file tree
Hide file tree
Showing 3 changed files with 131 additions and 0 deletions.
9 changes: 9 additions & 0 deletions rcl_logging_spdlog/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,20 @@ if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(performance_test_fixture REQUIRED)
# Give cppcheck hints about macro definitions coming from outside this package
get_target_property(ament_cmake_cppcheck_ADDITIONAL_INCLUDE_DIRS
performance_test_fixture::performance_test_fixture INTERFACE_INCLUDE_DIRECTORIES)

find_package(ament_cmake_gtest REQUIRED)
ament_add_gtest(test_logging_interface test/test_logging_interface.cpp)
if(TARGET test_logging_interface)
target_link_libraries(test_logging_interface ${PROJECT_NAME})
endif()
add_performance_test(benchmark_logging_interface test/benchmark/benchmark_logging_interface.cpp)
if(TARGET benchmark_logging_interface)
target_link_libraries(benchmark_logging_interface ${PROJECT_NAME})
endif()
endif()

ament_export_include_directories(include)
Expand Down
2 changes: 2 additions & 0 deletions rcl_logging_spdlog/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>performance_test_fixture</test_depend>
<test_depend>rcpputils</test_depend>

<member_of_group>rcl_logging_packages</member_of_group>

Expand Down
120 changes: 120 additions & 0 deletions rcl_logging_spdlog/test/benchmark/benchmark_logging_interface.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,120 @@
// 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;
}

class LoggingBenchmarkPerformance : public PerformanceTest
{
public:
void SetUp(benchmark::State & st)
{
rcl_logging_ret_t ret = rcl_logging_external_initialize(
nullptr,
rcutils_get_default_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);
}
}

std::string data;
};

BENCHMARK_F(LoggingBenchmarkPerformance, log_level_hit)(benchmark::State & st)
{
setLogLevel(RCUTILS_LOG_SEVERITY_INFO, st);

rcl_logging_external_log(RCUTILS_LOG_SEVERITY_INFO, nullptr, data.c_str());
reset_heap_counters();

for (auto _ : st) {
rcl_logging_external_log(RCUTILS_LOG_SEVERITY_INFO, nullptr, data.c_str());
}
}

BENCHMARK_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_F(PerformanceTest, logging_reinitialize)(benchmark::State & st)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
rcl_logging_ret_t ret = rcl_logging_external_initialize(nullptr, allocator);

reset_heap_counters();

for (auto _ : st) {
ret = rcl_logging_external_initialize(nullptr, allocator);
if (ret != RCL_LOGGING_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
}

ret = rcl_logging_external_shutdown();
if (ret != RCL_LOGGING_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
}

BENCHMARK_F(PerformanceTest, logging_initialize_shutdown)(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);
}
ret = rcl_logging_external_shutdown();
if (ret != RCL_LOGGING_RET_OK) {
st.SkipWithError(rcutils_get_error_string().str);
}
}
}

0 comments on commit a473079

Please sign in to comment.