From 7af20545ec3c11b2dcf1f99fc3705f10c45b6e2b Mon Sep 17 00:00:00 2001 From: Zard-C <58285320+Zard-C@users.noreply.github.com> Date: Fri, 28 Jul 2023 17:14:35 +0800 Subject: [PATCH] fix rclc_example: memory leaking in msg.data allocation (#386) Signed-off-by: zhangtonghe Co-authored-by: zhangtonghe --- rclc_examples/src/example_executor.c | 2 +- rclc_examples/src/example_executor_only_rcl.c | 2 +- rclc_examples/src/example_executor_trigger.c | 3 ++- rclc_examples/src/example_pingpong.cpp | 4 ++-- rclc_examples/src/example_sub_context.c | 2 +- 5 files changed, 7 insertions(+), 6 deletions(-) diff --git a/rclc_examples/src/example_executor.c b/rclc_examples/src/example_executor.c index b9853ca2..bf07f566 100644 --- a/rclc_examples/src/example_executor.c +++ b/rclc_examples/src/example_executor.c @@ -109,7 +109,7 @@ int main(int argc, const char * argv[]) // assign message to publisher std_msgs__msg__String__init(&pub_msg); const unsigned int PUB_MSG_CAPACITY = 20; - pub_msg.data.data = malloc(PUB_MSG_CAPACITY); + pub_msg.data.data = allocator.reallocate(pub_msg.data.data, PUB_MSG_CAPACITY, allocator.state); pub_msg.data.capacity = PUB_MSG_CAPACITY; snprintf(pub_msg.data.data, pub_msg.data.capacity, "Hello World!"); pub_msg.data.size = strlen(pub_msg.data.data); diff --git a/rclc_examples/src/example_executor_only_rcl.c b/rclc_examples/src/example_executor_only_rcl.c index 3d1c7cf3..0b7860fc 100644 --- a/rclc_examples/src/example_executor_only_rcl.c +++ b/rclc_examples/src/example_executor_only_rcl.c @@ -127,7 +127,7 @@ int main(int argc, const char * argv[]) // assign message to publisher std_msgs__msg__String__init(&pub_msg); const unsigned int PUB_MSG_CAPACITY = 20; - pub_msg.data.data = malloc(PUB_MSG_CAPACITY); + pub_msg.data.data = allocator.reallocate(pub_msg.data.data, PUB_MSG_CAPACITY, allocator.state); pub_msg.data.capacity = PUB_MSG_CAPACITY; snprintf(pub_msg.data.data, pub_msg.data.capacity, "Hello World!"); pub_msg.data.size = strlen(pub_msg.data.data); diff --git a/rclc_examples/src/example_executor_trigger.c b/rclc_examples/src/example_executor_trigger.c index 8698bcb9..272e5166 100644 --- a/rclc_examples/src/example_executor_trigger.c +++ b/rclc_examples/src/example_executor_trigger.c @@ -139,6 +139,7 @@ void my_int_subscriber_callback(const void * msgin) void my_timer_string_callback(rcl_timer_t * timer, int64_t last_call_time) { rcl_ret_t rc; + rcl_allocator_t allocator = rcl_get_default_allocator(); RCLC_UNUSED(last_call_time); if (timer != NULL) { //printf("Timer: time since last call %d\n", (int) last_call_time); @@ -146,7 +147,7 @@ void my_timer_string_callback(rcl_timer_t * timer, int64_t last_call_time) std_msgs__msg__String pub_msg; std_msgs__msg__String__init(&pub_msg); const unsigned int PUB_MSG_CAPACITY = 20; - pub_msg.data.data = malloc(PUB_MSG_CAPACITY); + pub_msg.data.data = allocator.reallocate(pub_msg.data.data, PUB_MSG_CAPACITY, allocator.state); pub_msg.data.capacity = PUB_MSG_CAPACITY; snprintf(pub_msg.data.data, pub_msg.data.capacity, "Hello World!%d", string_pub_value++); pub_msg.data.size = strlen(pub_msg.data.data); diff --git a/rclc_examples/src/example_pingpong.cpp b/rclc_examples/src/example_pingpong.cpp index 0bba9932..0f174edf 100644 --- a/rclc_examples/src/example_pingpong.cpp +++ b/rclc_examples/src/example_pingpong.cpp @@ -181,7 +181,7 @@ int main(int argc, const char * argv[]) // assign message to publisher std_msgs__msg__String__init(&pingNode_ping_msg); const unsigned int PUB_MSG_CAPACITY = 20; - pingNode_ping_msg.data.data = (char *) malloc(PUB_MSG_CAPACITY); + pingNode_ping_msg.data.data = (char *) allocator.reallocate(pingNode_ping_msg.data.data, PUB_MSG_CAPACITY, allocator.state); pingNode_ping_msg.data.capacity = PUB_MSG_CAPACITY; snprintf(pingNode_ping_msg.data.data, pingNode_ping_msg.data.capacity, "AAAAAAAAAAAAAAAAAAA"); pingNode_ping_msg.data.size = strlen(pingNode_ping_msg.data.data); @@ -258,7 +258,7 @@ int main(int argc, const char * argv[]) // assign message to publisher std_msgs__msg__String__init(&pongNode_pong_msg); //const unsigned int PUB_MSG_CAPACITY = 20; - pongNode_pong_msg.data.data = (char *) malloc(PUB_MSG_CAPACITY); + pongNode_pong_msg.data.data = (char *) allocator.reallocate(pongNode_pong_msg.data.data, PUB_MSG_CAPACITY, allocator.state); pongNode_pong_msg.data.capacity = PUB_MSG_CAPACITY; snprintf(pongNode_pong_msg.data.data, pongNode_pong_msg.data.capacity, "BAAAAAAAAAAAAAAAAAAA"); pongNode_pong_msg.data.size = strlen(pongNode_pong_msg.data.data); diff --git a/rclc_examples/src/example_sub_context.c b/rclc_examples/src/example_sub_context.c index 86e1b22a..dc169d59 100644 --- a/rclc_examples/src/example_sub_context.c +++ b/rclc_examples/src/example_sub_context.c @@ -111,7 +111,7 @@ int main(int argc, const char * argv[]) // assign message to publisher std_msgs__msg__String__init(&( pub_msgs[i] ) ); const unsigned int PUB_MSG_CAPACITY = 40; - pub_msgs[i].data.data = malloc(PUB_MSG_CAPACITY); + pub_msgs[i].data.data = allocator.reallocate(pub_msgs[i].data.data, PUB_MSG_CAPACITY, allocator.state); pub_msgs[i].data.capacity = PUB_MSG_CAPACITY; snprintf( pub_msgs[i].data.data, pub_msgs[i].data.capacity, "Hello World! on %s",