AP_HAL_PX4: moved size of main thread stack to Scheduler.h

make it more obvious
This commit is contained in:
Andrew Tridgell 2015-02-07 08:06:53 +11:00
parent 1c270d17a8
commit f2a919c55e
2 changed files with 7 additions and 5 deletions

View File

@ -234,7 +234,7 @@ void HAL_PX4::init(int argc, char * const argv[]) const
daemon_task = task_spawn_cmd(SKETCHNAME,
SCHED_FIFO,
APM_MAIN_PRIORITY,
8192,
APM_MAIN_THREAD_STACK_SIZE,
main_loop,
NULL);
exit(0);

View File

@ -19,6 +19,8 @@
#define APM_OVERTIME_PRIORITY 10
#define APM_STARTUP_PRIORITY 10
#define APM_MAIN_THREAD_STACK_SIZE 8192
/* Scheduler implementation: */
class PX4::PX4Scheduler : public AP_HAL::Scheduler {
public: