Skip to content
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

Add benchmarks for rosidl_runtime_* packages #521

Merged
merged 9 commits into from
Sep 24, 2020
9 changes: 9 additions & 0 deletions rosidl_runtime_c/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ ament_index_register_resource("rosidl_runtime_packages")

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
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)
ament_lint_auto_find_test_dependencies()

# For gtest
Expand Down Expand Up @@ -101,6 +104,12 @@ if(BUILD_TESTING)
target_link_libraries(test_u16string_functions ${PROJECT_NAME})
target_compile_definitions(test_u16string_functions PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
endif()

add_performance_test(benchmark_string_conversion test/benchmark_string_conversion.cpp)
if(TARGET benchmark_string_conversion)
target_include_directories(benchmark_string_conversion PUBLIC include)
target_link_libraries(benchmark_string_conversion ${PROJECT_NAME})
endif()
endif()

install(
Expand Down
1 change: 1 addition & 0 deletions rosidl_runtime_c/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

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

<member_of_group>rosidl_runtime_packages</member_of_group>

Expand Down
126 changes: 126 additions & 0 deletions rosidl_runtime_c/test/benchmark_string_conversion.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
// 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 "rosidl_runtime_c/string_functions.h"
#include "rosidl_runtime_c/u16string_functions.h"

#include "performance_test_fixture/performance_test_fixture.hpp"

using performance_test_fixture::PerformanceTest;

BENCHMARK_DEFINE_F(PerformanceTest, string_assign_complexity)(benchmark::State & st)
{
size_t len = st.range(0);
std::string data(len, '*');

rosidl_runtime_c__String s;
if (!rosidl_runtime_c__String__init(&s)) {
st.SkipWithError("String initialization failed");
return;
}

// No explicit resize function - just do a copy
rosidl_runtime_c__String__assignn(&s, data.c_str(), len);
cottsay marked this conversation as resolved.
Show resolved Hide resolved

for (auto _ : st) {
rosidl_runtime_c__String__assignn(&s, data.c_str(), len);
cottsay marked this conversation as resolved.
Show resolved Hide resolved
}

st.SetComplexityN(len);

rosidl_runtime_c__String__fini(&s);
}

BENCHMARK_REGISTER_F(PerformanceTest, string_assign_complexity)
->RangeMultiplier(2)->Range(1 << 3, 1 << 12);

BENCHMARK_DEFINE_F(PerformanceTest, string_resize_assign_complexity)(benchmark::State & st)
{
size_t len = st.range(0);
std::string data(len, '*');

rosidl_runtime_c__String s;
if (!rosidl_runtime_c__String__init(&s)) {
st.SkipWithError("String initialization failed");
return;
}

// No explicit resize function - just do a copy
rosidl_runtime_c__String__assignn(&s, data.c_str(), 0);

for (auto _ : st) {
rosidl_runtime_c__String__assignn(&s, data.c_str(), len);
rosidl_runtime_c__String__assignn(&s, data.c_str(), 0);
}

st.SetComplexityN(len);

rosidl_runtime_c__String__fini(&s);
}

BENCHMARK_REGISTER_F(PerformanceTest, string_resize_assign_complexity)
->RangeMultiplier(2)->Range(1 << 3, 1 << 12);

BENCHMARK_DEFINE_F(PerformanceTest, u16string_assign_complexity)(benchmark::State & st)
{
size_t len = st.range(0);
std::string data(len, '*');

rosidl_runtime_c__U16String s;
if (!rosidl_runtime_c__U16String__init(&s)) {
st.SkipWithError("U16String initialization failed");
return;
}

rosidl_runtime_c__U16String__resize(&s, len);

for (auto _ : st) {
rosidl_runtime_c__U16String__assignn_from_char(&s, data.c_str(), len);
}

st.SetComplexityN(len);

rosidl_runtime_c__U16String__fini(&s);
}

BENCHMARK_REGISTER_F(PerformanceTest, u16string_assign_complexity)
->RangeMultiplier(2)->Range(1 << 3, 1 << 12);

BENCHMARK_DEFINE_F(PerformanceTest, u16string_resize_assign_complexity)(benchmark::State & st)
{
size_t len = st.range(0);
std::string data(len, '*');

rosidl_runtime_c__U16String s;
if (!rosidl_runtime_c__U16String__init(&s)) {
st.SkipWithError("U16String initialization failed");
return;
}

rosidl_runtime_c__U16String__resize(&s, 0);

for (auto _ : st) {
rosidl_runtime_c__U16String__assignn_from_char(&s, data.c_str(), len);
rosidl_runtime_c__U16String__resize(&s, 0);
}

st.SetComplexityN(len);

rosidl_runtime_c__U16String__fini(&s);
}

BENCHMARK_REGISTER_F(PerformanceTest, u16string_resize_assign_complexity)
->RangeMultiplier(2)->Range(1 << 3, 1 << 12);