Skip to content

Commit

Permalink
fix rclc_example: memory leaking in msg.data allocation (#386)
Browse files Browse the repository at this point in the history
Signed-off-by: zhangtonghe <[email protected]>
Co-authored-by: zhangtonghe <[email protected]>
  • Loading branch information
Zard-C and zhangtonghe committed Jul 28, 2023
1 parent 64fa8fe commit 7af2054
Show file tree
Hide file tree
Showing 5 changed files with 7 additions and 6 deletions.
2 changes: 1 addition & 1 deletion rclc_examples/src/example_executor.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion rclc_examples/src/example_executor_only_rcl.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
3 changes: 2 additions & 1 deletion rclc_examples/src/example_executor_trigger.c
Original file line number Diff line number Diff line change
Expand Up @@ -139,14 +139,15 @@ 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);

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);
Expand Down
4 changes: 2 additions & 2 deletions rclc_examples/src/example_pingpong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion rclc_examples/src/example_sub_context.c
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down

0 comments on commit 7af2054

Please sign in to comment.