mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: sneak the scheduler Stack Sizes values down to smaller but still ok-we-hope values.
WARN - may cause crashes!
This commit is contained in:
parent
f5c28cc12d
commit
f10333e787
|
@ -85,16 +85,16 @@ public:
|
|||
static const int IO_PRIO = 5;
|
||||
static const int STORAGE_PRIO = 4;
|
||||
|
||||
static const int TIMER_SS = 4096;
|
||||
static const int MAIN_SS = 8192;
|
||||
static const int RCIN_SS = 4096;
|
||||
static const int RCOUT_SS = 4096;
|
||||
static const int WIFI_SS1 = 6192;
|
||||
static const int WIFI_SS2 = 6192;
|
||||
static const int UART_SS = 2048;
|
||||
static const int DEVICE_SS = 4096;
|
||||
static const int IO_SS = 4096;
|
||||
static const int STORAGE_SS = 8192;
|
||||
static const int TIMER_SS = 1024*3;
|
||||
static const int MAIN_SS = 1024*5;
|
||||
static const int RCIN_SS = 1024*3;
|
||||
static const int RCOUT_SS = 1024*1.5;
|
||||
static const int WIFI_SS1 = 1024*2.25;
|
||||
static const int WIFI_SS2 = 1024*2.25;
|
||||
static const int UART_SS = 1024*2.25;
|
||||
static const int DEVICE_SS = 1024*4; // (DEVICEBUS/s)
|
||||
static const int IO_SS = 1024*3.5; // (APM_IO)
|
||||
static const int STORAGE_SS = 1024*2; // (APM_STORAGE)
|
||||
|
||||
private:
|
||||
AP_HAL::HAL::Callbacks *callbacks;
|
||||
|
|
Loading…
Reference in New Issue