diff --git a/rosidl_runtime_c/src/primitives_sequence_functions.c b/rosidl_runtime_c/src/primitives_sequence_functions.c index 5884c8e69..11c7fd02a 100644 --- a/rosidl_runtime_c/src/primitives_sequence_functions.c +++ b/rosidl_runtime_c/src/primitives_sequence_functions.c @@ -16,6 +16,8 @@ #include #include +#include + #include "rosidl_runtime_c/primitives_sequence_functions.h" #define ROSIDL_GENERATOR_C__DEFINE_PRIMITIVE_SEQUENCE_FUNCTIONS(STRUCT_NAME, TYPE_NAME) \ @@ -27,7 +29,8 @@ } \ TYPE_NAME * data = NULL; \ if (size) { \ - data = malloc(sizeof(TYPE_NAME) * size); \ + rcutils_allocator_t allocator = rcutils_get_default_allocator(); \ + data = allocator.allocate(sizeof(TYPE_NAME) * size, allocator.state); \ if (!data) { \ return false; \ } \ @@ -47,7 +50,8 @@ if (sequence->data) { \ /* ensure that data and capacity values are consistent */ \ assert(sequence->capacity > 0); \ - free(sequence->data); \ + rcutils_allocator_t allocator = rcutils_get_default_allocator(); \ + allocator.deallocate(sequence->data, allocator.state); \ sequence->data = NULL; \ sequence->size = 0; \ sequence->capacity = 0; \ diff --git a/rosidl_runtime_c/src/string_functions.c b/rosidl_runtime_c/src/string_functions.c index 2e4ef3464..9f47cefa5 100644 --- a/rosidl_runtime_c/src/string_functions.c +++ b/rosidl_runtime_c/src/string_functions.c @@ -19,6 +19,7 @@ #include #include +#include #include "rcutils/macros.h" bool @@ -29,7 +30,8 @@ rosidl_runtime_c__String__init(rosidl_runtime_c__String * str) if (!str) { return false; } - str->data = malloc(1); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + str->data = allocator.allocate(1, allocator.state); if (!str->data) { return false; } @@ -53,7 +55,8 @@ rosidl_runtime_c__String__fini(rosidl_runtime_c__String * str) "Exiting.\n"); exit(-1); } - free(str->data); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + allocator.deallocate(str->data, allocator.state); str->data = NULL; str->size = 0; str->capacity = 0; @@ -89,7 +92,8 @@ rosidl_runtime_c__String__assignn( if (n == SIZE_MAX) { return false; } - char * data = realloc(str->data, n + 1); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + char * data = allocator.reallocate(str->data, n + 1, allocator.state); if (!data) { return false; } @@ -124,7 +128,9 @@ rosidl_runtime_c__String__Sequence__init( } rosidl_runtime_c__String * data = NULL; if (size) { - data = (rosidl_runtime_c__String *)calloc(size, sizeof(rosidl_runtime_c__String)); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + data = (rosidl_runtime_c__String *)allocator.zero_allocate( + size, sizeof(rosidl_runtime_c__String), allocator.state); if (!data) { return false; } @@ -135,7 +141,7 @@ rosidl_runtime_c__String__Sequence__init( for (; i-- > 0; ) { rosidl_runtime_c__String__fini(&data[i]); } - free(data); + allocator.deallocate(data, allocator.state); return false; } } @@ -160,7 +166,8 @@ rosidl_runtime_c__String__Sequence__fini( for (size_t i = 0; i < sequence->capacity; ++i) { rosidl_runtime_c__String__fini(&sequence->data[i]); } - free(sequence->data); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + allocator.deallocate(sequence->data, allocator.state); sequence->data = NULL; sequence->size = 0; sequence->capacity = 0; @@ -174,14 +181,16 @@ rosidl_runtime_c__String__Sequence__fini( rosidl_runtime_c__String__Sequence * rosidl_runtime_c__String__Sequence__create(size_t size) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); rosidl_runtime_c__String__Sequence * sequence = - (rosidl_runtime_c__String__Sequence *)malloc(sizeof(rosidl_runtime_c__String__Sequence)); + (rosidl_runtime_c__String__Sequence *)allocator.allocate( + sizeof(rosidl_runtime_c__String__Sequence), allocator.state); if (!sequence) { return NULL; } bool success = rosidl_runtime_c__String__Sequence__init(sequence, size); if (!success) { - free(sequence); + allocator.deallocate(sequence, allocator.state); return NULL; } return sequence; @@ -194,5 +203,6 @@ rosidl_runtime_c__String__Sequence__destroy( if (sequence) { rosidl_runtime_c__String__Sequence__fini(sequence); } - free(sequence); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + allocator.deallocate(sequence, allocator.state); } diff --git a/rosidl_runtime_c/src/u16string_functions.c b/rosidl_runtime_c/src/u16string_functions.c index 9ae5e4faf..d55c42538 100644 --- a/rosidl_runtime_c/src/u16string_functions.c +++ b/rosidl_runtime_c/src/u16string_functions.c @@ -19,6 +19,7 @@ #include #include +#include #include "rcutils/macros.h" bool @@ -29,7 +30,8 @@ rosidl_runtime_c__U16String__init(rosidl_runtime_c__U16String * str) if (!str) { return false; } - str->data = malloc(sizeof(uint16_t)); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + str->data = allocator.allocate(sizeof(uint16_t), allocator.state); if (!str->data) { return false; } @@ -53,7 +55,8 @@ rosidl_runtime_c__U16String__fini(rosidl_runtime_c__U16String * str) "Exiting.\n"); exit(-1); } - free(str->data); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + allocator.deallocate(str->data, allocator.state); str->data = NULL; str->size = 0; str->capacity = 0; @@ -89,7 +92,8 @@ rosidl_runtime_c__U16String__assignn( if (n == SIZE_MAX) { return false; } - uint16_t * data = realloc(str->data, (n + 1) * sizeof(uint16_t)); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + uint16_t * data = allocator.reallocate(str->data, (n + 1) * sizeof(uint16_t), allocator.state); if (!data) { return false; } @@ -145,7 +149,8 @@ rosidl_runtime_c__U16String__resize( if (n > SIZE_MAX / sizeof(uint16_t) - 1) { return false; } - uint16_t * data = realloc(str->data, (n + 1) * sizeof(uint16_t)); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + uint16_t * data = allocator.reallocate(str->data, (n + 1) * sizeof(uint16_t), allocator.state); if (!data) { return false; } @@ -167,7 +172,9 @@ rosidl_runtime_c__U16String__Sequence__init( } rosidl_runtime_c__U16String * data = NULL; if (size) { - data = (rosidl_runtime_c__U16String *)malloc(size * sizeof(rosidl_runtime_c__U16String)); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + data = (rosidl_runtime_c__U16String *)allocator.allocate( + size * sizeof(rosidl_runtime_c__U16String), allocator.state); if (!data) { return false; } @@ -178,7 +185,7 @@ rosidl_runtime_c__U16String__Sequence__init( for (; i-- > 0; ) { rosidl_runtime_c__U16String__fini(&data[i]); } - free(data); + allocator.deallocate(data, allocator.state); return false; } } @@ -203,7 +210,8 @@ rosidl_runtime_c__U16String__Sequence__fini( for (size_t i = 0; i < sequence->capacity; ++i) { rosidl_runtime_c__U16String__fini(&sequence->data[i]); } - free(sequence->data); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + allocator.deallocate(sequence->data, allocator.state); sequence->data = NULL; sequence->size = 0; sequence->capacity = 0; @@ -217,15 +225,16 @@ rosidl_runtime_c__U16String__Sequence__fini( rosidl_runtime_c__U16String__Sequence * rosidl_runtime_c__U16String__Sequence__create(size_t size) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); rosidl_runtime_c__U16String__Sequence * sequence = - (rosidl_runtime_c__U16String__Sequence *)malloc( - sizeof(rosidl_runtime_c__U16String__Sequence)); + (rosidl_runtime_c__U16String__Sequence *)allocator.allocate( + sizeof(rosidl_runtime_c__U16String__Sequence), allocator.state); if (!sequence) { return NULL; } bool success = rosidl_runtime_c__U16String__Sequence__init(sequence, size); if (!success) { - free(sequence); + allocator.deallocate(sequence, allocator.state); return NULL; } return sequence; @@ -238,5 +247,6 @@ rosidl_runtime_c__U16String__Sequence__destroy( if (sequence) { rosidl_runtime_c__U16String__Sequence__fini(sequence); } - free(sequence); + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + allocator.deallocate(sequence, allocator.state); }