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

Added benchmark test for rosidl_generator_c #529

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 15 additions & 1 deletion rosidl_generator_c/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.5)

project(rosidl_generator_c C)
project(rosidl_generator_c C CXX)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Rather than this, enable the language only if BUILD_TESTING is specified as is done here:

# For gtest
enable_language(CXX)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

Suggested change
project(rosidl_generator_c C CXX)
project(rosidl_generator_c C)


# Default to C11
if(NOT CMAKE_C_STANDARD)
Expand Down Expand Up @@ -28,8 +28,12 @@ endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(performance_test_fixture REQUIRED)
find_package(test_interface_files REQUIRED)
find_package(rosidl_runtime_c 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()

include(cmake/register_c.cmake)
Expand Down Expand Up @@ -94,6 +98,16 @@ if(BUILD_TESTING)
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME}
${rosidl_runtime_c_INCLUDE_DIRS}
)

add_performance_test(benchmark_interfaces test/benchmark/benchmark_interfaces.cpp)
set_target_properties(benchmark_interfaces PROPERTIES LINKER_LANGUAGE CXX)
if(TARGET benchmark_interfaces)
target_include_directories(benchmark_interfaces PUBLIC
include
${CMAKE_CURRENT_BINARY_DIR}/${PROJECT_NAME})
target_link_libraries(benchmark_interfaces
${PROJECT_NAME}_interfaces__${PROJECT_NAME})
endif()
endif()

ament_package(
Expand Down
1 change: 1 addition & 0 deletions rosidl_generator_c/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>performance_test_fixture</test_depend>
<test_depend>rosidl_cmake</test_depend>
<test_depend>rosidl_runtime_c</test_depend>
<test_depend>test_interface_files</test_depend>
Expand Down
349 changes: 349 additions & 0 deletions rosidl_generator_c/test/benchmark/benchmark_interfaces.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,349 @@
// 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 "rosidl_runtime_c/primitives_sequence_functions.h"
#include "rosidl_runtime_c/string_functions.h"
#include "rosidl_runtime_c/u16string_functions.h"

#include "rosidl_generator_c/msg/arrays.h"
#include "rosidl_generator_c/msg/defaults.h"
#include "rosidl_generator_c/msg/basic_types.h"
#include "rosidl_generator_c/msg/bounded_sequences.h"
#include "rosidl_generator_c/msg/multi_nested.h"
#include "rosidl_generator_c/msg/nested.h"
#include "rosidl_generator_c/msg/strings.h"
#include "rosidl_generator_c/msg/unbounded_sequences.h"

#include "performance_test_fixture/performance_test_fixture.hpp"

using performance_test_fixture::PerformanceTest;

BENCHMARK_DEFINE_F(PerformanceTest, msg_array_complexity)(benchmark::State & st)
{
rosidl_generator_c__msg__Arrays * arr = NULL;

for (auto _ : st) {
arr = rosidl_generator_c__msg__Arrays__create();
if (arr == nullptr) {
st.SkipWithError("Array create function failed");
return;
}

for (unsigned int i = 0; i < 3; i++) {
arr->bool_values[i] = true;
arr->char_values[i] = 'a';
arr->float32_values[i] = -3.000001f;
arr->float64_values[i] = -120310.00843902140001;
arr->int8_values[i] = -50;
arr->uint8_values[i] = 0;
arr->int16_values[i] = -2222;
arr->uint16_values[i] = 0U;
arr->int32_values[i] = 30;
arr->uint32_values[i] = 0UL;
arr->int64_values[i] = -9223372036854775807LL;
arr->uint64_values[i] = 0ULL;
rosidl_runtime_c__String__assign(&arr->string_values[i], "value");
}

rosidl_generator_c__msg__Arrays__destroy(arr);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_array_complexity);

BENCHMARK_DEFINE_F(PerformanceTest, msg_default_complexity)(benchmark::State & st)
{
rosidl_generator_c__msg__Defaults * def = NULL;

for (auto _ : st) {
def = rosidl_generator_c__msg__Defaults__create();
if (def == nullptr) {
st.SkipWithError("Default create function failed");
return;
}
rosidl_generator_c__msg__Defaults__destroy(def);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_default_complexity);

BENCHMARK_DEFINE_F(PerformanceTest, msg_basic_types_complexity)(benchmark::State & st)
{
rosidl_generator_c__msg__BasicTypes * basic = NULL;

for (auto _ : st) {
basic = rosidl_generator_c__msg__BasicTypes__create();
if (basic == nullptr) {
st.SkipWithError("Default create function failed");
return;
}
basic->bool_value = false;
basic->byte_value = 25;
basic->char_value = 0;
basic->float32_value = 0;
basic->float64_value = 0;
basic->int8_value = 0;
basic->uint8_value = 0;
basic->int16_value = 0;
basic->uint16_value = 0;
basic->int32_value = 0;
basic->uint32_value = 0;
basic->int64_value = 0;
basic->uint64_value = 0;
rosidl_generator_c__msg__BasicTypes__destroy(basic);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_basic_types_complexity);

BENCHMARK_DEFINE_F(PerformanceTest, msg_bounded_sequences_complexity)(benchmark::State & st)
{
size_t len = st.range(0);
rosidl_generator_c__msg__BoundedSequences * seq = NULL;

for (auto _ : st) {
seq = rosidl_generator_c__msg__BoundedSequences__create();

if (seq == nullptr) {
st.SkipWithError("BoundedSequences create function failed");
return;
}

bool res = false;
unsigned int i = 0;
res = rosidl_runtime_c__boolean__Sequence__init(&seq->bool_values, len);
if (!res) {
st.SkipWithError("boolean__Sequence__init failed");
return;
}
res = rosidl_runtime_c__byte__Sequence__init(&seq->byte_values, len);
if (!res) {
st.SkipWithError("byte__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint8__Sequence__init(&seq->char_values, len);
if (!res) {
st.SkipWithError("uint8__Sequence__init failed");
return;
}
res = rosidl_runtime_c__float32__Sequence__init(&seq->float32_values, len);
if (!res) {
st.SkipWithError("float32__Sequence__init failed");
return;
}
res = rosidl_runtime_c__float64__Sequence__init(&seq->float64_values, len);
if (!res) {
st.SkipWithError("float64__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int8__Sequence__init(&seq->int8_values, len);
if (!res) {
st.SkipWithError("int8__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint8__Sequence__init(&seq->uint8_values, len);
if (!res) {
st.SkipWithError("uint8__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int16__Sequence__init(&seq->int16_values, len);
if (!res) {
st.SkipWithError("int16__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint16__Sequence__init(&seq->uint16_values, len);
if (!res) {
st.SkipWithError("uint16__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int32__Sequence__init(&seq->int32_values, len);
if (!res) {
st.SkipWithError("int32__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint32__Sequence__init(&seq->uint32_values, len);
if (!res) {
st.SkipWithError("uint32__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int64__Sequence__init(&seq->int64_values, len);
if (!res) {
st.SkipWithError("int64__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint64__Sequence__init(&seq->uint64_values, len);
if (!res) {
st.SkipWithError("uint64__Sequence__init failed");
return;
}
res = rosidl_runtime_c__String__Sequence__init(&seq->string_values, len);
if (!res) {
st.SkipWithError("String__Sequence__init failed");
return;
}

for (i = 0; i < len; i++) {
seq->bool_values.data[i] = true;
seq->char_values.data[i] = 'a';
seq->float32_values.data[i] = -3.000001f;
seq->float64_values.data[i] = -120310.00843902140001;
seq->int8_values.data[i] = -50;
seq->uint8_values.data[i] = 0;
seq->int16_values.data[i] = -2222;
seq->uint16_values.data[i] = 0U;
seq->int32_values.data[i] = 30;
seq->uint32_values.data[i] = 0UL;
seq->int64_values.data[i] = -9223372036854775807LL;
seq->uint64_values.data[i] = 0ULL;
rosidl_runtime_c__String__assign(&seq->string_values.data[i], "value");
}
rosidl_generator_c__msg__BoundedSequences__destroy(seq);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_bounded_sequences_complexity)
->RangeMultiplier(2)->Range(1 << 3, 1 << 12);

BENCHMARK_DEFINE_F(PerformanceTest, msg_multi_nested_complexity)(benchmark::State & st)
{
rosidl_generator_c__msg__MultiNested * msg = NULL;

for (auto _ : st) {
msg = rosidl_generator_c__msg__MultiNested__create();
if (msg == nullptr) {
st.SkipWithError("Multi nested create function failed");
return;
}
rosidl_generator_c__msg__MultiNested__destroy(msg);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_multi_nested_complexity);

BENCHMARK_DEFINE_F(PerformanceTest, msg_nested_complexity)(benchmark::State & st)
{
rosidl_generator_c__msg__Nested * nested = NULL;

for (auto _ : st) {
nested = rosidl_generator_c__msg__Nested__create();
if (nested == nullptr) {
st.SkipWithError("Nested create function failed");
return;
}
rosidl_generator_c__msg__Nested__destroy(nested);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_nested_complexity);

BENCHMARK_DEFINE_F(PerformanceTest, msg_unbounded_sequences_complexity)(benchmark::State & st)
{
size_t len = st.range(0);
rosidl_generator_c__msg__UnboundedSequences * seq = NULL;

for (auto _ : st) {
seq = rosidl_generator_c__msg__UnboundedSequences__create();

if (seq == nullptr) {
st.SkipWithError("BoundedSequences create function failed");
return;
}

bool res = false;
unsigned int i = 0;
res = rosidl_runtime_c__boolean__Sequence__init(&seq->bool_values, len);
if (!res) {
st.SkipWithError("boolean__Sequence__init failed");
return;
}
res = rosidl_runtime_c__byte__Sequence__init(&seq->byte_values, len);
if (!res) {
st.SkipWithError("byte__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint8__Sequence__init(&seq->char_values, len);
if (!res) {
st.SkipWithError("uint8__Sequence__init failed");
return;
}
res = rosidl_runtime_c__float32__Sequence__init(&seq->float32_values, len);
if (!res) {
st.SkipWithError("float32__Sequence__init failed");
return;
}
res = rosidl_runtime_c__float64__Sequence__init(&seq->float64_values, len);
if (!res) {
st.SkipWithError("float64__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int8__Sequence__init(&seq->int8_values, len);
if (!res) {
st.SkipWithError("int8__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint8__Sequence__init(&seq->uint8_values, len);
if (!res) {
st.SkipWithError("uint8__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int16__Sequence__init(&seq->int16_values, len);
if (!res) {
st.SkipWithError("int16__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint16__Sequence__init(&seq->uint16_values, len);
if (!res) {
st.SkipWithError("uint16__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int32__Sequence__init(&seq->int32_values, len);
if (!res) {
st.SkipWithError("int32__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint32__Sequence__init(&seq->uint32_values, len);
if (!res) {
st.SkipWithError("uint32__Sequence__init failed");
return;
}
res = rosidl_runtime_c__int64__Sequence__init(&seq->int64_values, len);
if (!res) {
st.SkipWithError("int64__Sequence__init failed");
return;
}
res = rosidl_runtime_c__uint64__Sequence__init(&seq->uint64_values, len);
if (!res) {
st.SkipWithError("uint64__Sequence__init failed");
return;
}
res = rosidl_runtime_c__String__Sequence__init(&seq->string_values, len);
if (!res) {
st.SkipWithError("String__Sequence__init failed");
return;
}

for (i = 0; i < len; i++) {
seq->bool_values.data[i] = true;
seq->char_values.data[i] = 'a';
seq->float32_values.data[i] = -3.000001f;
seq->float64_values.data[i] = -120310.00843902140001;
seq->int8_values.data[i] = -50;
seq->uint8_values.data[i] = 0;
seq->int16_values.data[i] = -2222;
seq->uint16_values.data[i] = 0U;
seq->int32_values.data[i] = 30;
seq->uint32_values.data[i] = 0UL;
seq->int64_values.data[i] = -9223372036854775807LL;
seq->uint64_values.data[i] = 0ULL;
rosidl_runtime_c__String__assign(&seq->string_values.data[i], "value");
}
rosidl_generator_c__msg__UnboundedSequences__destroy(seq);
}
}
BENCHMARK_REGISTER_F(PerformanceTest, msg_unbounded_sequences_complexity)
->RangeMultiplier(2)->Range(1 << 3, 1 << 12);