mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_HAL_ChibiOS: Handle scripting priority
This commit is contained in:
parent
73901274b0
commit
11ab6c59e1
@ -419,6 +419,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
||||
{ PRIORITY_IO, APM_IO_PRIORITY},
|
||||
{ PRIORITY_UART, APM_UART_PRIORITY},
|
||||
{ PRIORITY_STORAGE, APM_STORAGE_PRIORITY},
|
||||
{ PRIORITY_SCRIPTING, APM_SCRIPTING_PRIORITY},
|
||||
};
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(priority_map); i++) {
|
||||
if (priority_map[i].base == base) {
|
||||
|
@ -29,6 +29,7 @@
|
||||
#define APM_STORAGE_PRIORITY 59
|
||||
#define APM_IO_PRIORITY 58
|
||||
#define APM_STARTUP_PRIORITY 10
|
||||
#define APM_SCRIPTING_PRIORITY LOWPRIO
|
||||
|
||||
/*
|
||||
boost priority handling
|
||||
|
Loading…
Reference in New Issue
Block a user