mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_PX4: moved size of main thread stack to Scheduler.h
make it more obvious
This commit is contained in:
parent
1c270d17a8
commit
f2a919c55e
@ -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);
|
||||
|
@ -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:
|
||||
|
Loading…
Reference in New Issue
Block a user