Skip to content

Commit c48741a

Browse files
committed
Replace rcutils_allocator with the system allocator
Signed-off-by: Nikolai Morin <[email protected]>
1 parent d5d0b1a commit c48741a

File tree

4 files changed

+8
-15
lines changed

4 files changed

+8
-15
lines changed

rosidl_generator_c/resource/msg__functions.c.em

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -456,10 +456,8 @@ bool
456456
if (output->capacity < input->size) {
457457
const size_t allocation_size =
458458
input->size * sizeof(@(message_typename));
459-
rcutils_allocator_t allocator = rcutils_get_default_allocator();
460459
@(message_typename) * data =
461-
(@(message_typename) *)allocator.reallocate(
462-
output->data, allocation_size, allocator.state);
460+
(@(message_typename) *)realloc(output->data, allocation_size);
463461
if (!data) {
464462
return false;
465463
}
@@ -469,7 +467,7 @@ bool
469467
for (; i-- > output->capacity; ) {
470468
@(message_typename)__fini(&data[i]);
471469
}
472-
allocator.deallocate(data, allocator.state);
470+
free(data);
473471
return false;
474472
}
475473
}

rosidl_runtime_c/src/primitives_sequence_functions.c

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -85,9 +85,8 @@
8585
return false; \
8686
} \
8787
if (output->capacity < input->size) { \
88-
rcutils_allocator_t allocator = rcutils_get_default_allocator(); \
89-
TYPE_NAME * data = (TYPE_NAME *)allocator.reallocate( \
90-
output->data, sizeof(TYPE_NAME) * input->size, allocator.state); \
88+
TYPE_NAME * data = (TYPE_NAME *)realloc( \
89+
output->data, sizeof(TYPE_NAME) * input->size); \
9190
if (!data) { \
9291
return false; \
9392
} \

rosidl_runtime_c/src/string_functions.c

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -229,10 +229,8 @@ rosidl_runtime_c__String__Sequence__copy(
229229
if (output->capacity < input->size) {
230230
const size_t allocation_size =
231231
input->size * sizeof(rosidl_runtime_c__String);
232-
rcutils_allocator_t allocator = rcutils_get_default_allocator();
233232
rosidl_runtime_c__String * data =
234-
(rosidl_runtime_c__String *)allocator.reallocate(
235-
output->data, allocation_size, allocator.state);
233+
(rosidl_runtime_c__String *)realloc(output->data, allocation_size);
236234
if (!data) {
237235
return false;
238236
}
@@ -242,7 +240,7 @@ rosidl_runtime_c__String__Sequence__copy(
242240
for (; i-- > output->capacity; ) {
243241
rosidl_runtime_c__String__fini(&data[i]);
244242
}
245-
allocator.deallocate(data, allocator.state);
243+
free(data);
246244
return false;
247245
}
248246
}

rosidl_runtime_c/src/u16string_functions.c

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -272,10 +272,8 @@ rosidl_runtime_c__U16String__Sequence__copy(
272272
if (output->capacity < input->size) {
273273
const size_t size =
274274
input->size * sizeof(rosidl_runtime_c__U16String);
275-
rcutils_allocator_t allocator = rcutils_get_default_allocator();
276275
rosidl_runtime_c__U16String * data =
277-
(rosidl_runtime_c__U16String *)allocator.reallocate(
278-
output->data, size, allocator.state);
276+
(rosidl_runtime_c__U16String *)realloc(output->data, size);
279277
if (!data) {
280278
return false;
281279
}
@@ -285,7 +283,7 @@ rosidl_runtime_c__U16String__Sequence__copy(
285283
for (; i-- > output->capacity; ) {
286284
rosidl_runtime_c__U16String__fini(&data[i]);
287285
}
288-
allocator.deallocate(data, allocator.state);
286+
free(data);
289287
return false;
290288
}
291289
}

0 commit comments

Comments
 (0)