Skip to content

Commit

Permalink
Use RCUtils allocators in rosidl_generator_c (#584)
Browse files Browse the repository at this point in the history
* Initial

Initial

Signed-off-by: Your Name <you@example.com>

* Move include

Signed-off-by: Pablo Garrido <pablogs9@gmail.com>

* Update package.xml

Signed-off-by: Pablo Garrido <pablogs9@gmail.com>

* Add rosidl_runtime_c rcutils allocators

Signed-off-by: Pablo Garrido <pablogs9@gmail.com>
  • Loading branch information
pablogs9 authored May 5, 2021
1 parent dceaeb9 commit 44105c6
Show file tree
Hide file tree
Showing 6 changed files with 71 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@ foreach(_abs_idl_file ${rosidl_generate_interfaces_ABS_IDL_FILES})
)
endforeach()

find_package(rcutils REQUIRED)

set(_dependency_files "")
set(_dependencies "")
foreach(_pkg_name ${rosidl_generate_interfaces_DEPENDENCY_PACKAGE_NAMES})
Expand Down Expand Up @@ -130,7 +132,8 @@ foreach(_pkg_name ${rosidl_generate_interfaces_DEPENDENCY_PACKAGE_NAMES})
endforeach()
ament_target_dependencies(${rosidl_generate_interfaces_TARGET}${_target_suffix}
"rosidl_runtime_c"
"rosidl_typesupport_interface")
"rosidl_typesupport_interface"
"rcutils")
ament_export_dependencies(
"rosidl_runtime_c"
"rosidl_typesupport_interface")
Expand Down
2 changes: 2 additions & 0 deletions rosidl_generator_c/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,12 @@
<buildtool_export_depend>rosidl_cmake</buildtool_export_depend>

<build_export_depend>rosidl_typesupport_interface</build_export_depend>
<build_export_depend>rcutils</build_export_depend>

<exec_depend>ament_index_python</exec_depend>
<exec_depend>rosidl_cli</exec_depend>
<exec_depend>rosidl_parser</exec_depend>
<exec_depend>rcutils</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
28 changes: 19 additions & 9 deletions rosidl_generator_c/resource/msg__functions.c.em
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ for member in message.structure.members:
@#>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>
@
@#<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<
#include <rcutils/allocator.h>

@[if includes]@

// Include directives for member types
Expand Down Expand Up @@ -235,14 +237,15 @@ for line in lines:
@(message_typename) *
@(message_typename)__create()
{
@(message_typename) * msg = (@(message_typename) *)malloc(sizeof(@(message_typename)));
rcutils_allocator_t allocator = rcutils_get_default_allocator();
@(message_typename) * msg = (@(message_typename) *)allocator.allocate(sizeof(@(message_typename)), allocator.state);
if (!msg) {
return NULL;
}
memset(msg, 0, sizeof(@(message_typename)));
bool success = @(message_typename)__init(msg);
if (!success) {
free(msg);
allocator.deallocate(msg, allocator.state);
return NULL;
}
return msg;
Expand All @@ -251,10 +254,11 @@ for line in lines:
void
@(message_typename)__destroy(@(message_typename) * msg)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
if (msg) {
@(message_typename)__fini(msg);
}
free(msg);
allocator.deallocate(msg, allocator.state);
}


Expand All @@ -267,9 +271,11 @@ bool
if (!array) {
return false;
}
rcutils_allocator_t allocator = rcutils_get_default_allocator();
@(message_typename) * data = NULL;

if (size) {
data = (@(message_typename) *)calloc(size, sizeof(@(message_typename)));
data = (@(message_typename) *)allocator.zero_allocate(size, sizeof(@(message_typename)), allocator.state);
if (!data) {
return false;
}
Expand All @@ -286,7 +292,7 @@ bool
for (; i > 0; --i) {
@(message_typename)__fini(&data[i - 1]);
}
free(data);
allocator.deallocate(data, allocator.state);
return false;
}
}
Expand All @@ -302,14 +308,16 @@ void
if (!array) {
return;
}
rcutils_allocator_t allocator = rcutils_get_default_allocator();

if (array->data) {
// ensure that data and capacity values are consistent
assert(array->capacity > 0);
// finalize all array elements
for (size_t i = 0; i < array->capacity; ++i) {
@(message_typename)__fini(&array->data[i]);
}
free(array->data);
allocator.deallocate(array->data, allocator.state);
array->data = NULL;
array->size = 0;
array->capacity = 0;
Expand All @@ -323,13 +331,14 @@ void
@(array_typename) *
@(array_typename)__create(size_t size)
{
@(array_typename) * array = (@(array_typename) *)malloc(sizeof(@(array_typename)));
rcutils_allocator_t allocator = rcutils_get_default_allocator();
@(array_typename) * array = (@(array_typename) *)allocator.allocate(sizeof(@(array_typename)), allocator.state);
if (!array) {
return NULL;
}
bool success = @(array_typename)__init(array, size);
if (!success) {
free(array);
allocator.deallocate(array, allocator.state);
return NULL;
}
return array;
Expand All @@ -338,8 +347,9 @@ void
void
@(array_typename)__destroy(@(array_typename) * array)
{
rcutils_allocator_t allocator = rcutils_get_default_allocator();
if (array) {
@(array_typename)__fini(array);
}
free(array);
allocator.deallocate(array, allocator.state);
}
8 changes: 6 additions & 2 deletions rosidl_runtime_c/src/primitives_sequence_functions.c
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
#include <stdint.h>
#include <stdlib.h>

#include <rcutils/allocator.h>

#include "rosidl_runtime_c/primitives_sequence_functions.h"

#define ROSIDL_GENERATOR_C__DEFINE_PRIMITIVE_SEQUENCE_FUNCTIONS(STRUCT_NAME, TYPE_NAME) \
Expand All @@ -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; \
} \
Expand All @@ -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; \
Expand Down
28 changes: 19 additions & 9 deletions rosidl_runtime_c/src/string_functions.c
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <string.h>
#include <stdio.h>

#include <rcutils/allocator.h>
#include "rcutils/macros.h"

bool
Expand All @@ -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;
}
Expand All @@ -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;
Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -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;
}
Expand All @@ -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;
}
}
Expand All @@ -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;
Expand All @@ -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;
Expand All @@ -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);
}
32 changes: 21 additions & 11 deletions rosidl_runtime_c/src/u16string_functions.c
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <string.h>
#include <stdio.h>

#include <rcutils/allocator.h>
#include "rcutils/macros.h"

bool
Expand All @@ -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;
}
Expand All @@ -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;
Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -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;
}
Expand All @@ -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;
}
Expand All @@ -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;
}
}
Expand All @@ -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;
Expand All @@ -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;
Expand All @@ -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);
}

0 comments on commit 44105c6

Please sign in to comment.