diff --git a/rcl/CMakeLists.txt b/rcl/CMakeLists.txt index 4a7d20c..c60faf3 100644 --- a/rcl/CMakeLists.txt +++ b/rcl/CMakeLists.txt @@ -41,7 +41,7 @@ if(AMENT_ENABLE_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() - set(extra_test_libraries ) + set(extra_test_libraries) ament_find_gtest() # For GTEST_LIBRARIES if(APPLE) add_library(${PROJECT_NAME}_memory_tools_interpose SHARED test/memory_tools_osx_interpose.cpp) diff --git a/rcl/include/rcl/allocator.h b/rcl/include/rcl/allocator.h index b47313f..0e1b2d6 100644 --- a/rcl/include/rcl/allocator.h +++ b/rcl/include/rcl/allocator.h @@ -24,12 +24,13 @@ extern "C" /// Encapsulation of an allocator. /* To use malloc, free, and realloc use rcl_get_default_allocator */ -typedef struct rcl_allocator_t { +typedef struct rcl_allocator_t +{ /// Allocate memory, given a size and state structure. /* An error should be indicated by returning null. */ void * (*allocate)(size_t size, void * state); /// Deallocate previously allocated memory, mimicking free(). - void (*deallocate)(void * pointer, void * state); + void (* deallocate)(void * pointer, void * state); /// Reallocates if possible, otherwise it deallocates and allocates. /* If unsupported then do deallocate and then allocate. * This should behave as realloc is described, as opposed to reallocf, i.e. diff --git a/rcl/include/rcl/guard_condition.h b/rcl/include/rcl/guard_condition.h index 2f150ac..de46b93 100644 --- a/rcl/include/rcl/guard_condition.h +++ b/rcl/include/rcl/guard_condition.h @@ -26,12 +26,14 @@ extern "C" struct rcl_guard_condition_impl_t; /// Handle for a rcl guard condition. -typedef struct rcl_guard_condition_t { +typedef struct rcl_guard_condition_t +{ struct rcl_guard_condition_impl_t * impl; } rcl_guard_condition_t; /// Options available for a rcl guard condition. -typedef struct rcl_guard_condition_options_t { +typedef struct rcl_guard_condition_options_t +{ /// Custom allocator for the guard condition, used for incidental allocations. /* For default behavior (malloc/free), use: rcl_get_default_allocator() */ rcl_allocator_t allocator; diff --git a/rcl/include/rcl/node.h b/rcl/include/rcl/node.h index 02ab38e..78a1fe9 100644 --- a/rcl/include/rcl/node.h +++ b/rcl/include/rcl/node.h @@ -29,12 +29,14 @@ extern "C" struct rcl_node_impl_t; /// Handle for a ROS node. -typedef struct rcl_node_t { +typedef struct rcl_node_t +{ /// Private implementation pointer. struct rcl_node_impl_t * impl; } rcl_node_t; -typedef struct rcl_node_options_t { +typedef struct rcl_node_options_t +{ // bool anonymous_name; // rmw_qos_profile_t parameter_qos; /// If true, no parameter infrastructure will be setup. diff --git a/rcl/include/rcl/publisher.h b/rcl/include/rcl/publisher.h index 6f20616..bf57d1b 100644 --- a/rcl/include/rcl/publisher.h +++ b/rcl/include/rcl/publisher.h @@ -28,12 +28,14 @@ extern "C" struct rcl_publisher_impl_t; /// Handle for a rcl publisher. -typedef struct rcl_publisher_t { +typedef struct rcl_publisher_t +{ struct rcl_publisher_impl_t * impl; } rcl_publisher_t; /// Options available for a rcl publisher. -typedef struct rcl_publisher_options_t { +typedef struct rcl_publisher_options_t +{ /// Middleware quality of service settings for the publisher. rmw_qos_profile_t qos; /// Custom allocator for the publisher, used for incidental allocations. diff --git a/rcl/include/rcl/subscription.h b/rcl/include/rcl/subscription.h index 0b212d2..8d6e6f7 100644 --- a/rcl/include/rcl/subscription.h +++ b/rcl/include/rcl/subscription.h @@ -28,12 +28,14 @@ extern "C" struct rcl_subscription_impl_t; /// Handle for a rcl subscription. -typedef struct rcl_subscription_t { +typedef struct rcl_subscription_t +{ struct rcl_subscription_impl_t * impl; } rcl_subscription_t; /// Options available for a rcl subscription. -typedef struct rcl_subscription_options_t { +typedef struct rcl_subscription_options_t +{ /// Middleware quality of service settings for the subscription. rmw_qos_profile_t qos; /// If true, messages published from within the same node are ignored. diff --git a/rcl/include/rcl/time.h b/rcl/include/rcl/time.h index fddbce4..b12f508 100644 --- a/rcl/include/rcl/time.h +++ b/rcl/include/rcl/time.h @@ -42,7 +42,8 @@ extern "C" * The struct is capable of representing any time until the year 2554 with * nanosecond precisions. */ -typedef struct rcl_system_time_point_t { +typedef struct rcl_system_time_point_t +{ uint64_t nanoseconds; } rcl_system_time_point_t; @@ -56,7 +57,8 @@ typedef struct rcl_system_time_point_t { * * The struct represents time as nanoseconds in an unsigned 64-bit integer. */ -typedef struct rcl_steady_time_point_t { +typedef struct rcl_steady_time_point_t +{ uint64_t nanoseconds; } rcl_steady_time_point_t; @@ -64,7 +66,8 @@ typedef struct rcl_steady_time_point_t { /* The struct can represent any time within the range [~292 years, ~-292 years] * with nanosecond precision. */ -typedef struct rcl_duration_t { +typedef struct rcl_duration_t +{ int64_t nanoseconds; } rcl_duration_t; diff --git a/rcl/include/rcl/timer.h b/rcl/include/rcl/timer.h index ca921e4..2298741 100644 --- a/rcl/include/rcl/timer.h +++ b/rcl/include/rcl/timer.h @@ -30,7 +30,8 @@ extern "C" struct rcl_timer_impl_t; /// Handle for a ROS timer. -typedef struct rcl_timer_t { +typedef struct rcl_timer_t +{ /// Private implementation pointer. struct rcl_timer_impl_t * impl; } rcl_timer_t; diff --git a/rcl/include/rcl/wait.h b/rcl/include/rcl/wait.h index eb75555..55e926b 100644 --- a/rcl/include/rcl/wait.h +++ b/rcl/include/rcl/wait.h @@ -31,7 +31,8 @@ extern "C" struct rcl_wait_set_impl_t; /// Container for subscription's, guard condition's, etc to be waited on. -typedef struct rcl_wait_set_t { +typedef struct rcl_wait_set_t +{ /// Storage for subscription pointers. const rcl_subscription_t ** subscriptions; size_t size_of_subscriptions; diff --git a/rcl/src/rcl/common.h b/rcl/src/rcl/common.h index 379611f..03bf242 100644 --- a/rcl/src/rcl/common.h +++ b/rcl/src/rcl/common.h @@ -27,8 +27,8 @@ extern "C" RCL_CHECK_FOR_NULL_WITH_MSG(argument, #argument " argument is null", return error_return_type) #define RCL_CHECK_FOR_NULL_WITH_MSG(value, msg, error_statement) if (!value) { \ - RCL_SET_ERROR_MSG(msg); \ - error_statement; \ + RCL_SET_ERROR_MSG(msg); \ + error_statement; \ } // This value put in env_value is only valid until the next call to rcl_impl_getenv (on Windows). diff --git a/rcl/src/rcl/guard_condition.c b/rcl/src/rcl/guard_condition.c index 595c58f..f081d61 100644 --- a/rcl/src/rcl/guard_condition.c +++ b/rcl/src/rcl/guard_condition.c @@ -23,7 +23,8 @@ extern "C" #include "rcl/rcl.h" #include "rmw/rmw.h" -typedef struct rcl_guard_condition_impl_t { +typedef struct rcl_guard_condition_impl_t +{ rmw_guard_condition_t * rmw_handle; rcl_guard_condition_options_t options; } rcl_guard_condition_impl_t; diff --git a/rcl/src/rcl/node.c b/rcl/src/rcl/node.c index d6e94b3..57dab8e 100644 --- a/rcl/src/rcl/node.c +++ b/rcl/src/rcl/node.c @@ -28,7 +28,8 @@ extern "C" #include "./common.h" -typedef struct rcl_node_impl_t { +typedef struct rcl_node_impl_t +{ rcl_node_options_t options; rmw_node_t * rmw_node_handle; uint64_t rcl_instance_id; @@ -80,7 +81,7 @@ rcl_node_init(rcl_node_t * node, const char * name, const rcl_node_options_t * o goto fail; } if (ros_domain_id) { - unsigned long number = strtoul(ros_domain_id, NULL, 0); + unsigned long number = strtoul(ros_domain_id, NULL, 0); // NOLINT(runtime/int) if (number == ULONG_MAX) { RCL_SET_ERROR_MSG("failed to interpret ROS_DOMAIN_ID as integral number"); goto fail; diff --git a/rcl/src/rcl/publisher.c b/rcl/src/rcl/publisher.c index c7dc189..d0c2a67 100644 --- a/rcl/src/rcl/publisher.c +++ b/rcl/src/rcl/publisher.c @@ -24,7 +24,8 @@ extern "C" #include "./common.h" #include "rmw/rmw.h" -typedef struct rcl_publisher_impl_t { +typedef struct rcl_publisher_impl_t +{ rcl_publisher_options_t options; rmw_publisher_t * rmw_handle; } rcl_publisher_impl_t; diff --git a/rcl/src/rcl/rcl.c b/rcl/src/rcl/rcl.c index 537b975..53d4b25 100644 --- a/rcl/src/rcl/rcl.c +++ b/rcl/src/rcl/rcl.c @@ -65,7 +65,7 @@ rcl_init(int argc, char ** argv, rcl_allocator_t allocator) memset(__rcl_argv, 0, sizeof(char **) * argc); for (size_t i = 0; i < argc; ++i) { __rcl_argv[i] = (char *)__rcl_allocator.allocate(strlen(argv[i]), __rcl_allocator.state); - strcpy(__rcl_argv[i], argv[i]); + strcpy(__rcl_argv[i], argv[i]); // NOLINT(runtime/printf) } atomic_store(&__rcl_instance_id, ++__rcl_next_unique_id); if (atomic_load(&__rcl_instance_id) == 0) { diff --git a/rcl/src/rcl/subscription.c b/rcl/src/rcl/subscription.c index 6e8b3a0..57a6b8c 100644 --- a/rcl/src/rcl/subscription.c +++ b/rcl/src/rcl/subscription.c @@ -22,7 +22,8 @@ extern "C" #include "rmw/rmw.h" #include "./common.h" -typedef struct rcl_subscription_impl_t { +typedef struct rcl_subscription_impl_t +{ rcl_subscription_options_t options; rmw_subscription_t * rmw_handle; } rcl_subscription_impl_t; diff --git a/rcl/src/rcl/time_win32.c b/rcl/src/rcl/time_win32.c index dcc8c20..b57a552 100644 --- a/rcl/src/rcl/time_win32.c +++ b/rcl/src/rcl/time_win32.c @@ -155,7 +155,7 @@ rcl_system_time_point_now(rcl_system_time_point_t * now) #else start_li.QuadPart -= 116444736000000000ULL; #endif - start.sec = (uint64_t)(start_li.QuadPart / 10000000); // 100-ns units. odd. + start.sec = (uint64_t)(start_li.QuadPart / 10000000); // 100-ns units. odd. start.nsec = (start_li.LowPart % 10000000) * 100; if (atomic_compare_exchange_strong(&start_ns, 0, RCL_S_TO_NS(start.sec) + start.nsec)) { // If it matched 0 this call was first to setup, set the cpu_freq and init_cpu_time globals. diff --git a/rcl/src/rcl/timer.c b/rcl/src/rcl/timer.c index cea2edb..a8c74fa 100644 --- a/rcl/src/rcl/timer.c +++ b/rcl/src/rcl/timer.c @@ -23,7 +23,8 @@ extern "C" #include "./common.h" -typedef struct rcl_timer_impl_t { +typedef struct rcl_timer_impl_t +{ // The user supplied callback. atomic_uintptr_t callback; // This is a duration in nanoseconds. diff --git a/rcl/src/rcl/wait.c b/rcl/src/rcl/wait.c index d7aff5e..25d4807 100644 --- a/rcl/src/rcl/wait.c +++ b/rcl/src/rcl/wait.c @@ -29,7 +29,8 @@ extern "C" #include "rmw/rmw.h" #include "./common.h" -typedef struct rcl_wait_set_impl_t { +typedef struct rcl_wait_set_impl_t +{ size_t subscription_index; rmw_subscriptions_t rmw_subscriptions; size_t guard_condition_index; @@ -173,16 +174,16 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al RCL_SET_ERROR_MSG("wait set is invalid"); \ return RCL_RET_WAIT_SET_INVALID; \ } \ - if (!(wait_set->impl->Type##_index < wait_set->size_of_##Type##s)) { \ + if (!(wait_set->impl->Type ## _index < wait_set->size_of_ ## Type ## s)) { \ RCL_SET_ERROR_MSG(#Type "s set is full"); \ return RCL_RET_WAIT_SET_FULL; \ } \ - size_t current_index = wait_set->impl->Type##_index++; \ - wait_set->Type##s[current_index] = Type; + size_t current_index = wait_set->impl->Type ## _index++; \ + wait_set->Type ## s[current_index] = Type; #define SET_ADD_RMW(Type, RMWStorage) \ /* Also place into rmw storage. */ \ - rmw_##Type##_t * rmw_handle = rcl_##Type##_get_rmw_##Type##_handle(Type); \ + rmw_ ## Type ## _t * rmw_handle = rcl_ ## Type ## _get_rmw_ ## Type ## _handle(Type); \ RCL_CHECK_FOR_NULL_WITH_MSG( \ rmw_handle, rcl_get_error_string_safe(), return RCL_RET_ERROR); \ wait_set->impl->RMWStorage[current_index] = rmw_handle->data; @@ -193,8 +194,8 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al RCL_SET_ERROR_MSG("wait set is invalid"); \ return RCL_RET_WAIT_SET_INVALID; \ } \ - memset(wait_set->Type##s, 0, sizeof(rcl_##Type##_t *) * wait_set->size_of_##Type##s); \ - wait_set->impl->Type##_index = 0; \ + memset(wait_set->Type ## s, 0, sizeof(rcl_ ## Type ## _t *) * wait_set->size_of_ ## Type ## s); \ + wait_set->impl->Type ## _index = 0; \ #define SET_CLEAR_RMW(Type, RMWStorage, RMWCount) \ /* Also clear the rmw storage. */ \ @@ -207,43 +208,42 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT); \ RCL_CHECK_FOR_NULL_WITH_MSG( \ wait_set->impl, "wait set is invalid", return RCL_RET_WAIT_SET_INVALID); \ - if (size == wait_set->size_of_##Type##s) { \ + if (size == wait_set->size_of_ ## Type ## s) { \ return RCL_RET_OK; \ } \ rcl_allocator_t allocator = wait_set->impl->allocator; \ if (size == 0) { \ - if (wait_set->Type##s) { \ - allocator.deallocate(wait_set->Type##s, allocator.state); \ - wait_set->Type##s = NULL; \ + if (wait_set->Type ## s) { \ + allocator.deallocate(wait_set->Type ## s, allocator.state); \ + wait_set->Type ## s = NULL; \ } \ ExtraDealloc \ - } \ - else { \ - wait_set->size_of_##Type##s = 0; \ - wait_set->Type##s = (const rcl_##Type##_t **)allocator.reallocate( \ - wait_set->Type##s, sizeof(rcl_##Type##_t *) * size, allocator.state); \ + } else { \ + wait_set->size_of_ ## Type ## s = 0; \ + wait_set->Type ## s = (const rcl_ ## Type ## _t * *)allocator.reallocate( \ + wait_set->Type ## s, sizeof(rcl_ ## Type ## _t *) * size, allocator.state); \ RCL_CHECK_FOR_NULL_WITH_MSG( \ - wait_set->Type##s, "allocating memory failed", return RCL_RET_BAD_ALLOC); \ - wait_set->size_of_##Type##s = size; \ + wait_set->Type ## s, "allocating memory failed", return RCL_RET_BAD_ALLOC); \ + wait_set->size_of_ ## Type ## s = size; \ ExtraRealloc \ } \ return RCL_RET_OK; #define SET_RESIZE_RMW_DEALLOC(RMWStorage, RMWCount) \ /* Also deallocate the rmw storage. */ \ - if (wait_set->impl->RMWStorage) { \ - allocator.deallocate(wait_set->impl->RMWStorage, allocator.state); \ - wait_set->impl->RMWStorage = NULL; \ - } + if (wait_set->impl->RMWStorage) { \ + allocator.deallocate(wait_set->impl->RMWStorage, allocator.state); \ + wait_set->impl->RMWStorage = NULL; \ + } #define SET_RESIZE_RMW_REALLOC(Type, RMWStorage, RMWCount) \ /* Also resize the rmw storage. */ \ wait_set->impl->RMWCount = 0; \ wait_set->impl->RMWStorage = (void **)allocator.reallocate( \ - wait_set->impl->RMWStorage, sizeof(rcl_##Type##_t *) * size, allocator.state); \ + wait_set->impl->RMWStorage, sizeof(rcl_ ## Type ## _t *) * size, allocator.state); \ if (!wait_set->impl->RMWStorage) { \ - allocator.deallocate(wait_set->Type##s, allocator.state); \ - wait_set->size_of_##Type##s = 0; \ + allocator.deallocate(wait_set->Type ## s, allocator.state); \ + wait_set->size_of_ ## Type ## s = 0; \ RCL_SET_ERROR_MSG("allocating memory failed"); \ return RCL_RET_BAD_ALLOC; \ } \ @@ -336,7 +336,7 @@ rcl_wait_set_clear_timers(rcl_wait_set_t * wait_set) rcl_ret_t rcl_wait_set_resize_timers(rcl_wait_set_t * wait_set, size_t size) { - SET_RESIZE(timer, ;, ;) + SET_RESIZE(timer,;,;) // NOLINT } rcl_ret_t @@ -397,8 +397,7 @@ rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout) &wait_set->impl->rmw_guard_conditions, &dummy_services, &dummy_clients, - timeout_argument - ); + timeout_argument); // Check for error. if (ret != RMW_RET_OK) { RCL_SET_ERROR_MSG(rmw_get_error_string_safe()); diff --git a/rcl/test/memory_tools.hpp b/rcl/test/memory_tools.hpp index ac20a65..f220baf 100644 --- a/rcl/test/memory_tools.hpp +++ b/rcl/test/memory_tools.hpp @@ -16,29 +16,32 @@ // https://dxr.mozilla.org/mozilla-central/rev/ // cc9c6cd756cb744596ba039dcc5ad3065a7cc3ea/memory/build/replace_malloc.c -#ifndef TEST__MEMORY_TOOLS_HPP_ -#define TEST__MEMORY_TOOLS_HPP_ +#ifndef MEMORY_TOOLS_HPP_ +#define MEMORY_TOOLS_HPP_ #include - -#include #include -typedef std::function UnexpectedCallbackType; +#include + +typedef std::function UnexpectedCallbackType; void start_memory_checking(); -#define ASSERT_NO_MALLOC(statements) assert_no_malloc_begin(); statements; assert_no_malloc_end(); +#define ASSERT_NO_MALLOC(statements) \ + assert_no_malloc_begin(); statements; assert_no_malloc_end(); void assert_no_malloc_begin(); void assert_no_malloc_end(); void set_on_unepexcted_malloc_callback(UnexpectedCallbackType callback); -#define ASSERT_NO_REALLOC(statements) assert_no_realloc_begin(); statements; assert_no_realloc_end(); +#define ASSERT_NO_REALLOC(statements) \ + assert_no_realloc_begin(); statements; assert_no_realloc_end(); void assert_no_realloc_begin(); void assert_no_realloc_end(); void set_on_unepexcted_realloc_callback(UnexpectedCallbackType callback); -#define ASSERT_NO_FREE(statements) assert_no_free_begin(); statements; assert_no_free_end(); +#define ASSERT_NO_FREE(statements) \ + assert_no_free_begin(); statements; assert_no_free_end(); void assert_no_free_begin(); void assert_no_free_end(); void set_on_unepexcted_free_callback(UnexpectedCallbackType callback); @@ -47,4 +50,4 @@ void stop_memory_checking(); void memory_checking_thread_init(); -#endif // TEST__MEMORY_TOOLS_HPP_ +#endif // MEMORY_TOOLS_HPP_ diff --git a/rcl/test/memory_tools_common.cpp b/rcl/test/memory_tools_common.cpp index 731db36..18c3ef0 100644 --- a/rcl/test/memory_tools_common.cpp +++ b/rcl/test/memory_tools_common.cpp @@ -39,7 +39,8 @@ void set_on_unepexcted_malloc_callback(UnexpectedCallbackType callback) return; } if (!unexpected_malloc_callback) { - unexpected_malloc_callback = (UnexpectedCallbackType *)malloc(sizeof(UnexpectedCallbackType)); + unexpected_malloc_callback = + reinterpret_cast(malloc(sizeof(UnexpectedCallbackType))); if (!unexpected_malloc_callback) { throw std::bad_alloc(); } @@ -51,7 +52,7 @@ void set_on_unepexcted_malloc_callback(UnexpectedCallbackType callback) void * custom_malloc(size_t size) { - if (!enabled.load()) return malloc(size); + if (!enabled.load()) {return malloc(size);} auto foo = SCOPE_EXIT(enabled.store(true);); enabled.store(false); if (!malloc_expected) { @@ -78,7 +79,8 @@ void set_on_unepexcted_realloc_callback(UnexpectedCallbackType callback) return; } if (!unexpected_realloc_callback) { - unexpected_realloc_callback = (UnexpectedCallbackType *)malloc(sizeof(UnexpectedCallbackType)); + unexpected_realloc_callback = + reinterpret_cast(malloc(sizeof(UnexpectedCallbackType))); if (!unexpected_realloc_callback) { throw std::bad_alloc(); } @@ -90,7 +92,7 @@ void set_on_unepexcted_realloc_callback(UnexpectedCallbackType callback) void * custom_realloc(void * memory_in, size_t size) { - if (!enabled.load()) return realloc(memory_in, size); + if (!enabled.load()) {return realloc(memory_in, size);} auto foo = SCOPE_EXIT(enabled.store(true);); enabled.store(false); if (!realloc_expected) { @@ -118,7 +120,8 @@ void set_on_unepexcted_free_callback(UnexpectedCallbackType callback) return; } if (!unexpected_free_callback) { - unexpected_free_callback = (UnexpectedCallbackType *)malloc(sizeof(UnexpectedCallbackType)); + unexpected_free_callback = + reinterpret_cast(malloc(sizeof(UnexpectedCallbackType))); if (!unexpected_free_callback) { throw std::bad_alloc(); } @@ -130,7 +133,7 @@ void set_on_unepexcted_free_callback(UnexpectedCallbackType callback) void custom_free(void * memory) { - if (!enabled.load()) return free(memory); + if (!enabled.load()) {return free(memory);} auto foo = SCOPE_EXIT(enabled.store(true);); enabled.store(false); if (!free_expected) { diff --git a/rcl/test/memory_tools_osx_interpose.cpp b/rcl/test/memory_tools_osx_interpose.cpp index 980b005..91579cf 100644 --- a/rcl/test/memory_tools_osx_interpose.cpp +++ b/rcl/test/memory_tools_osx_interpose.cpp @@ -20,16 +20,17 @@ // used an interposition table like the following: // -typedef struct interpose_s { +typedef struct interpose_s +{ void * new_func; void * orig_func; } interpose_t; -#define OSX_INTERPOSE(newf,oldf) \ +#define OSX_INTERPOSE(newf, oldf) \ __attribute__((used)) static const interpose_t \ - macinterpose##newf##oldf __attribute__ ((section("__DATA, __interpose"))) = { \ - (void *)newf, \ - (void *)oldf, \ + macinterpose ## newf ## oldf __attribute__ ((section("__DATA, __interpose"))) = { \ + reinterpret_cast(newf), \ + reinterpret_cast(oldf), \ } // End Interpose. diff --git a/rcl/test/rcl/test_allocator.cpp b/rcl/test/rcl/test_allocator.cpp index f63ec18..0294267 100644 --- a/rcl/test/rcl/test_allocator.cpp +++ b/rcl/test/rcl/test_allocator.cpp @@ -18,7 +18,8 @@ #include "../memory_tools.hpp" -class TestAllocatorFixture : public ::testing::Test { +class TestAllocatorFixture : public::testing::Test +{ public: TestAllocatorFixture() { @@ -47,17 +48,22 @@ public: /* Tests the default allocator. */ -TEST_F(TestAllocatorFixture, test_default_allocator_normal) -{ +TEST_F(TestAllocatorFixture, test_default_allocator_normal) { ASSERT_NO_MALLOC( rcl_allocator_t allocator = rcl_get_default_allocator(); ) size_t mallocs = 0; size_t reallocs = 0; size_t frees = 0; - set_on_unepexcted_malloc_callback([&mallocs]() {mallocs++;}); - set_on_unepexcted_realloc_callback([&reallocs]() {reallocs++;}); - set_on_unepexcted_free_callback([&frees]() {frees++;}); + set_on_unepexcted_malloc_callback([&mallocs]() { + mallocs++; + }); + set_on_unepexcted_realloc_callback([&reallocs]() { + reallocs++; + }); + set_on_unepexcted_free_callback([&frees]() { + frees++; + }); assert_no_malloc_begin(); assert_no_realloc_begin(); assert_no_free_begin(); diff --git a/rcl/test/rcl/test_time.cpp b/rcl/test/rcl/test_time.cpp index 7c259bd..99851fe 100644 --- a/rcl/test/rcl/test_time.cpp +++ b/rcl/test/rcl/test_time.cpp @@ -21,7 +21,8 @@ #include "../memory_tools.hpp" -class TestTimeFixture : public ::testing::Test { +class TestTimeFixture : public::testing::Test +{ public: void SetUp() { @@ -45,8 +46,7 @@ public: /* Tests the rcl_system_time_point_now() function. */ -TEST_F(TestTimeFixture, test_rcl_system_time_point_now) -{ +TEST_F(TestTimeFixture, test_rcl_system_time_point_now) { assert_no_realloc_begin(); rcl_ret_t ret = RCL_RET_OK; // Check for invalid argument error condition (allowed to alloc). @@ -78,8 +78,7 @@ TEST_F(TestTimeFixture, test_rcl_system_time_point_now) /* Tests the rcl_steady_time_point_now() function. */ -TEST_F(TestTimeFixture, test_rcl_steady_time_point_now) -{ +TEST_F(TestTimeFixture, test_rcl_steady_time_point_now) { assert_no_realloc_begin(); rcl_ret_t ret = RCL_RET_OK; // Check for invalid argument error condition (allowed to alloc). diff --git a/rcl/test/scope_exit.hpp b/rcl/test/scope_exit.hpp index cb12fce..056e1fa 100644 --- a/rcl/test/scope_exit.hpp +++ b/rcl/test/scope_exit.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TEST__SCOPE_EXIT_HPP_ -#define TEST__SCOPE_EXIT_HPP_ +#ifndef SCOPE_EXIT_HPP_ +#define SCOPE_EXIT_HPP_ #include @@ -37,4 +37,4 @@ make_scope_exit(Callable callable) #define SCOPE_EXIT(code) make_scope_exit([&]() {code; }) -#endif // TEST__SCOPE_EXIT_HPP_ +#endif // SCOPE_EXIT_HPP_ diff --git a/rcl/test/test_memory_tools.cpp b/rcl/test/test_memory_tools.cpp index 770991e..1714c4f 100644 --- a/rcl/test/test_memory_tools.cpp +++ b/rcl/test/test_memory_tools.cpp @@ -18,16 +18,21 @@ /* Tests the allocatation checking tools. */ -TEST(TestMemoryTools, test_allocation_checking_tools) -{ +TEST(TestMemoryTools, test_allocation_checking_tools) { size_t unexpected_mallocs = 0; - auto on_unexpected_malloc = [&unexpected_mallocs]() {unexpected_mallocs++;}; + auto on_unexpected_malloc = ([&unexpected_mallocs]() { + unexpected_mallocs++; + }); set_on_unepexcted_malloc_callback(on_unexpected_malloc); size_t unexpected_reallocs = 0; - auto on_unexpected_realloc = [&unexpected_reallocs]() {unexpected_reallocs++;}; + auto on_unexpected_realloc = ([&unexpected_reallocs]() { + unexpected_reallocs++; + }); set_on_unepexcted_realloc_callback(on_unexpected_realloc); size_t unexpected_frees = 0; - auto on_unexpected_free = [&unexpected_frees]() {unexpected_frees++;}; + auto on_unexpected_free = ([&unexpected_frees]() { + unexpected_frees++; + }); set_on_unepexcted_free_callback(on_unexpected_free); void * mem = nullptr; // First try before enabling, should have no effect.