Added benchmark test to rcl_yaml_param_parser (#803)
* Added benchmark test to rcl_yaml_param_parser Signed-off-by: ahcorde <ahcorde@gmail.com> * reset heap counters Signed-off-by: ahcorde <ahcorde@gmail.com> * updated benchmark tests Signed-off-by: ahcorde <ahcorde@gmail.com> * Added feedback Signed-off-by: ahcorde <ahcorde@gmail.com> * Replace BENCHMARK_DEFINE_F and BENCHMARK_REGISTER_F with BENCHMARK_F Signed-off-by: ahcorde <ahcorde@gmail.com> * Used rcpputils for the path Signed-off-by: ahcorde <ahcorde@gmail.com> * Clean up the CMake dependencies Signed-off-by: Scott K Logan <logans@cottsay.net> * Updated test Signed-off-by: ahcorde <ahcorde@gmail.com> * udpated test name Signed-off-by: ahcorde <ahcorde@gmail.com> Co-authored-by: Scott K Logan <logans@cottsay.net>
This commit is contained in:
parent
46e9ff8032
commit
1c08083888
5 changed files with 332 additions and 0 deletions
|
@ -57,6 +57,11 @@ if(BUILD_TESTING)
|
|||
find_package(osrf_testing_tools_cpp 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)
|
||||
|
||||
# Gtests
|
||||
ament_add_gtest(test_parse_yaml
|
||||
test/test_parse_yaml.cpp
|
||||
|
@ -80,6 +85,23 @@ if(BUILD_TESTING)
|
|||
target_link_libraries(test_parser ${PROJECT_NAME})
|
||||
endif()
|
||||
|
||||
add_performance_test(benchmark_parse_yaml test/benchmark/benchmark_parse_yaml.cpp
|
||||
WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||
if(TARGET benchmark_parse_yaml)
|
||||
target_link_libraries(benchmark_parse_yaml ${PROJECT_NAME})
|
||||
ament_target_dependencies(benchmark_parse_yaml
|
||||
"rcpputils"
|
||||
"rcutils"
|
||||
)
|
||||
endif()
|
||||
|
||||
add_performance_test(benchmark_variant test/benchmark/benchmark_variant.cpp)
|
||||
if(TARGET benchmark_variant)
|
||||
target_link_libraries(benchmark_variant ${PROJECT_NAME})
|
||||
ament_target_dependencies(benchmark_variant
|
||||
"rcutils"
|
||||
)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
ament_export_dependencies(ament_cmake libyaml_vendor)
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
<test_depend>ament_lint_common</test_depend>
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>osrf_testing_tools_cpp</test_depend>
|
||||
<test_depend>performance_test_fixture</test_depend>
|
||||
<test_depend>rcpputils</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
# config/test_yaml
|
||||
---
|
||||
|
||||
foo_ns:
|
||||
foo_name:
|
||||
ros__parameters:
|
||||
param1: 1
|
|
@ -0,0 +1,45 @@
|
|||
// 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 <string>
|
||||
|
||||
#include "performance_test_fixture/performance_test_fixture.hpp"
|
||||
|
||||
#include "rcl_yaml_param_parser/parser.h"
|
||||
|
||||
#include "rcpputils/filesystem_helper.hpp"
|
||||
|
||||
#include "rcutils/allocator.h"
|
||||
#include "rcutils/error_handling.h"
|
||||
#include "rcutils/filesystem.h"
|
||||
|
||||
using performance_test_fixture::PerformanceTest;
|
||||
|
||||
BENCHMARK_F(PerformanceTest, parser_yaml_param)(benchmark::State & st)
|
||||
{
|
||||
std::string path =
|
||||
(rcpputils::fs::current_path() / "test" / "benchmark" / "benchmark_params.yaml").string();
|
||||
reset_heap_counters();
|
||||
for (auto _ : st) {
|
||||
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(rcutils_get_default_allocator());
|
||||
if (NULL == params_hdl) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
bool res = rcl_parse_yaml_file(path.c_str(), params_hdl);
|
||||
if (!res) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
rcl_yaml_node_struct_fini(params_hdl);
|
||||
}
|
||||
}
|
256
rcl_yaml_param_parser/test/benchmark/benchmark_variant.cpp
Normal file
256
rcl_yaml_param_parser/test/benchmark/benchmark_variant.cpp
Normal file
|
@ -0,0 +1,256 @@
|
|||
// 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 <string>
|
||||
#include <type_traits>
|
||||
|
||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||
|
||||
#include "performance_test_fixture/performance_test_fixture.hpp"
|
||||
|
||||
#include "rcl_yaml_param_parser/parser.h"
|
||||
|
||||
#include "rcutils/allocator.h"
|
||||
#include "rcutils/error_handling.h"
|
||||
#include "rcutils/filesystem.h"
|
||||
#include "rcutils/strdup.h"
|
||||
|
||||
#include "../src/impl/yaml_variant.h"
|
||||
|
||||
using performance_test_fixture::PerformanceTest;
|
||||
|
||||
namespace
|
||||
{
|
||||
constexpr const uint64_t kSize = 1024;
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, bool_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
bool bool_value = true;
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
src_variant.bool_value = &bool_value;
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
src_variant.bool_value = nullptr;
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, int_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
int64_t int_value = 42;
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
src_variant.integer_value = &int_value;
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
src_variant.integer_value = nullptr;
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, double_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
double double_value = 3.14157;
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
src_variant.double_value = &double_value;
|
||||
|
||||
reset_heap_counters();
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
src_variant.double_value = nullptr;
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, string_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
std::string data(kSize, '*');
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
|
||||
char * tmp_string = rcutils_strdup(data.c_str(), allocator);
|
||||
src_variant.string_value = tmp_string;
|
||||
|
||||
reset_heap_counters();
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
}
|
||||
src_variant.string_value = nullptr;
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, array_bool_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
bool bool_arry[kSize];
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
using ArrayT = std::remove_pointer<decltype(src_variant.bool_array_value)>::type;
|
||||
src_variant.bool_array_value =
|
||||
static_cast<ArrayT *>(allocator.allocate(sizeof(ArrayT), allocator.state));
|
||||
using ValueT = std::remove_pointer<decltype(src_variant.bool_array_value->values)>::type;
|
||||
src_variant.bool_array_value->values =
|
||||
static_cast<ValueT *>(
|
||||
allocator.zero_allocate(kSize, sizeof(ValueT), allocator.state));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
rcl_yaml_variant_fini(&src_variant, allocator);
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
src_variant.bool_array_value = nullptr;
|
||||
dest_variant.bool_array_value = nullptr;
|
||||
});
|
||||
src_variant.bool_array_value->size = kSize;
|
||||
for (size_t i = 0; i < kSize; ++i) {
|
||||
src_variant.bool_array_value->values[i] = bool_arry[i];
|
||||
}
|
||||
|
||||
reset_heap_counters();
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
dest_variant.double_array_value = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, array_int_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
int int_arry[kSize];
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
using ArrayT = std::remove_pointer<decltype(src_variant.integer_array_value)>::type;
|
||||
src_variant.integer_array_value =
|
||||
static_cast<ArrayT *>(allocator.allocate(sizeof(ArrayT), allocator.state));
|
||||
using ValueT = std::remove_pointer<decltype(src_variant.integer_array_value->values)>::type;
|
||||
src_variant.integer_array_value->values =
|
||||
static_cast<ValueT *>(
|
||||
allocator.zero_allocate(kSize, sizeof(ValueT), allocator.state));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
rcl_yaml_variant_fini(&src_variant, allocator);
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
src_variant.integer_array_value = nullptr;
|
||||
dest_variant.integer_array_value = nullptr;
|
||||
});
|
||||
src_variant.integer_array_value->size = kSize;
|
||||
for (size_t i = 0; i < kSize; ++i) {
|
||||
src_variant.integer_array_value->values[i] = int_arry[i];
|
||||
}
|
||||
|
||||
reset_heap_counters();
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
dest_variant.double_array_value = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, array_double_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
double double_arry[kSize];
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
using ArrayT = std::remove_pointer<decltype(src_variant.double_array_value)>::type;
|
||||
src_variant.double_array_value =
|
||||
static_cast<ArrayT *>(allocator.allocate(sizeof(ArrayT), allocator.state));
|
||||
using ValueT = std::remove_pointer<decltype(src_variant.double_array_value->values)>::type;
|
||||
src_variant.double_array_value->values =
|
||||
static_cast<ValueT *>(
|
||||
allocator.zero_allocate(kSize, sizeof(ValueT), allocator.state));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
rcl_yaml_variant_fini(&src_variant, allocator);
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
src_variant.double_array_value = nullptr;
|
||||
dest_variant.double_array_value = nullptr;
|
||||
});
|
||||
src_variant.double_array_value->size = kSize;
|
||||
for (size_t i = 0; i < kSize; ++i) {
|
||||
src_variant.double_array_value->values[i] = double_arry[i];
|
||||
}
|
||||
|
||||
reset_heap_counters();
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
dest_variant.double_array_value = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
BENCHMARK_F(PerformanceTest, array_string_copy_variant)(benchmark::State & st)
|
||||
{
|
||||
rcl_variant_t src_variant{};
|
||||
rcl_variant_t dest_variant{};
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
|
||||
src_variant.string_array_value =
|
||||
static_cast<rcutils_string_array_t *>(
|
||||
allocator.allocate(sizeof(rcutils_string_array_t), allocator.state));
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
rcl_yaml_variant_fini(&src_variant, allocator);
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
});
|
||||
*src_variant.string_array_value = rcutils_get_zero_initialized_string_array();
|
||||
if (rcutils_string_array_init(src_variant.string_array_value, kSize, &allocator) !=
|
||||
RCUTILS_RET_OK)
|
||||
{
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
src_variant.string_array_value->size = kSize;
|
||||
for (size_t i = 0; i < kSize; i++) {
|
||||
src_variant.string_array_value->data[i] = rcutils_strdup("string", allocator);
|
||||
if (src_variant.string_array_value->data[i] == NULL) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
}
|
||||
reset_heap_counters();
|
||||
|
||||
for (auto _ : st) {
|
||||
if (!rcl_yaml_variant_copy(&dest_variant, &src_variant, allocator)) {
|
||||
st.SkipWithError(rcutils_get_error_string().str);
|
||||
}
|
||||
rcl_yaml_variant_fini(&dest_variant, allocator);
|
||||
dest_variant.double_array_value = nullptr;
|
||||
}
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue