From 68e7c708a164d9dda27da161d31eba2f4f648e6b Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 21 May 2018 21:23:10 -0700 Subject: [PATCH 01/10] remove old memory tools --- rcl/test/memory_tools/CMakeLists.txt | 41 ----- rcl/test/memory_tools/memory_tools.cpp | 143 --------------- rcl/test/memory_tools/memory_tools.hpp | 132 -------------- rcl/test/memory_tools/memory_tools_common.cpp | 166 ------------------ .../memory_tools_osx_interpose.cpp | 57 ------ rcl/test/memory_tools/test_memory_tools.cpp | 136 -------------- rcl/test/scope_exit.hpp | 40 ----- 7 files changed, 715 deletions(-) delete mode 100644 rcl/test/memory_tools/CMakeLists.txt delete mode 100644 rcl/test/memory_tools/memory_tools.cpp delete mode 100644 rcl/test/memory_tools/memory_tools.hpp delete mode 100644 rcl/test/memory_tools/memory_tools_common.cpp delete mode 100644 rcl/test/memory_tools/memory_tools_osx_interpose.cpp delete mode 100644 rcl/test/memory_tools/test_memory_tools.cpp delete mode 100644 rcl/test/scope_exit.hpp diff --git a/rcl/test/memory_tools/CMakeLists.txt b/rcl/test/memory_tools/CMakeLists.txt deleted file mode 100644 index 6455b2ad4..000000000 --- a/rcl/test/memory_tools/CMakeLists.txt +++ /dev/null @@ -1,41 +0,0 @@ -ament_find_gtest() # For GTEST_LIBRARIES - -# Create the memory_tools library which is used by the tests. (rmw implementation agnostic) -add_library(${PROJECT_NAME}_memory_tools SHARED memory_tools.cpp) -if(APPLE) - # Create an OS X specific version of the memory tools that does interposing. - # See: http://toves.freeshell.org/interpose/ - add_library(${PROJECT_NAME}_memory_tools_interpose SHARED memory_tools_osx_interpose.cpp) - target_link_libraries(${PROJECT_NAME}_memory_tools_interpose ${GTEST_LIBRARIES}) - list(APPEND extra_test_libraries ${PROJECT_NAME}_memory_tools_interpose) - list(APPEND extra_test_env - DYLD_INSERT_LIBRARIES=$) -endif() -if(UNIX AND NOT APPLE) - # On Linux like systems, add dl and use the normal library and DL_PRELOAD. - list(APPEND extra_test_libraries dl) - list(APPEND extra_test_env DL_PRELOAD=$) -endif() -list(APPEND extra_lib_dirs $) -target_link_libraries(${PROJECT_NAME}_memory_tools ${extra_test_libraries}) -target_compile_definitions(${PROJECT_NAME}_memory_tools - PRIVATE "RCL_MEMORY_TOOLS_BUILDING_DLL") -list(APPEND extra_test_libraries ${PROJECT_NAME}_memory_tools) - -# Create tests for the memory tools library. -set(SKIP_TEST "") -if(WIN32) # (memory tools doesn't do anything on Windows) - set(SKIP_TEST "SKIP_TEST") -endif() - -include(../cmake/rcl_add_custom_gtest.cmake) -rcl_add_custom_gtest(test_memory_tools - SRCS test_memory_tools.cpp - ENV ${extra_test_env} - LIBRARIES ${extra_test_libraries} - ${SKIP_TEST} -) - -set(extra_test_libraries ${extra_test_libraries} PARENT_SCOPE) -set(extra_test_env ${extra_test_env} PARENT_SCOPE) -set(extra_lib_dirs ${extra_lib_dirs} PARENT_SCOPE) diff --git a/rcl/test/memory_tools/memory_tools.cpp b/rcl/test/memory_tools/memory_tools.cpp deleted file mode 100644 index 5468d3818..000000000 --- a/rcl/test/memory_tools/memory_tools.cpp +++ /dev/null @@ -1,143 +0,0 @@ -// Copyright 2015 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. - -#if defined(__linux__) -/****************************************************************************** - * Begin Linux - *****************************************************************************/ - -#include -#include -#include - -#include "./memory_tools_common.cpp" - -void * -malloc(size_t size) -{ - void * (* libc_malloc)(size_t) = (void *(*)(size_t))dlsym(RTLD_NEXT, "malloc"); - if (enabled.load()) { - return custom_malloc(size); - } - return libc_malloc(size); -} - -void * -realloc(void * pointer, size_t size) -{ - void * (* libc_realloc)(void *, size_t) = (void *(*)(void *, size_t))dlsym(RTLD_NEXT, "realloc"); - if (enabled.load()) { - return custom_realloc(pointer, size); - } - return libc_realloc(pointer, size); -} - -void -free(void * pointer) -{ - void (* libc_free)(void *) = (void (*)(void *))dlsym(RTLD_NEXT, "free"); - if (enabled.load()) { - return custom_free(pointer); - } - return libc_free(pointer); -} - -void start_memory_checking() -{ - if (!enabled.exchange(true)) { - printf("starting memory checking...\n"); - } -} - -void stop_memory_checking() -{ - if (enabled.exchange(false)) { - printf("stopping memory checking...\n"); - } -} - -/****************************************************************************** - * End Linux - *****************************************************************************/ -#elif defined(__APPLE__) -/****************************************************************************** - * Begin Apple - *****************************************************************************/ - -// The apple implementation is in a separate shared library, loaded with DYLD_INSERT_LIBRARIES. -// Therefore we do not include the common cpp file here. - -void osx_start_memory_checking(); -void osx_stop_memory_checking(); - -void start_memory_checking() -{ - return osx_start_memory_checking(); -} - -void stop_memory_checking() -{ - return osx_stop_memory_checking(); -} - -/****************************************************************************** - * End Apple - *****************************************************************************/ -// #elif defined(_WIN32) -/****************************************************************************** - * Begin Windows - *****************************************************************************/ - -// TODO(wjwwood): install custom malloc (and others) for Windows. - -/****************************************************************************** - * End Windows - *****************************************************************************/ -#else -// Default case: do nothing. - -#include "./memory_tools.hpp" - -#include - -void start_memory_checking() -{ - printf("starting memory checking... not available\n"); -} -void stop_memory_checking() -{ - printf("stopping memory checking... not available\n"); -} - -void assert_no_malloc_begin() {} - -void assert_no_malloc_end() {} - -void set_on_unexpected_malloc_callback(UnexpectedCallbackType callback) {} - -void assert_no_realloc_begin() {} - -void assert_no_realloc_end() {} - -void set_on_unexpected_realloc_callback(UnexpectedCallbackType callback) {} - -void assert_no_free_begin() {} - -void assert_no_free_end() {} - -void set_on_unexpected_free_callback(UnexpectedCallbackType callback) {} - -void memory_checking_thread_init() {} - -#endif // if defined(__linux__) elif defined(__APPLE__) elif defined(_WIN32) else ... diff --git a/rcl/test/memory_tools/memory_tools.hpp b/rcl/test/memory_tools/memory_tools.hpp deleted file mode 100644 index 3e294b751..000000000 --- a/rcl/test/memory_tools/memory_tools.hpp +++ /dev/null @@ -1,132 +0,0 @@ -// Copyright 2015 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. - -// Code to do replacing of malloc/free/etc... inspired by: -// https://dxr.mozilla.org/mozilla-central/rev/ -// cc9c6cd756cb744596ba039dcc5ad3065a7cc3ea/memory/build/replace_malloc.c - -#ifndef MEMORY_TOOLS__MEMORY_TOOLS_HPP_ -#define MEMORY_TOOLS__MEMORY_TOOLS_HPP_ - -#include - -#include - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ - #ifdef __GNUC__ - #define RCL_MEMORY_TOOLS_EXPORT __attribute__ ((dllexport)) - #define RCL_MEMORY_TOOLS_IMPORT __attribute__ ((dllimport)) - #else - #define RCL_MEMORY_TOOLS_EXPORT __declspec(dllexport) - #define RCL_MEMORY_TOOLS_IMPORT __declspec(dllimport) - #endif - #ifdef RCL_MEMORY_TOOLS_BUILDING_DLL - #define RCL_MEMORY_TOOLS_PUBLIC RCL_MEMORY_TOOLS_EXPORT - #else - #define RCL_MEMORY_TOOLS_PUBLIC RCL_MEMORY_TOOLS_IMPORT - #endif - #define RCL_MEMORY_TOOLS_PUBLIC_TYPE RCL_MEMORY_TOOLS_PUBLIC - #define RCL_MEMORY_TOOLS_LOCAL -#else - #define RCL_MEMORY_TOOLS_EXPORT __attribute__ ((visibility("default"))) - #define RCL_MEMORY_TOOLS_IMPORT - #if __GNUC__ >= 4 - #define RCL_MEMORY_TOOLS_PUBLIC __attribute__ ((visibility("default"))) - #define RCL_MEMORY_TOOLS_LOCAL __attribute__ ((visibility("hidden"))) - #else - #define RCL_MEMORY_TOOLS_PUBLIC - #define RCL_MEMORY_TOOLS_LOCAL - #endif - #define RCL_MEMORY_TOOLS_PUBLIC_TYPE -#endif - -typedef std::function UnexpectedCallbackType; - -RCL_MEMORY_TOOLS_PUBLIC -void -start_memory_checking(); - -#define ASSERT_NO_MALLOC(statements) \ - assert_no_malloc_begin(); statements; assert_no_malloc_end(); -RCL_MEMORY_TOOLS_PUBLIC -void -assert_no_malloc_begin(); -RCL_MEMORY_TOOLS_PUBLIC -void -assert_no_malloc_end(); -RCL_MEMORY_TOOLS_PUBLIC -void -set_on_unexpected_malloc_callback(UnexpectedCallbackType callback); - -#define ASSERT_NO_REALLOC(statements) \ - assert_no_realloc_begin(); statements; assert_no_realloc_end(); -RCL_MEMORY_TOOLS_PUBLIC -void -assert_no_realloc_begin(); -RCL_MEMORY_TOOLS_PUBLIC -void -assert_no_realloc_end(); -RCL_MEMORY_TOOLS_PUBLIC -void -set_on_unexpected_realloc_callback(UnexpectedCallbackType callback); - -#define ASSERT_NO_FREE(statements) \ - assert_no_free_begin(); statements; assert_no_free_end(); -RCL_MEMORY_TOOLS_PUBLIC -void -assert_no_free_begin(); -RCL_MEMORY_TOOLS_PUBLIC -void -assert_no_free_end(); -RCL_MEMORY_TOOLS_PUBLIC -void -set_on_unexpected_free_callback(UnexpectedCallbackType callback); - -RCL_MEMORY_TOOLS_PUBLIC -void -stop_memory_checking(); - -RCL_MEMORY_TOOLS_PUBLIC -void -memory_checking_thread_init(); - -// What follows is a set of failing allocator functions, used for testing. -void * -failing_malloc(size_t size, void * state) -{ - (void)size; - (void)state; - return nullptr; -} - -void * -failing_realloc(void * pointer, size_t size, void * state) -{ - (void)pointer; - (void)size; - (void)state; - return nullptr; -} - -void -failing_free(void * pointer, void * state) -{ - (void)pointer; - (void)state; -} - -#endif // MEMORY_TOOLS__MEMORY_TOOLS_HPP_ diff --git a/rcl/test/memory_tools/memory_tools_common.cpp b/rcl/test/memory_tools/memory_tools_common.cpp deleted file mode 100644 index 8f8d51f55..000000000 --- a/rcl/test/memory_tools/memory_tools_common.cpp +++ /dev/null @@ -1,166 +0,0 @@ -// Copyright 2015 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 - -#include -#include - -#if defined(__APPLE__) -#include -#define MALLOC_PRINTF malloc_printf -#else // defined(__APPLE__) -#define MALLOC_PRINTF printf -#endif // defined(__APPLE__) - -#include "./memory_tools.hpp" -#include "../scope_exit.hpp" - -static std::atomic enabled(false); - -static __thread bool malloc_expected = true; -static __thread UnexpectedCallbackType * unexpected_malloc_callback = nullptr; -void set_on_unexpected_malloc_callback(UnexpectedCallbackType callback) -{ - if (unexpected_malloc_callback) { - unexpected_malloc_callback->~UnexpectedCallbackType(); - free(unexpected_malloc_callback); - unexpected_malloc_callback = nullptr; - } - if (!callback) { - return; - } - if (!unexpected_malloc_callback) { - unexpected_malloc_callback = - reinterpret_cast(malloc(sizeof(UnexpectedCallbackType))); - if (!unexpected_malloc_callback) { - throw std::bad_alloc(); - } - new (unexpected_malloc_callback) UnexpectedCallbackType(); - } - *unexpected_malloc_callback = callback; -} - -void * -custom_malloc(size_t size) -{ - if (!enabled.load()) {return malloc(size);} - auto foo = SCOPE_EXIT(enabled.store(true);); - enabled.store(false); - if (!malloc_expected) { - if (unexpected_malloc_callback) { - (*unexpected_malloc_callback)(); - } - } - void * memory = malloc(size); - uint64_t fw_size = size; - if (!malloc_expected) { - MALLOC_PRINTF( - " malloc (%s) %p %" PRIu64 "\n", - malloc_expected ? " expected" : "not expected", memory, fw_size); - } - return memory; -} - -static __thread bool realloc_expected = true; -static __thread UnexpectedCallbackType * unexpected_realloc_callback = nullptr; -void set_on_unexpected_realloc_callback(UnexpectedCallbackType callback) -{ - if (unexpected_realloc_callback) { - unexpected_realloc_callback->~UnexpectedCallbackType(); - free(unexpected_realloc_callback); - unexpected_realloc_callback = nullptr; - } - if (!callback) { - return; - } - if (!unexpected_realloc_callback) { - unexpected_realloc_callback = - reinterpret_cast(malloc(sizeof(UnexpectedCallbackType))); - if (!unexpected_realloc_callback) { - throw std::bad_alloc(); - } - new (unexpected_realloc_callback) UnexpectedCallbackType(); - } - *unexpected_realloc_callback = callback; -} - -void * -custom_realloc(void * memory_in, size_t size) -{ - if (!enabled.load()) {return realloc(memory_in, size);} - auto foo = SCOPE_EXIT(enabled.store(true);); - enabled.store(false); - if (!realloc_expected) { - if (unexpected_realloc_callback) { - (*unexpected_realloc_callback)(); - } - } - void * memory = realloc(memory_in, size); - uint64_t fw_size = size; - if (!realloc_expected) { - MALLOC_PRINTF( - "realloc (%s) %p %p %" PRIu64 "\n", - realloc_expected ? " expected" : "not expected", memory_in, memory, fw_size); - } - return memory; -} - -static __thread bool free_expected = true; -static __thread UnexpectedCallbackType * unexpected_free_callback = nullptr; -void set_on_unexpected_free_callback(UnexpectedCallbackType callback) -{ - if (unexpected_free_callback) { - unexpected_free_callback->~UnexpectedCallbackType(); - free(unexpected_free_callback); - unexpected_free_callback = nullptr; - } - if (!callback) { - return; - } - if (!unexpected_free_callback) { - unexpected_free_callback = - reinterpret_cast(malloc(sizeof(UnexpectedCallbackType))); - if (!unexpected_free_callback) { - throw std::bad_alloc(); - } - new (unexpected_free_callback) UnexpectedCallbackType(); - } - *unexpected_free_callback = callback; -} - -void -custom_free(void * memory) -{ - if (!enabled.load()) {return free(memory);} - auto foo = SCOPE_EXIT(enabled.store(true);); - enabled.store(false); - if (!free_expected) { - if (unexpected_free_callback) { - (*unexpected_free_callback)(); - } - } - if (!free_expected) { - MALLOC_PRINTF( - " free (%s) %p\n", free_expected ? " expected" : "not expected", memory); - } - free(memory); -} - -void assert_no_malloc_begin() {malloc_expected = false;} -void assert_no_malloc_end() {malloc_expected = true;} -void assert_no_realloc_begin() {realloc_expected = false;} -void assert_no_realloc_end() {realloc_expected = true;} -void assert_no_free_begin() {free_expected = false;} -void assert_no_free_end() {free_expected = true;} diff --git a/rcl/test/memory_tools/memory_tools_osx_interpose.cpp b/rcl/test/memory_tools/memory_tools_osx_interpose.cpp deleted file mode 100644 index d9397dfd0..000000000 --- a/rcl/test/memory_tools/memory_tools_osx_interpose.cpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2015 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. - -// Pulled from: -// https://github.com/emeryberger/Heap-Layers/blob/ -// 076e9e7ef53b66380b159e40473b930f25cc353b/wrappers/macinterpose.h - -// The interposition data structure (just pairs of function pointers), -// used an interposition table like the following: -// - -typedef struct interpose_s -{ - void * new_func; - void * orig_func; -} interpose_t; - -#define OSX_INTERPOSE(newf, oldf) \ - __attribute__((used)) static const interpose_t \ - macinterpose ## newf ## oldf __attribute__ ((section("__DATA, __interpose"))) = { \ - reinterpret_cast(newf), \ - reinterpret_cast(oldf), \ - } - -// End Interpose. - -#include "./memory_tools_common.cpp" - -void osx_start_memory_checking() -{ - // No loading required, it is handled by DYLD_INSERT_LIBRARIES and dynamic library interposing. - if (!enabled.exchange(true)) { - MALLOC_PRINTF("starting memory checking...\n"); - } -} - -void osx_stop_memory_checking() -{ - if (enabled.exchange(false)) { - MALLOC_PRINTF("stopping memory checking...\n"); - } -} - -OSX_INTERPOSE(custom_malloc, malloc); -OSX_INTERPOSE(custom_realloc, realloc); -OSX_INTERPOSE(custom_free, free); diff --git a/rcl/test/memory_tools/test_memory_tools.cpp b/rcl/test/memory_tools/test_memory_tools.cpp deleted file mode 100644 index ecbcf1ac0..000000000 --- a/rcl/test/memory_tools/test_memory_tools.cpp +++ /dev/null @@ -1,136 +0,0 @@ -// Copyright 2015 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 - -#include "./memory_tools.hpp" - -/* Tests the allocatation checking tools. - */ -TEST(TestMemoryTools, test_allocation_checking_tools) { - size_t unexpected_mallocs = 0; - auto on_unexpected_malloc = - [&unexpected_mallocs]() { - unexpected_mallocs++; - }; - set_on_unexpected_malloc_callback(on_unexpected_malloc); - size_t unexpected_reallocs = 0; - auto on_unexpected_realloc = - [&unexpected_reallocs]() { - unexpected_reallocs++; - }; - set_on_unexpected_realloc_callback(on_unexpected_realloc); - size_t unexpected_frees = 0; - auto on_unexpected_free = - [&unexpected_frees]() { - unexpected_frees++; - }; - set_on_unexpected_free_callback(on_unexpected_free); - void * mem = nullptr; - void * remem = nullptr; - // First try before enabling, should have no effect. - mem = malloc(1024); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - EXPECT_EQ(unexpected_mallocs, 0u); - EXPECT_EQ(unexpected_reallocs, 0u); - EXPECT_EQ(unexpected_frees, 0u); - // Enable checking, but no assert, should have no effect. - start_memory_checking(); - mem = malloc(1024); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - EXPECT_EQ(unexpected_mallocs, 0u); - EXPECT_EQ(unexpected_reallocs, 0u); - EXPECT_EQ(unexpected_frees, 0u); - // Enable no_* asserts, should increment all once. - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - mem = malloc(1024); - assert_no_malloc_end(); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - assert_no_realloc_end(); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - assert_no_free_end(); - EXPECT_EQ(unexpected_mallocs, 1u); - EXPECT_EQ(unexpected_reallocs, 1u); - EXPECT_EQ(unexpected_frees, 1u); - // Enable on malloc assert, only malloc should increment. - assert_no_malloc_begin(); - mem = malloc(1024); - assert_no_malloc_end(); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - EXPECT_EQ(unexpected_mallocs, 2u); - EXPECT_EQ(unexpected_reallocs, 1u); - EXPECT_EQ(unexpected_frees, 1u); - // Enable on realloc assert, only realloc should increment. - assert_no_realloc_begin(); - mem = malloc(1024); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - assert_no_realloc_end(); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - EXPECT_EQ(unexpected_mallocs, 2u); - EXPECT_EQ(unexpected_reallocs, 2u); - EXPECT_EQ(unexpected_frees, 1u); - // Enable on free assert, only free should increment. - assert_no_free_begin(); - mem = malloc(1024); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - assert_no_free_end(); - EXPECT_EQ(unexpected_mallocs, 2u); - EXPECT_EQ(unexpected_reallocs, 2u); - EXPECT_EQ(unexpected_frees, 2u); - // Go again, after disabling asserts, should have no effect. - mem = malloc(1024); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - EXPECT_EQ(unexpected_mallocs, 2u); - EXPECT_EQ(unexpected_reallocs, 2u); - EXPECT_EQ(unexpected_frees, 2u); - // Go once more after disabling everything, should have no effect. - stop_memory_checking(); - mem = malloc(1024); - ASSERT_NE(mem, nullptr); - remem = realloc(mem, 2048); - ASSERT_NE(remem, nullptr); - if (!remem) {free(mem);} - free(remem); - EXPECT_EQ(unexpected_mallocs, 2u); - EXPECT_EQ(unexpected_reallocs, 2u); - EXPECT_EQ(unexpected_frees, 2u); -} diff --git a/rcl/test/scope_exit.hpp b/rcl/test/scope_exit.hpp deleted file mode 100644 index e1012443a..000000000 --- a/rcl/test/scope_exit.hpp +++ /dev/null @@ -1,40 +0,0 @@ -// Copyright 2015 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. - -#ifndef SCOPE_EXIT_HPP_ -#define SCOPE_EXIT_HPP_ - -#include - -template -struct ScopeExit -{ - explicit ScopeExit(Callable callable) - : callable_(callable) {} - ~ScopeExit() {callable_();} - -private: - Callable callable_; -}; - -template -ScopeExit -make_scope_exit(Callable callable) -{ - return ScopeExit(callable); -} - -#define SCOPE_EXIT(code) make_scope_exit([&]() {code;}) - -#endif // SCOPE_EXIT_HPP_ From bf0f290816e06617252e46eff03e0d65e7282bdf Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 21 May 2018 21:25:41 -0700 Subject: [PATCH 02/10] updates to use new memory_tools from osrf_testing_tools_cpp --- rcl/package.xml | 1 + rcl/test/CMakeLists.txt | 108 ++++++---- rcl/test/rcl/arg_macros.hpp | 20 +- rcl/test/rcl/client_fixture.cpp | 48 ++--- rcl/test/rcl/failing_allocator_functions.hpp | 54 +++++ rcl/test/rcl/service_fixture.cpp | 62 +++--- rcl/test/rcl/test_client.cpp | 29 +-- rcl/test/rcl/test_get_node_names.cpp | 18 +- rcl/test/rcl/test_graph.cpp | 42 +--- rcl/test/rcl/test_guard_condition.cpp | 88 ++++---- rcl/test/rcl/test_node.cpp | 216 ++++++++----------- rcl/test/rcl/test_publisher.cpp | 42 ++-- rcl/test/rcl/test_rcl.cpp | 38 ++-- rcl/test/rcl/test_service.cpp | 54 ++--- rcl/test/rcl/test_subscription.cpp | 83 +++---- rcl/test/rcl/test_time.cpp | 39 ++-- rcl/test/rcl/test_timer.cpp | 80 +++---- rcl/test/rcl/test_wait.cpp | 104 +++++---- rcl/test/test_namespace.cpp | 47 ++-- 19 files changed, 496 insertions(+), 677 deletions(-) create mode 100644 rcl/test/rcl/failing_allocator_functions.hpp diff --git a/rcl/package.xml b/rcl/package.xml index d0a57d0a8..82d790e7c 100644 --- a/rcl/package.xml +++ b/rcl/package.xml @@ -35,6 +35,7 @@ rmw_implementation_cmake launch example_interfaces + osrf_testing_tools_cpp std_msgs diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 6c8e6ad63..5be75966c 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -6,21 +6,21 @@ find_package(std_msgs REQUIRED) find_package(rmw_implementation_cmake REQUIRED) +find_package(osrf_testing_tools_cpp REQUIRED) + +get_target_property(memory_tools_ld_preload_env_var + osrf_testing_tools_cpp::memory_tools LIBRARY_PRELOAD_ENVIRONMENT_VARIABLE) + include(cmake/rcl_add_custom_executable.cmake) include(cmake/rcl_add_custom_gtest.cmake) include(cmake/rcl_add_custom_launch_test.cmake) -set(extra_test_libraries) -set(extra_test_env) set(extra_lib_dirs "${rcl_lib_dir}") # finding gtest once in the highest scope # prevents finding it repeatedly in each local scope ament_find_gtest() -# This subdirectory extends both extra_test_libraries, extra_test_env, and extra_lib_dirs. -add_subdirectory(memory_tools) - macro(test_target) find_package(${rmw_implementation} REQUIRED) test_target_function() @@ -28,42 +28,43 @@ endmacro() function(test_target_function) message(STATUS "Creating tests for '${rmw_implementation}'") - list(APPEND extra_test_env RMW_IMPLEMENTATION=${rmw_implementation}) + set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) # Gtests rcl_add_custom_gtest(test_client${target_suffix} SRCS rcl/test_client.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" ) rcl_add_custom_gtest(test_time${target_suffix} SRCS rcl/test_time.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_common${target_suffix} SRCS rcl/test_common.cpp ENV - ${extra_test_env} + ${rmw_implementation_env_var} EMPTY_TEST= NORMAL_TEST=foo APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_get_node_names${target_suffix} SRCS rcl/test_get_node_names.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} ) @@ -93,97 +94,107 @@ function(test_target_function) endif() rcl_add_custom_gtest(test_graph${target_suffix} SRCS rcl/test_graph.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" "std_msgs" ${SKIP_TEST} ) rcl_add_custom_gtest(test_rcl${target_suffix} SRCS rcl/test_rcl.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_node${target_suffix} SRCS rcl/test_node.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_arguments${target_suffix} SRCS rcl/test_arguments.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} ) rcl_add_custom_gtest(test_remap${target_suffix} SRCS rcl/test_remap.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} ) rcl_add_custom_gtest(test_remap_integration${target_suffix} SRCS rcl/test_remap_integration.cpp + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} TIMEOUT 200 - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES "std_msgs" "example_interfaces" ) rcl_add_custom_gtest(test_guard_condition${target_suffix} SRCS rcl/test_guard_condition.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_publisher${target_suffix} SRCS rcl/test_publisher.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "std_msgs" ) rcl_add_custom_gtest(test_service${target_suffix} SRCS rcl/test_service.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" ) rcl_add_custom_gtest(test_subscription${target_suffix} SRCS rcl/test_subscription.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "std_msgs" ) rcl_add_custom_gtest(test_wait${target_suffix} SRCS rcl/test_wait.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} ) rcl_add_custom_gtest(test_namespace${target_suffix} SRCS test_namespace.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" ) @@ -191,20 +202,22 @@ function(test_target_function) rcl_add_custom_executable(service_fixture${target_suffix} SRCS rcl/service_fixture.cpp - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" ) rcl_add_custom_executable(client_fixture${target_suffix} SRCS rcl/client_fixture.cpp - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} "example_interfaces" ) rcl_add_custom_launch_test(test_services service_fixture client_fixture - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} TIMEOUT 15 ) @@ -249,21 +262,22 @@ call_for_each_rmw_implementation(test_target) rcl_add_custom_gtest(test_validate_topic_name SRCS rcl/test_validate_topic_name.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} ) rcl_add_custom_gtest(test_expand_topic_name SRCS rcl/test_expand_topic_name.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} ) rcl_add_custom_gtest(test_timer${target_suffix} SRCS rcl/test_timer.cpp - ENV ${extra_test_env} + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} ) diff --git a/rcl/test/rcl/arg_macros.hpp b/rcl/test/rcl/arg_macros.hpp index 200098101..1ab5aef7f 100644 --- a/rcl/test/rcl/arg_macros.hpp +++ b/rcl/test/rcl/arg_macros.hpp @@ -19,7 +19,7 @@ #include "rcl/rcl.h" #include "rcutils/strdup.h" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" /// Helper to get around non-const args passed to rcl_init(). char ** @@ -52,12 +52,11 @@ destroy_args(int argc, char ** args) rcl_ret_t ret = rcl_init(argc, argv, rcl_get_default_allocator()); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ } \ - auto __scope_global_args_exit = make_scope_exit( \ - [argc, argv] { \ - destroy_args(argc, argv); \ - rcl_ret_t ret = rcl_shutdown(); \ - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ - }) + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \ + destroy_args(argc, argv); \ + rcl_ret_t ret = rcl_shutdown(); \ + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ + }) #define SCOPE_ARGS(local_arguments, ...) \ { \ @@ -68,9 +67,8 @@ destroy_args(int argc, char ** args) local_argc, local_argv, rcl_get_default_allocator(), &local_arguments); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ } \ - auto __scope_ ## local_arguments ## _exit = make_scope_exit( \ - [&local_arguments] { \ - ASSERT_EQ(RCL_RET_OK, rcl_arguments_fini(&local_arguments)); \ - }) + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \ + ASSERT_EQ(RCL_RET_OK, rcl_arguments_fini(&local_arguments)); \ + }) #endif // RCL__ARG_MACROS_HPP_ diff --git a/rcl/test/rcl/client_fixture.cpp b/rcl/test/rcl/client_fixture.cpp index 4cfbef77c..834df0cfb 100644 --- a/rcl/test/rcl/client_fixture.cpp +++ b/rcl/test/rcl/client_fixture.cpp @@ -23,8 +23,7 @@ #include "example_interfaces/srv/add_two_ints.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #include "rcl/graph.h" @@ -68,14 +67,13 @@ wait_for_client_to_be_ready( ROS_PACKAGE_NAME, "Error in wait set init: %s", rcl_get_error_string_safe()) return false; } - auto wait_set_exit = make_scope_exit( - [&wait_set]() { - if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { - RCUTILS_LOG_ERROR_NAMED( - ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string_safe()) - throw std::runtime_error("error while waiting for client"); - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string_safe()) + throw std::runtime_error("error while waiting for client"); + } + }); size_t iteration = 0; do { ++iteration; @@ -123,14 +121,13 @@ int main(int argc, char ** argv) ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string_safe()) return -1; } - auto node_exit = make_scope_exit( - [&main_ret, &node]() { - if (rcl_node_fini(&node) != RCL_RET_OK) { - RCUTILS_LOG_ERROR_NAMED( - ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string_safe()) - main_ret = -1; - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_node_fini(&node) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string_safe()) + main_ret = -1; + } + }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( example_interfaces, AddTwoInts); @@ -145,14 +142,13 @@ int main(int argc, char ** argv) return -1; } - auto client_exit = make_scope_exit( - [&client, &main_ret, &node]() { - if (rcl_client_fini(&client, &node)) { - RCUTILS_LOG_ERROR_NAMED( - ROS_PACKAGE_NAME, "Error in client fini: %s", rcl_get_error_string_safe()) - main_ret = -1; - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_client_fini(&client, &node)) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in client fini: %s", rcl_get_error_string_safe()) + main_ret = -1; + } + }); // Wait until server is available if (!wait_for_server_to_be_available(&node, &client, 1000, 100)) { diff --git a/rcl/test/rcl/failing_allocator_functions.hpp b/rcl/test/rcl/failing_allocator_functions.hpp new file mode 100644 index 000000000..88515380c --- /dev/null +++ b/rcl/test/rcl/failing_allocator_functions.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 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. + +#ifndef RCL__FAILING_ALLOCATOR_FUNCTIONS_HPP_ +#define RCL__FAILING_ALLOCATOR_FUNCTIONS_HPP_ + +#include + +extern "C" +{ +inline +void * +failing_malloc(size_t size, void * state) +{ + (void)size; + (void)state; + return nullptr; +} + +inline +void * +failing_realloc(void * memory_in, size_t size, void * state) +{ + (void)memory_in; + (void)size; + (void)state; + // this is the right fail case, i.e. if failed, the memory_in is not free'd + // see reallocf() for this behavior fix + return nullptr; +} + +inline +void * +failing_calloc(size_t count, size_t size, void * state) +{ + (void)count; + (void)size; + (void)state; + return nullptr; +} +} // extern "C" + +#endif // RCL__FAILING_ALLOCATOR_FUNCTIONS_HPP_ diff --git a/rcl/test/rcl/service_fixture.cpp b/rcl/test/rcl/service_fixture.cpp index ae752c85a..afd132de7 100644 --- a/rcl/test/rcl/service_fixture.cpp +++ b/rcl/test/rcl/service_fixture.cpp @@ -24,8 +24,7 @@ #include "example_interfaces/srv/add_two_ints.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" bool @@ -41,14 +40,13 @@ wait_for_service_to_be_ready( ROS_PACKAGE_NAME, "Error in wait set init: %s", rcl_get_error_string_safe()) return false; } - auto wait_set_exit = make_scope_exit( - [&wait_set]() { - if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { - RCUTILS_LOG_ERROR_NAMED( - ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string_safe()) - throw std::runtime_error("error waiting for service to be ready"); - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string_safe()) + throw std::runtime_error("error waiting for service to be ready"); + } + }); size_t iteration = 0; do { ++iteration; @@ -96,14 +94,13 @@ int main(int argc, char ** argv) ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string_safe()) return -1; } - auto node_exit = make_scope_exit( - [&main_ret, &node]() { - if (rcl_node_fini(&node) != RCL_RET_OK) { - RCUTILS_LOG_ERROR_NAMED( - ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string_safe()) - main_ret = -1; - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_node_fini(&node) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string_safe()) + main_ret = -1; + } + }); const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( example_interfaces, AddTwoInts); @@ -118,22 +115,20 @@ int main(int argc, char ** argv) return -1; } - auto service_exit = make_scope_exit( - [&main_ret, &service, &node]() { - if (rcl_service_fini(&service, &node)) { - RCUTILS_LOG_ERROR_NAMED( - ROS_PACKAGE_NAME, "Error in service fini: %s", rcl_get_error_string_safe()) - main_ret = -1; - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_service_fini(&service, &node)) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in service fini: %s", rcl_get_error_string_safe()) + main_ret = -1; + } + }); // Initialize a response. example_interfaces__srv__AddTwoInts_Response service_response; example_interfaces__srv__AddTwoInts_Response__init(&service_response); - auto response_exit = make_scope_exit( - [&service_response]() { - example_interfaces__srv__AddTwoInts_Response__fini(&service_response); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + example_interfaces__srv__AddTwoInts_Response__fini(&service_response); + }); // Block until a client request comes in. @@ -145,10 +140,9 @@ int main(int argc, char ** argv) // Take the pending request. example_interfaces__srv__AddTwoInts_Request service_request; example_interfaces__srv__AddTwoInts_Request__init(&service_request); - auto request_exit = make_scope_exit( - [&service_request]() { - example_interfaces__srv__AddTwoInts_Request__fini(&service_request); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + example_interfaces__srv__AddTwoInts_Request__fini(&service_request); + }); rmw_request_id_t header; // TODO(jacquelinekay) May have to check for timeout error codes if (rcl_take_request(&service, &header, &service_request) != RCL_RET_OK) { diff --git a/rcl/test/rcl/test_client.cpp b/rcl/test/rcl/test_client.cpp index da843f847..599fd9fcb 100644 --- a/rcl/test/rcl/test_client.cpp +++ b/rcl/test/rcl/test_client.cpp @@ -21,8 +21,8 @@ #include "example_interfaces/srv/add_two_ints.h" #include "rosidl_generator_c/string_functions.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "./failing_allocator_functions.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" class TestClientFixture : public ::testing::Test @@ -31,7 +31,6 @@ class TestClientFixture : public ::testing::Test rcl_node_t * node_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -41,21 +40,10 @@ class TestClientFixture : public ::testing::Test rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -67,7 +55,6 @@ class TestClientFixture : public ::testing::Test /* Basic nominal test of a client. */ TEST_F(TestClientFixture, test_client_nominal) { - stop_memory_checking(); rcl_ret_t ret; rcl_client_t client = rcl_get_zero_initialized_client(); @@ -84,12 +71,10 @@ TEST_F(TestClientFixture, test_client_nominal) { ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0); - auto client_exit = make_scope_exit( - [&client, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); // Initialize the client request. example_interfaces__srv__AddTwoInts_Request req; @@ -108,7 +93,6 @@ TEST_F(TestClientFixture, test_client_nominal) { /* Testing the client init and fini functions. */ TEST_F(TestClientFixture, test_client_init_fini) { - stop_memory_checking(); rcl_ret_t ret; // Setup valid inputs. rcl_client_t client; @@ -197,7 +181,6 @@ TEST_F(TestClientFixture, test_client_init_fini) { rcl_client_options_t client_options_with_failing_allocator; client_options_with_failing_allocator = rcl_client_get_default_options(); client_options_with_failing_allocator.allocator.allocate = failing_malloc; - client_options_with_failing_allocator.allocator.deallocate = failing_free; client_options_with_failing_allocator.allocator.reallocate = failing_realloc; ret = rcl_client_init( &client, this->node_ptr, ts, topic_name, &client_options_with_failing_allocator); diff --git a/rcl/test/rcl/test_get_node_names.cpp b/rcl/test/rcl/test_get_node_names.cpp index 3345a0579..9cf340eb6 100644 --- a/rcl/test/rcl/test_get_node_names.cpp +++ b/rcl/test/rcl/test_get_node_names.cpp @@ -25,7 +25,6 @@ #include "rcl/rcl.h" #include "rmw/rmw.h" -#include "../memory_tools/memory_tools.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -41,23 +40,10 @@ class CLASSNAME (TestGetNodeNames, RMW_IMPLEMENTATION) : public ::testing::Test { public: void SetUp() - { - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); - } + {} void TearDown() - { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); - } + {} }; TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) { diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 0d75ef3df..a10baf0f6 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -35,8 +35,7 @@ #include "std_msgs/msg/string.h" #include "example_interfaces/srv/add_two_ints.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -57,7 +56,6 @@ class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test rcl_wait_set_t * wait_set_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -81,22 +79,10 @@ class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test this->wait_set_ptr = new rcl_wait_set_t; *this->wait_set_ptr = rcl_get_zero_initialized_wait_set(); ret = rcl_wait_set_init(this->wait_set_ptr, 0, 1, 0, 0, 0, rcl_get_default_allocator()); - - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret; ret = rcl_node_fini(this->old_node_ptr); delete this->old_node_ptr; @@ -123,7 +109,6 @@ TEST_F( CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_get_and_destroy_topic_names_and_types ) { - stop_memory_checking(); rcl_ret_t ret; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_names_and_types_t tnat {}; @@ -165,7 +150,6 @@ TEST_F( CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_count_publishers ) { - stop_memory_checking(); rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); const char * topic_name = "/topic_test_rcl_count_publishers"; @@ -203,7 +187,6 @@ TEST_F( CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_count_subscribers ) { - stop_memory_checking(); rcl_ret_t ret; rcl_node_t zero_node = rcl_get_zero_initialized_node(); const char * topic_name = "/topic_test_rcl_count_subscribers"; @@ -330,7 +313,6 @@ check_graph_state( /* Test graph queries with a hand crafted graph. */ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functions) { - stop_memory_checking(); std::string topic_name("/test_graph_query_functions__"); std::chrono::nanoseconds now = std::chrono::system_clock::now().time_since_epoch(); topic_name += std::to_string(now.count()); @@ -416,7 +398,6 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio * Note: this test could be impacted by other communications on the same ROS Domain. */ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_condition_topics) { - stop_memory_checking(); rcl_ret_t ret; // Create a thread to sleep for a time, then create a publisher, sleep more, then a subscriber, // sleep more, destroy the subscriber, sleep more, and then destroy the publisher. @@ -485,7 +466,6 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi /* Test the rcl_service_server_is_available function. */ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_is_available) { - stop_memory_checking(); rcl_ret_t ret; // First create a client which will be used to call the function. rcl_client_t client = rcl_get_zero_initialized_client(); @@ -494,12 +474,10 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_ rcl_client_options_t client_options = rcl_client_get_default_options(); ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto client_exit = make_scope_exit( - [&client, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); // Check, knowing there is no service server (created by us at least). bool is_available; ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available); @@ -563,12 +541,10 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_ rcl_service_options_t service_options = rcl_service_get_default_options(); ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto service_exit = make_scope_exit( - [&service, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); // Wait for and then assert that it is available. wait_for_service_state_to_change(true, is_available); ASSERT_TRUE(is_available); diff --git a/rcl/test/rcl/test_guard_condition.cpp b/rcl/test/rcl/test_guard_condition.cpp index 2f2f3e1e2..3abe6efbb 100644 --- a/rcl/test/rcl/test_guard_condition.cpp +++ b/rcl/test/rcl/test_guard_condition.cpp @@ -19,8 +19,9 @@ #include "rcl/rcl.h" #include "rcl/guard_condition.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "./failing_allocator_functions.hpp" +#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -30,26 +31,26 @@ # define CLASSNAME(NAME, SUFFIX) NAME #endif +using osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_free; + class CLASSNAME (TestGuardConditionFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: void SetUp() { - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); + osrf_testing_tools_cpp::memory_tools::initialize(); + on_unexpected_malloc([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); + on_unexpected_realloc([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); + on_unexpected_calloc([]() {ASSERT_FALSE(true) << "UNEXPECTED CALLOC";}); + on_unexpected_free([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); + osrf_testing_tools_cpp::memory_tools::uninitialize(); } }; @@ -57,19 +58,19 @@ class CLASSNAME (TestGuardConditionFixture, RMW_IMPLEMENTATION) : public ::testi */ TEST_F( CLASSNAME(TestGuardConditionFixture, RMW_IMPLEMENTATION), test_rcl_guard_condition_accessors) { - stop_memory_checking(); + osrf_testing_tools_cpp::memory_tools::enable_monitoring_in_all_threads(); + rcl_ret_t ret; // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); // Setup automatic rcl_shutdown() - auto rcl_shutdown_exit = make_scope_exit( - []() { - stop_memory_checking(); - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); // Create a zero initialized guard_condition (but not initialized). rcl_guard_condition_t zero_guard_condition = rcl_get_zero_initialized_guard_condition(); @@ -80,12 +81,11 @@ TEST_F( ret = rcl_guard_condition_init(&guard_condition, default_options); ASSERT_EQ(RCL_RET_OK, ret); // Setup automatic finalization of guard condition. - auto rcl_guard_condition_exit = make_scope_exit( - [&guard_condition]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_guard_condition_fini(&guard_condition); - EXPECT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + rcl_ret_t ret = rcl_guard_condition_fini(&guard_condition); + EXPECT_EQ(RCL_RET_OK, ret); + }); // Test rcl_guard_condition_get_options(). const rcl_guard_condition_options_t * actual_options; @@ -95,15 +95,9 @@ TEST_F( actual_options = rcl_guard_condition_get_options(&zero_guard_condition); EXPECT_EQ(nullptr, actual_options); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - actual_options = rcl_guard_condition_get_options(&guard_condition); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + actual_options = rcl_guard_condition_get_options(&guard_condition); + }); EXPECT_NE(nullptr, actual_options); if (actual_options) { EXPECT_EQ(default_options.allocator.allocate, actual_options->allocator.allocate); @@ -116,15 +110,9 @@ TEST_F( gc_handle = rcl_guard_condition_get_rmw_handle(&zero_guard_condition); EXPECT_EQ(nullptr, gc_handle); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - gc_handle = rcl_guard_condition_get_rmw_handle(&guard_condition); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + gc_handle = rcl_guard_condition_get_rmw_handle(&guard_condition); + }); EXPECT_NE(nullptr, gc_handle); } @@ -132,7 +120,6 @@ TEST_F( */ TEST_F( CLASSNAME(TestGuardConditionFixture, RMW_IMPLEMENTATION), test_rcl_guard_condition_life_cycle) { - stop_memory_checking(); rcl_ret_t ret; rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); rcl_guard_condition_options_t default_options = rcl_guard_condition_get_default_options(); @@ -144,11 +131,10 @@ TEST_F( // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_shutdown_exit = make_scope_exit( - []() { - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); // Try invalid arguments. ret = rcl_guard_condition_init(nullptr, default_options); ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT"; @@ -168,8 +154,8 @@ TEST_F( rcl_guard_condition_options_t options_with_failing_allocator = rcl_guard_condition_get_default_options(); options_with_failing_allocator.allocator.allocate = failing_malloc; - options_with_failing_allocator.allocator.deallocate = failing_free; options_with_failing_allocator.allocator.reallocate = failing_realloc; + options_with_failing_allocator.allocator.zero_allocate = failing_calloc; ret = rcl_guard_condition_init(&guard_condition, options_with_failing_allocator); ASSERT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC"; // The error will not be set because the allocator will not work. diff --git a/rcl/test/rcl/test_node.cpp b/rcl/test/rcl/test_node.cpp index c97284a09..4197622cb 100644 --- a/rcl/test/rcl/test_node.cpp +++ b/rcl/test/rcl/test_node.cpp @@ -14,14 +14,16 @@ #include +#include #include #include "rcl/rcl.h" #include "rcl/node.h" #include "rmw/rmw.h" // For rmw_get_implementation_identifier. -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "./failing_allocator_functions.hpp" +#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -31,26 +33,42 @@ # define CLASSNAME(NAME, SUFFIX) NAME #endif +using osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_free; + class CLASSNAME (TestNodeFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: void SetUp() { - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); + auto common = + [](auto service, const char * name) { + // only fail if call originated in our library, librcl. + std::regex pattern("/?librcl\\."); + auto st = service.get_stack_trace(); // nullptr if stack trace not available + if (st && st->matches_any_object_filename(pattern)) { + // Implicitly this means if one of the rmw implementations uses threads + // and does memory allocations in them, but the calls didn't originate + // from an rcl call, we will ignore it. + // The goal here is ensure that no rcl function or thread is using memory. + // Separate tests will be needed to ensure the rmw implementation does + // not allocate memory or cause it to be allocated. + service.print_backtrace(); + ADD_FAILURE() << "Unexpected call to " << name << " originating from within librcl."; + } + }; + osrf_testing_tools_cpp::memory_tools::initialize(); + on_unexpected_malloc([common](auto service) {common(service, "malloc");}); + on_unexpected_realloc([common](auto service) {common(service, "realloc");}); + on_unexpected_calloc([common](auto service) {common(service, "calloc");}); + on_unexpected_free([common](auto service) {common(service, "free");}); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); + osrf_testing_tools_cpp::memory_tools::uninitialize(); } }; @@ -65,7 +83,7 @@ bool is_windows = false; /* Tests the node accessors, i.e. rcl_node_get_* functions. */ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) { - stop_memory_checking(); + osrf_testing_tools_cpp::memory_tools::enable_monitoring_in_all_threads(); rcl_ret_t ret; // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); @@ -88,34 +106,31 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) // This is the normal check (not windows and windows if not opensplice) ASSERT_EQ(RCL_RET_OK, ret); } - auto rcl_invalid_node_exit = make_scope_exit( - [&invalid_node]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_node_fini(&invalid_node); - EXPECT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + rcl_ret_t ret = rcl_node_fini(&invalid_node); + EXPECT_EQ(RCL_RET_OK, ret); + }); ret = rcl_shutdown(); // Shutdown to invalidate the node. ASSERT_EQ(RCL_RET_OK, ret); ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_shutdown_exit = make_scope_exit( - []() { - stop_memory_checking(); - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); // Create a zero init node. rcl_node_t zero_node = rcl_get_zero_initialized_node(); // Create a normal node. rcl_node_t node = rcl_get_zero_initialized_node(); ret = rcl_node_init(&node, name, namespace_, &default_options); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_node_exit = make_scope_exit( - [&node]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_node_fini(&node); - EXPECT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + rcl_ret_t ret = rcl_node_fini(&node); + EXPECT_EQ(RCL_RET_OK, ret); + }); // Test rcl_node_is_valid(). bool is_valid; is_valid = rcl_node_is_valid(nullptr, nullptr); @@ -141,15 +156,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) actual_node_name = rcl_node_get_name(&invalid_node); EXPECT_EQ(nullptr, actual_node_name); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - actual_node_name = rcl_node_get_name(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + actual_node_name = rcl_node_get_name(&node); + }); EXPECT_TRUE(actual_node_name ? true : false); if (actual_node_name) { EXPECT_EQ(std::string(name), std::string(actual_node_name)); @@ -165,15 +174,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) actual_node_namespace = rcl_node_get_namespace(&invalid_node); EXPECT_EQ(nullptr, actual_node_namespace); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - actual_node_namespace = rcl_node_get_namespace(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + actual_node_namespace = rcl_node_get_namespace(&node); + }); EXPECT_TRUE(actual_node_namespace ? true : false); if (actual_node_namespace) { EXPECT_EQ(std::string(namespace_), std::string(actual_node_namespace)); @@ -189,15 +192,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) actual_node_logger_name = rcl_node_get_logger_name(&invalid_node); EXPECT_EQ(nullptr, actual_node_logger_name); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - actual_node_logger_name = rcl_node_get_logger_name(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + actual_node_logger_name = rcl_node_get_logger_name(&node); + }); EXPECT_TRUE(actual_node_logger_name ? true : false); if (actual_node_logger_name) { EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name)); @@ -213,15 +210,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) actual_options = rcl_node_get_options(&invalid_node); EXPECT_EQ(nullptr, actual_options); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - actual_options = rcl_node_get_options(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + actual_options = rcl_node_get_options(&node); + }); EXPECT_NE(nullptr, actual_options); if (actual_options) { EXPECT_EQ(default_options.allocator.allocate, actual_options->allocator.allocate); @@ -241,15 +232,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(RCL_RET_NODE_INVALID, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - ret = rcl_node_get_domain_id(&node, &actual_domain_id); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + ret = rcl_node_get_domain_id(&node, &actual_domain_id); + }); EXPECT_EQ(RCL_RET_OK, ret); if (RCL_RET_OK == ret && (!is_windows || !is_opensplice)) { // Can only expect the domain id to be 42 if not windows or not opensplice. @@ -266,15 +251,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) node_handle = rcl_node_get_rmw_handle(&invalid_node); EXPECT_EQ(nullptr, node_handle); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - node_handle = rcl_node_get_rmw_handle(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + node_handle = rcl_node_get_rmw_handle(&node); + }); EXPECT_NE(nullptr, node_handle); // Test rcl_node_get_rcl_instance_id(). uint64_t instance_id; @@ -288,15 +267,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_NE(0u, instance_id); EXPECT_NE(42u, instance_id); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - instance_id = rcl_node_get_rcl_instance_id(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + instance_id = rcl_node_get_rcl_instance_id(&node); + }); EXPECT_NE(0u, instance_id); // Test rcl_node_get_graph_guard_condition const rcl_guard_condition_t * graph_guard_condition = nullptr; @@ -309,22 +282,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) graph_guard_condition = rcl_node_get_graph_guard_condition(&invalid_node); EXPECT_EQ(nullptr, graph_guard_condition); rcl_reset_error(); - start_memory_checking(); - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - graph_guard_condition = rcl_node_get_graph_guard_condition(&node); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + graph_guard_condition = rcl_node_get_graph_guard_condition(&node); + }); EXPECT_NE(nullptr, graph_guard_condition); } /* Tests the node life cycle, including rcl_node_init() and rcl_node_fini(). */ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) { - stop_memory_checking(); rcl_ret_t ret; rcl_node_t node = rcl_get_zero_initialized_node(); const char * name = "test_rcl_node_life_cycle_node"; @@ -338,11 +304,10 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_shutdown_exit = make_scope_exit( - []() { - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); // Try invalid arguments. ret = rcl_node_init(nullptr, name, namespace_, &default_options); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); @@ -372,7 +337,6 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) // Try with failing allocator. rcl_node_options_t options_with_failing_allocator = rcl_node_get_default_options(); options_with_failing_allocator.allocator.allocate = failing_malloc; - options_with_failing_allocator.allocator.deallocate = failing_free; options_with_failing_allocator.allocator.reallocate = failing_realloc; ret = rcl_node_init(&node, name, namespace_, &options_with_failing_allocator); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC"; @@ -423,17 +387,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) /* Tests the node name restrictions enforcement. */ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restrictions) { - stop_memory_checking(); rcl_ret_t ret; // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_shutdown_exit = make_scope_exit( - []() { - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); const char * namespace_ = "/ns"; rcl_node_options_t default_options = rcl_node_get_default_options(); @@ -484,17 +446,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri /* Tests the node namespace restrictions enforcement. */ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_restrictions) { - stop_memory_checking(); rcl_ret_t ret; // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_shutdown_exit = make_scope_exit( - []() { - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); const char * name = "node"; rcl_node_options_t default_options = rcl_node_get_default_options(); @@ -583,17 +543,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r /* Tests the logger name associated with the node. */ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name) { - stop_memory_checking(); rcl_ret_t ret; // Initialize rcl with rcl_init(). ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret); - auto rcl_shutdown_exit = make_scope_exit( - []() { - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_shutdown(); + ASSERT_EQ(RCL_RET_OK, ret); + }); const char * name = "node"; const char * actual_node_logger_name; diff --git a/rcl/test/rcl/test_publisher.cpp b/rcl/test/rcl/test_publisher.cpp index ecc5484c1..f40f722c7 100644 --- a/rcl/test/rcl/test_publisher.cpp +++ b/rcl/test/rcl/test_publisher.cpp @@ -21,8 +21,8 @@ #include "std_msgs/msg/string.h" #include "rosidl_generator_c/string_functions.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "./failing_allocator_functions.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -38,7 +38,6 @@ class CLASSNAME (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::T rcl_node_t * node_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -48,21 +47,10 @@ class CLASSNAME (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::T rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -74,7 +62,6 @@ class CLASSNAME (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::T /* Basic nominal test of a publisher. */ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal) { - stop_memory_checking(); rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64); @@ -93,12 +80,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto publisher_exit = make_scope_exit( - [&publisher, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0); std_msgs__msg__Int64 msg; std_msgs__msg__Int64__init(&msg); @@ -111,7 +96,6 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin /* Basic nominal test of a publisher with a string. */ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nominal_string) { - stop_memory_checking(); rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String); @@ -119,12 +103,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto publisher_exit = make_scope_exit( - [&publisher, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); std_msgs__msg__String msg; std_msgs__msg__String__init(&msg); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.data, "testing")); @@ -136,7 +118,6 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin /* Testing the publisher init and fini functions. */ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_fini) { - stop_memory_checking(); rcl_ret_t ret; // Setup valid inputs. rcl_publisher_t publisher; @@ -146,6 +127,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_ // Check if null publisher is valid EXPECT_FALSE(rcl_publisher_is_valid(nullptr, nullptr)); + rcl_reset_error(); // Check if zero initialized node is valid publisher = rcl_get_zero_initialized_publisher(); @@ -222,8 +204,8 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_ rcl_publisher_options_t publisher_options_with_failing_allocator; publisher_options_with_failing_allocator = rcl_publisher_get_default_options(); publisher_options_with_failing_allocator.allocator.allocate = failing_malloc; - publisher_options_with_failing_allocator.allocator.deallocate = failing_free; publisher_options_with_failing_allocator.allocator.reallocate = failing_realloc; + publisher_options_with_failing_allocator.allocator.zero_allocate = failing_calloc; ret = rcl_publisher_init( &publisher, this->node_ptr, ts, topic_name, &publisher_options_with_failing_allocator); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string_safe(); diff --git a/rcl/test/rcl/test_rcl.cpp b/rcl/test/rcl/test_rcl.cpp index 83194a90a..d00859fd7 100644 --- a/rcl/test/rcl/test_rcl.cpp +++ b/rcl/test/rcl/test_rcl.cpp @@ -16,7 +16,8 @@ #include "rcl/rcl.h" -#include "../memory_tools/memory_tools.hpp" +#include "./failing_allocator_functions.hpp" +#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp" #include "rcl/error_handling.h" #include "rcutils/snprintf.h" @@ -27,26 +28,25 @@ # define CLASSNAME(NAME, SUFFIX) NAME #endif +using osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_free; + class CLASSNAME (TestRCLFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: void SetUp() { - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); + osrf_testing_tools_cpp::memory_tools::initialize(); + on_unexpected_malloc([]() {ADD_FAILURE() << "UNEXPECTED MALLOC";}); + on_unexpected_realloc([]() {ADD_FAILURE() << "UNEXPECTED REALLOC";}); + on_unexpected_free([]() {ADD_FAILURE() << "UNEXPECTED FREE";}); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); + osrf_testing_tools_cpp::memory_tools::uninitialize(); } }; @@ -117,9 +117,9 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_and_ok_and_s { FakeTestArgv test_args; rcl_allocator_t failing_allocator = rcl_get_default_allocator(); - failing_allocator.allocate = &failing_malloc; - failing_allocator.deallocate = failing_free; + failing_allocator.allocate = failing_malloc; failing_allocator.reallocate = failing_realloc; + failing_allocator.zero_allocate = failing_calloc; ret = rcl_init(test_args.argc, test_args.argv, failing_allocator); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret); rcl_reset_error(); @@ -187,13 +187,9 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_get_instance_id_a } // And it should be allocation free. uint64_t first_instance_id; - assert_no_malloc_begin(); - assert_no_realloc_begin(); - assert_no_free_begin(); - first_instance_id = rcl_get_instance_id(); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); + EXPECT_NO_MEMORY_OPERATIONS({ + first_instance_id = rcl_get_instance_id(); + }); EXPECT_NE(0u, first_instance_id); EXPECT_EQ(first_instance_id, rcl_get_instance_id()); // Repeat calls should return the same. EXPECT_EQ(true, rcl_ok()); diff --git a/rcl/test/rcl/test_service.cpp b/rcl/test/rcl/test_service.cpp index 9318423a5..6ca020e22 100644 --- a/rcl/test/rcl/test_service.cpp +++ b/rcl/test/rcl/test_service.cpp @@ -24,8 +24,7 @@ #include "example_interfaces/srv/add_two_ints.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -41,7 +40,6 @@ class CLASSNAME (TestServiceFixture, RMW_IMPLEMENTATION) : public ::testing::Tes rcl_node_t * node_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -51,21 +49,10 @@ class CLASSNAME (TestServiceFixture, RMW_IMPLEMENTATION) : public ::testing::Tes rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -84,12 +71,10 @@ wait_for_service_to_be_ready( rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto wait_set_exit = make_scope_exit( - [&wait_set]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_wait_set_fini(&wait_set); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_wait_set_fini(&wait_set); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); size_t iteration = 0; do { ++iteration; @@ -115,7 +100,6 @@ wait_for_service_to_be_ready( /* Basic nominal test of a service. */ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) { - stop_memory_checking(); rcl_ret_t ret; const rosidl_service_type_support_t * ts = ROSIDL_GET_SRV_TYPE_SUPPORT( example_interfaces, AddTwoInts); @@ -145,23 +129,19 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) // Check that the service name matches what we assigned. EXPECT_EQ(strcmp(rcl_service_get_service_name(&service), expected_topic), 0); - auto service_exit = make_scope_exit( - [&service, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_options_t client_options = rcl_client_get_default_options(); ret = rcl_client_init(&client, this->node_ptr, ts, topic, &client_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto client_exit = make_scope_exit( - [&client, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); // TODO(wjwwood): add logic to wait for the connection to be established // use count_services busy wait mechanism @@ -189,11 +169,9 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal) // Initialize a response. example_interfaces__srv__AddTwoInts_Response service_response; example_interfaces__srv__AddTwoInts_Response__init(&service_response); - auto msg_exit = make_scope_exit( - [&service_response]() { - stop_memory_checking(); - example_interfaces__srv__AddTwoInts_Response__fini(&service_response); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + example_interfaces__srv__AddTwoInts_Response__fini(&service_response); + }); // Initialize a separate instance of the request and take the pending request. example_interfaces__srv__AddTwoInts_Request service_request; diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index f258cced5..3aee2e808 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -25,8 +25,7 @@ #include "std_msgs/msg/string.h" #include "rosidl_generator_c/string_functions.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #ifdef RMW_IMPLEMENTATION @@ -42,7 +41,6 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing rcl_node_t * node_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -52,21 +50,10 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -85,12 +72,10 @@ wait_for_subscription_to_be_ready( rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 0, 0, 0, 0, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto wait_set_exit = make_scope_exit( - [&wait_set]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_wait_set_fini(&wait_set); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_wait_set_fini(&wait_set); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); size_t iteration = 0; do { ++iteration; @@ -116,7 +101,6 @@ wait_for_subscription_to_be_ready( /* Basic nominal test of a subscription. */ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal) { - stop_memory_checking(); rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Int64); @@ -135,22 +119,18 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto publisher_exit = make_scope_exit( - [&publisher, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto subscription_exit = make_scope_exit( - [&subscription, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); EXPECT_EQ(strcmp(rcl_subscription_get_topic_name(&subscription), expected_topic), 0); // Test is_valid for subscription with nullptr @@ -187,11 +167,9 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription { std_msgs__msg__Int64 msg; std_msgs__msg__Int64__init(&msg); - auto msg_exit = make_scope_exit( - [&msg]() { - stop_memory_checking(); - std_msgs__msg__Int64__fini(&msg); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + std_msgs__msg__Int64__fini(&msg); + }); ret = rcl_take(&subscription, &msg, nullptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(42, msg.data); @@ -201,7 +179,6 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Basic nominal test of a publisher with a string. */ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_nominal_string) { - stop_memory_checking(); rcl_ret_t ret; rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String); @@ -209,22 +186,18 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto publisher_exit = make_scope_exit( - [&publisher, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto subscription_exit = make_scope_exit( - [&subscription, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); // TODO(wjwwood): add logic to wait for the connection to be established // probably using the count_subscriptions busy wait mechanism // until then we will sleep for a short period of time @@ -244,11 +217,9 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription { std_msgs__msg__String msg; std_msgs__msg__String__init(&msg); - auto msg_exit = make_scope_exit( - [&msg]() { - stop_memory_checking(); - std_msgs__msg__String__fini(&msg); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + std_msgs__msg__String__fini(&msg); + }); ret = rcl_take(&subscription, &msg, nullptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(std::string(test_string), std::string(msg.data.data, msg.data.size)); diff --git a/rcl/test/rcl/test_time.cpp b/rcl/test/rcl/test_time.cpp index 895509201..85e426930 100644 --- a/rcl/test/rcl/test_time.cpp +++ b/rcl/test/rcl/test_time.cpp @@ -19,11 +19,10 @@ #include #include +#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp" #include "rcl/error_handling.h" #include "rcl/time.h" -#include "../memory_tools/memory_tools.hpp" - #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX # define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) @@ -31,37 +30,37 @@ # define CLASSNAME(NAME, SUFFIX) NAME #endif +using osrf_testing_tools_cpp::memory_tools::on_unexpected_malloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc; +using osrf_testing_tools_cpp::memory_tools::on_unexpected_free; + class CLASSNAME (TestTimeFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: void SetUp() { - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); + osrf_testing_tools_cpp::memory_tools::initialize(); + on_unexpected_malloc([]() {ADD_FAILURE() << "UNEXPECTED MALLOC";}); + on_unexpected_realloc([]() {ADD_FAILURE() << "UNEXPECTED REALLOC";}); + on_unexpected_calloc([]() {ADD_FAILURE() << "UNEXPECTED CALLOC";}); + on_unexpected_free([]() {ADD_FAILURE() << "UNEXPECTED FREE";}); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); + osrf_testing_tools_cpp::memory_tools::uninitialize(); } }; // Tests the rcl_set_ros_time_override() function. TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_ros_time_set_override) { + osrf_testing_tools_cpp::memory_tools::enable_monitoring_in_all_threads(); rcl_clock_t ros_clock; rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator); EXPECT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); - assert_no_realloc_begin(); rcl_ret_t ret; // Check for invalid argument error condition (allowed to alloc). ret = rcl_set_ros_time_override(nullptr, 0); @@ -82,14 +81,10 @@ TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_ros_time_set_ove ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(is_enabled, false); - assert_no_malloc_begin(); - assert_no_free_begin(); - // Check for normal operation (not allowed to alloc). - ret = rcl_clock_get_now(&ros_clock, &query_now); - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); + EXPECT_NO_MEMORY_OPERATIONS({ + // Check for normal operation (not allowed to alloc). + ret = rcl_clock_get_now(&ros_clock, &query_now); + }); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_NE(query_now.nanoseconds, 0u); // Compare to std::chrono::system_clock time (within a second). diff --git a/rcl/test/rcl/test_timer.cpp b/rcl/test/rcl/test_timer.cpp index 571e3f9a8..2b8971e4d 100644 --- a/rcl/test/rcl/test_timer.cpp +++ b/rcl/test/rcl/test_timer.cpp @@ -18,18 +18,15 @@ #include "rcl/rcl.h" -#include "../memory_tools/memory_tools.hpp" -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" - class TestTimerFixture : public ::testing::Test { public: rcl_node_t * node_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -39,21 +36,10 @@ class TestTimerFixture : public ::testing::Test rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -63,7 +49,6 @@ class TestTimerFixture : public ::testing::Test }; TEST_F(TestTimerFixture, test_two_timers) { - stop_memory_checking(); rcl_ret_t ret; rcl_timer_t timer = rcl_get_zero_initialized_timer(); rcl_timer_t timer2 = rcl_get_zero_initialized_timer(); @@ -82,15 +67,14 @@ TEST_F(TestTimerFixture, test_two_timers) { EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_wait_set_add_timer(&wait_set, &timer2); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto timer_exit = make_scope_exit([&timer, &timer2, &wait_set]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_timer_fini(&timer); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_timer_fini(&timer2); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_timer_fini(&timer); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_timer_fini(&timer2); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(10)); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); uint8_t nonnull_timers = 0; @@ -110,7 +94,6 @@ TEST_F(TestTimerFixture, test_two_timers) { } TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) { - stop_memory_checking(); rcl_ret_t ret; rcl_timer_t timer = rcl_get_zero_initialized_timer(); rcl_timer_t timer2 = rcl_get_zero_initialized_timer(); @@ -129,15 +112,14 @@ TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) { EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ret = rcl_wait_set_add_timer(&wait_set, &timer2); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto timer_exit = make_scope_exit([&timer, &timer2, &wait_set]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_timer_fini(&timer); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_timer_fini(&timer2); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_timer_fini(&timer); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_timer_fini(&timer2); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(20)); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); uint8_t nonnull_timers = 0; @@ -157,7 +139,6 @@ TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) { } TEST_F(TestTimerFixture, test_timer_not_ready) { - stop_memory_checking(); rcl_ret_t ret; rcl_timer_t timer = rcl_get_zero_initialized_timer(); @@ -171,13 +152,12 @@ TEST_F(TestTimerFixture, test_timer_not_ready) { ret = rcl_wait_set_add_timer(&wait_set, &timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto timer_exit = make_scope_exit([&timer, &wait_set]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_timer_fini(&timer); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_timer_fini(&timer); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1)); EXPECT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); uint8_t nonnull_timers = 0; @@ -194,7 +174,6 @@ TEST_F(TestTimerFixture, test_timer_not_ready) { } TEST_F(TestTimerFixture, test_canceled_timer) { - stop_memory_checking(); rcl_ret_t ret; rcl_timer_t timer = rcl_get_zero_initialized_timer(); @@ -211,13 +190,12 @@ TEST_F(TestTimerFixture, test_canceled_timer) { ret = rcl_wait_set_add_timer(&wait_set, &timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto timer_exit = make_scope_exit([&timer, &wait_set]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_timer_fini(&timer); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_timer_fini(&timer); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1)); EXPECT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); uint8_t nonnull_timers = 0; diff --git a/rcl/test/rcl/test_wait.cpp b/rcl/test/rcl/test_wait.cpp index b141c1f71..7458696d8 100644 --- a/rcl/test/rcl/test_wait.cpp +++ b/rcl/test/rcl/test_wait.cpp @@ -22,9 +22,9 @@ #include "gtest/gtest.h" -#include "../scope_exit.hpp" -#include "rcl/rcl.h" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" +#include "rcl/rcl.h" #include "rcl/wait.h" #include "rcutils/logging_macros.h" @@ -109,15 +109,14 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) { ret = rcl_wait_set_add_timer(&wait_set, &timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto scope_exit = make_scope_exit( - [&guard_cond, &wait_set, &timer]() { - rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_timer_fini(&timer); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_timer_fini(&timer); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); int64_t timeout = -1; std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); @@ -143,15 +142,14 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) { ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto scope_exit = make_scope_exit( - [&guard_cond, &wait_set]() { - rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); - // Time spent during wait should be negligible. +// Time spent during wait should be negligible. int64_t timeout = 0; std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); ret = rcl_wait(&wait_set, timeout); @@ -176,15 +174,14 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered ret = rcl_trigger_guard_condition(&guard_cond); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto scope_exit = make_scope_exit( - [&guard_cond, &wait_set]() { - rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); - // Time spent during wait should be negligible. +// Time spent during wait should be negligible. int64_t timeout = 0; std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); ret = rcl_wait(&wait_set, timeout); @@ -216,15 +213,14 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) { ret = rcl_wait_set_add_timer(&wait_set, &canceled_timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto scope_exit = make_scope_exit( - [&guard_cond, &wait_set, &canceled_timer]() { - rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_timer_fini(&canceled_timer); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_timer_fini(&canceled_timer); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); int64_t timeout = RCL_MS_TO_NS(10); std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); @@ -267,9 +263,9 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade std::vector test_sets(number_of_threads); // Setup common function for waiting on the triggered guard conditions. auto wait_func_factory = - [count_target, retry_limit, wait_period](TestSet & test_set) { + [](TestSet & test_set) { return - [&test_set, count_target, retry_limit, wait_period]() { + [&test_set]() { while (test_set.wake_count < count_target) { bool change_detected = false; size_t wake_try_count = 0; @@ -328,15 +324,14 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade test_set.thread_id = 0; } // Setup safe tear-down. - auto scope_exit = make_scope_exit( - [&test_sets]() { - for (auto & test_set : test_sets) { - rcl_ret_t ret = rcl_guard_condition_fini(&test_set.guard_condition); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_wait_set_fini(&test_set.wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - } - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + for (auto & test_set : test_sets) { + rcl_ret_t ret = rcl_guard_condition_fini(&test_set.guard_condition); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_wait_set_fini(&test_set.wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + } + }); // Now kick off all the threads. size_t thread_enumeration = 0; for (auto & test_set : test_sets) { @@ -346,7 +341,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade } // Loop, triggering every trigger_period until the threads are done. auto loop_test = - [&test_sets, count_target]() -> bool { + [&test_sets]() -> bool { for (const auto & test_set : test_sets) { if (test_set.wake_count.load() < count_target) { return true; @@ -385,13 +380,12 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) { ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto scope_exit = make_scope_exit( - [&wait_set, &guard_cond]() { - rcl_ret_t ret = rcl_wait_set_fini(&wait_set); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - ret = rcl_guard_condition_fini(&guard_cond); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_wait_set_fini(&wait_set); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + ret = rcl_guard_condition_fini(&guard_cond); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); std::promise p; diff --git a/rcl/test/test_namespace.cpp b/rcl/test/test_namespace.cpp index aee0027f1..ad5479819 100644 --- a/rcl/test/test_namespace.cpp +++ b/rcl/test/test_namespace.cpp @@ -25,8 +25,7 @@ #include "example_interfaces/srv/add_two_ints.h" #include "rosidl_generator_c/string_functions.h" -#include "./memory_tools/memory_tools.hpp" -#include "./scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" using namespace std::chrono_literals; @@ -37,7 +36,6 @@ class TestNamespaceFixture : public ::testing::Test rcl_node_t * node_ptr; void SetUp() { - stop_memory_checking(); rcl_ret_t ret; ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -47,21 +45,10 @@ class TestNamespaceFixture : public ::testing::Test rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - set_on_unexpected_malloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED MALLOC";}); - set_on_unexpected_realloc_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED REALLOC";}); - set_on_unexpected_free_callback([]() {ASSERT_FALSE(true) << "UNEXPECTED FREE";}); - start_memory_checking(); } void TearDown() { - assert_no_malloc_end(); - assert_no_realloc_end(); - assert_no_free_end(); - stop_memory_checking(); - set_on_unexpected_malloc_callback(nullptr); - set_on_unexpected_realloc_callback(nullptr); - set_on_unexpected_free_callback(nullptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); @@ -73,8 +60,6 @@ class TestNamespaceFixture : public ::testing::Test /* Basic nominal test of a client. */ TEST_F(TestNamespaceFixture, test_client_server) { - stop_memory_checking(); - rcl_ret_t ret; auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(example_interfaces, AddTwoInts); const char * service_name = "/my/namespace/test_namespace_client_server"; @@ -86,24 +71,20 @@ TEST_F(TestNamespaceFixture, test_client_server) { rcl_service_options_t service_options = rcl_service_get_default_options(); ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto service_exit = make_scope_exit( - [&service, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); rcl_client_t unmatched_client = rcl_get_zero_initialized_client(); rcl_client_options_t unmatched_client_options = rcl_client_get_default_options(); ret = rcl_client_init( &unmatched_client, this->node_ptr, ts, unmatched_client_name, &unmatched_client_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto unmatched_client_exit = make_scope_exit( - [&unmatched_client, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_client_fini(&unmatched_client, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_client_fini(&unmatched_client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); bool is_available = false; for (auto i = 0; i < timeout; ++i) { @@ -121,12 +102,10 @@ TEST_F(TestNamespaceFixture, test_client_server) { ret = rcl_client_init( &matched_client, this->node_ptr, ts, matched_client_name, &matched_client_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - auto matched_client_exit = make_scope_exit( - [&matched_client, this]() { - stop_memory_checking(); - rcl_ret_t ret = rcl_client_fini(&matched_client, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); - }); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_ret_t ret = rcl_client_fini(&matched_client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + }); is_available = false; for (auto i = 0; i < timeout; ++i) { From 99cb41bf1719d60010d0d964d864f5875953bce0 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 21 May 2018 21:59:56 -0700 Subject: [PATCH 03/10] fixup new test --- rcl/test/CMakeLists.txt | 1 + rcl/test/rcl/test_lexer_lookahead.cpp | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 5be75966c..f555ab1f1 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -78,6 +78,7 @@ function(test_target_function) rcl_add_custom_gtest(test_lexer_lookahead${target_suffix} SRCS rcl/test_lexer_lookahead.cpp + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} ENV ${extra_test_env} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} diff --git a/rcl/test/rcl/test_lexer_lookahead.cpp b/rcl/test/rcl/test_lexer_lookahead.cpp index 54d0f285b..53c094d6e 100644 --- a/rcl/test/rcl/test_lexer_lookahead.cpp +++ b/rcl/test/rcl/test_lexer_lookahead.cpp @@ -16,7 +16,7 @@ #include -#include "../scope_exit.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #include "rcl/lexer_lookahead.h" @@ -46,7 +46,7 @@ class CLASSNAME (TestLexerLookaheadFixture, RMW_IMPLEMENTATION) : public ::testi rcl_ret_t ret = rcl_lexer_lookahead2_init(&name, text, rcl_get_default_allocator()); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ } \ - auto __scope_lookahead2_ ## name = make_scope_exit( \ + auto __scope_lookahead2_ ## name = osrf_testing_tools_cpp::make_scope_exit( \ [&name]() { \ rcl_ret_t ret = rcl_lexer_lookahead2_fini(&buffer); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ From 5e410703acba139bcaaa465bb9b75417d883a089 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 22 May 2018 03:16:37 -0700 Subject: [PATCH 04/10] fix lambda captures for Windows --- rcl/test/rcl/test_wait.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/rcl/test/rcl/test_wait.cpp b/rcl/test/rcl/test_wait.cpp index 7458696d8..390212034 100644 --- a/rcl/test/rcl/test_wait.cpp +++ b/rcl/test/rcl/test_wait.cpp @@ -263,9 +263,9 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade std::vector test_sets(number_of_threads); // Setup common function for waiting on the triggered guard conditions. auto wait_func_factory = - [](TestSet & test_set) { + [=](TestSet & test_set) { return - [&test_set]() { + [=, &test_set]() { while (test_set.wake_count < count_target) { bool change_detected = false; size_t wake_try_count = 0; @@ -341,7 +341,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade } // Loop, triggering every trigger_period until the threads are done. auto loop_test = - [&test_sets]() -> bool { + [=, &test_sets]() -> bool { for (const auto & test_set : test_sets) { if (test_set.wake_count.load() < count_target) { return true; From 9e44bd3ef883418241ffc092fe05e0edfcc0bcb2 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 22 May 2018 17:30:31 -0700 Subject: [PATCH 05/10] uncrustify fix --- rcl/test/rcl/test_wait.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/rcl/test/rcl/test_wait.cpp b/rcl/test/rcl/test_wait.cpp index 390212034..be2036ab7 100644 --- a/rcl/test/rcl/test_wait.cpp +++ b/rcl/test/rcl/test_wait.cpp @@ -261,6 +261,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade size_t thread_id; }; std::vector test_sets(number_of_threads); + // *INDENT-OFF* (prevent uncrustify from making unnecessary whitespace around [=]) // Setup common function for waiting on the triggered guard conditions. auto wait_func_factory = [=](TestSet & test_set) { @@ -305,6 +306,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade } }; }; + // *INDENT-ON* // Setup each test set. for (auto & test_set : test_sets) { rcl_ret_t ret; @@ -340,6 +342,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade test_set.thread = std::thread(wait_func_factory(test_set)); } // Loop, triggering every trigger_period until the threads are done. + // *INDENT-OFF* (prevent uncrustify from making unnecessary whitespace around [=]) auto loop_test = [=, &test_sets]() -> bool { for (const auto & test_set : test_sets) { @@ -349,6 +352,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade } return false; }; + // *INDENT-ON* size_t loop_count = 0; while (loop_test()) { loop_count++; From 076f4b3989daac88aa6a33b589da77099fb9d8c6 Mon Sep 17 00:00:00 2001 From: dhood Date: Fri, 8 Jun 2018 17:55:42 -0700 Subject: [PATCH 06/10] extra_test_env -> rmw_implementation_env_var --- rcl/test/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index f555ab1f1..da9149aca 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -70,7 +70,7 @@ function(test_target_function) rcl_add_custom_gtest(test_lexer${target_suffix} SRCS rcl/test_lexer.cpp - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} AMENT_DEPENDENCIES ${rmw_implementation} @@ -79,7 +79,7 @@ function(test_target_function) rcl_add_custom_gtest(test_lexer_lookahead${target_suffix} SRCS rcl/test_lexer_lookahead.cpp INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} - ENV ${extra_test_env} + ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} AMENT_DEPENDENCIES ${rmw_implementation} From 68d4f15cf43035f00d56eb158a7a442909290b6d Mon Sep 17 00:00:00 2001 From: dhood Date: Fri, 8 Jun 2018 17:57:03 -0700 Subject: [PATCH 07/10] Stray extra_test_libraries --- rcl/test/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index da9149aca..1c181792d 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -72,7 +72,7 @@ function(test_target_function) SRCS rcl/test_lexer.cpp ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} ) @@ -81,7 +81,7 @@ function(test_target_function) INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} ${extra_test_libraries} + LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES ${rmw_implementation} ) From 42f1afcfea1ef47312cf48d63d9ca8781df868c5 Mon Sep 17 00:00:00 2001 From: dhood Date: Fri, 8 Jun 2018 17:57:57 -0700 Subject: [PATCH 08/10] Use default rmw impl outside of for_each_rmw_implementation loop --- rcl/test/CMakeLists.txt | 3 --- 1 file changed, 3 deletions(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 1c181792d..1e8fd0968 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -263,14 +263,12 @@ call_for_each_rmw_implementation(test_target) rcl_add_custom_gtest(test_validate_topic_name SRCS rcl/test_validate_topic_name.cpp - ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} ) rcl_add_custom_gtest(test_expand_topic_name SRCS rcl/test_expand_topic_name.cpp - ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} ) @@ -278,7 +276,6 @@ rcl_add_custom_gtest(test_expand_topic_name rcl_add_custom_gtest(test_timer${target_suffix} SRCS rcl/test_timer.cpp INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} - ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} ) From 89ddfd784989fa8cb013956e7e2bc23c2ac5bc7a Mon Sep 17 00:00:00 2001 From: William Woodall Date: Mon, 11 Jun 2018 15:43:21 -0700 Subject: [PATCH 09/10] style fixup --- rcl/test/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 1e8fd0968..6c84511d6 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -9,7 +9,7 @@ find_package(rmw_implementation_cmake REQUIRED) find_package(osrf_testing_tools_cpp REQUIRED) get_target_property(memory_tools_ld_preload_env_var - osrf_testing_tools_cpp::memory_tools LIBRARY_PRELOAD_ENVIRONMENT_VARIABLE) + osrf_testing_tools_cpp::memory_tools LIBRARY_PRELOAD_ENVIRONMENT_VARIABLE) include(cmake/rcl_add_custom_executable.cmake) include(cmake/rcl_add_custom_gtest.cmake) From 6f8b92495255f1873a7fa5fc4fd2c880fcd53a89 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 12 Jun 2018 00:11:00 -0700 Subject: [PATCH 10/10] fix typo --- rcl/test/rcl/test_wait.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/test/rcl/test_wait.cpp b/rcl/test/rcl/test_wait.cpp index be2036ab7..b09431878 100644 --- a/rcl/test/rcl/test_wait.cpp +++ b/rcl/test/rcl/test_wait.cpp @@ -149,7 +149,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) { EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); }); -// Time spent during wait should be negligible. + // Time spent during wait should be negligible. int64_t timeout = 0; std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); ret = rcl_wait(&wait_set, timeout);