Skip to content

Commit 272850d

Browse files
committed
demo: fix stack corruption in ping_pong demo
While running the ping_pong demo I noticed a crash: ping_pong_1-1 | [ros2run]: Aborted ping_pong_1-1 | [INFO] [1775242528.757714440] []: Created a timer with period 2000 ms. ping_pong_1-1 | ping_pong_2-1 | realloc(): invalid old size ping_pong_1-1 | mremap_chunk(): invalid pointer ping_pong_2-1 | [ros2run]: Aborted ping_pong_1-1 | [ros2run]: Aborted This is caused by stack memory being passed to realloc() at https://github.com/ros2/rosidl/blob/8cdfe315157f8bffa9b73b6750c52f44325a7847/rosidl_runtime_c/src/string_functions.c#L110 Use ros string allocators to handle this safely. The outcoming_ping is sprintf'd so we must preallocate. Signed-off-by: Cory Todd <cory@219design.com>
1 parent b86db30 commit 272850d

1 file changed

Lines changed: 18 additions & 12 deletions

File tree

rclc/ping_pong/main.c

Lines changed: 18 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@
55

66
#include <std_msgs/msg/header.h>
77

8+
#include <rcutils/allocator.h>
9+
#include <rosidl_runtime_c/string_functions.h>
10+
811
#include <stdio.h>
912
#include <unistd.h>
1013
#include <time.h>
@@ -110,24 +113,27 @@ int main()
110113
RCCHECK(rclc_executor_add_subscription(&executor, &ping_subscriber, &incoming_ping, &ping_subscription_callback, ON_NEW_DATA));
111114
RCCHECK(rclc_executor_add_subscription(&executor, &pong_subscriber, &incoming_pong, &pong_subscription_callback, ON_NEW_DATA));
112115

113-
// Create and allocate the pingpong messages
114-
115-
char outcoming_ping_buffer[STRING_BUFFER_LEN];
116-
outcoming_ping.frame_id.data = outcoming_ping_buffer;
116+
// Allocate frame_id buffers via the rcutils allocator before spinning.
117+
// The deserializer calls realloc() on frame_id.data when a message arrives;
118+
// Remember to pair these with a call to rosidl_runtime_c__String__fini.
119+
// outcoming_ping must be preallocated for sprintf to work. The others
120+
// are used on paths that automatically realloc().
121+
rcutils_allocator_t alloc = rcutils_get_default_allocator();
122+
outcoming_ping.frame_id.data = alloc.allocate(STRING_BUFFER_LEN, alloc.state);
117123
outcoming_ping.frame_id.capacity = STRING_BUFFER_LEN;
124+
outcoming_ping.frame_id.size = 0;
118125

119-
char incoming_ping_buffer[STRING_BUFFER_LEN];
120-
incoming_ping.frame_id.data = incoming_ping_buffer;
121-
incoming_ping.frame_id.capacity = STRING_BUFFER_LEN;
122-
123-
char incoming_pong_buffer[STRING_BUFFER_LEN];
124-
incoming_pong.frame_id.data = incoming_pong_buffer;
125-
incoming_pong.frame_id.capacity = STRING_BUFFER_LEN;
126+
(void) rosidl_runtime_c__String__init(&incoming_ping.frame_id);
127+
(void) rosidl_runtime_c__String__init(&incoming_pong.frame_id);
126128

127129
device_id = rand();
128130

129131
rclc_executor_spin(&executor);
130-
132+
133+
rosidl_runtime_c__String__fini(&outcoming_ping.frame_id);
134+
rosidl_runtime_c__String__fini(&incoming_ping.frame_id);
135+
rosidl_runtime_c__String__fini(&incoming_pong.frame_id);
136+
131137
RCCHECK(rcl_publisher_fini(&ping_publisher, &node));
132138
RCCHECK(rcl_publisher_fini(&pong_publisher, &node));
133139
RCCHECK(rcl_subscription_fini(&ping_subscriber, &node));

0 commit comments

Comments
 (0)