-
Notifications
You must be signed in to change notification settings - Fork 236
Description
While default build configuration, There are potential stack overflow in thread function named task_mavobc_entry
FMT-Firmware/src/task/comm/task_comm.c
Lines 838 to 847 in de5aecb
| TASK_EXPORT __fmt_task2_desc = { | |
| .name = "mavobc", | |
| .init = task_mavobc_init, | |
| .entry = task_mavobc_entry, | |
| .priority = MAVOBC_THREAD_PRIORITY, | |
| .auto_start = true, | |
| .stack_size = 4096, | |
| .param = NULL, | |
| .dependency = (char*[]) { "mavgcs", NULL } | |
| }; |
In this line, task_mavobc_entry Allows 4096 stack size.
However, after manually checking stack, it might have 4400 Bytes.
Steps to reproduce
- In
rtconfig.py, add this line:
# in 61 line..
...
CFLAGS += ' -std=c99'
CXXFLAGS += ' -std=c++14'
++ CXXFLAGS += ' -fstack-usage '
++ CFLAGS += ' -fstack-usage 'This will help you calculating stack size of each function.
- Build FMT-Firmware normally
cd FMT-Firmware/target/amov/icf5
scons -j4
Now we can get stack usage file (*.su) for each source file, So we can manually check stack size of each function.
In case of task_mavobc_entry:
There are large call stack with this flow:
task_mavobc_entry (task_mavobc_entry) => 0 size
mavproxy_channel_loop (mavproxy_channel_loop) => 72 size
mavproxy_cmd_exec (mavproxy_cmd_exec) => 192 size
mag_calibration (mag_calibration) => 672 size
ellipsoid_fit_solve (ellipsoid_fit_solve) =>2488 size
xzggev (xzggev) => 832 size
xzlartg (xzlartg) => 144 size
=>4400 Bytes!
So, there are potentially occur stack overflow in task_mavobc_entry Thread function.
I only check with icf5, but it seems that there are lots of any other configurations that potentially make thread stack overflow.