mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_PX4: Handle scripting priority
This commit is contained in:
parent
f506a96b7f
commit
a7d94ff6c7
@ -418,6 +418,7 @@ bool PX4Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint
|
||||
{ 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) {
|
||||
|
@ -23,6 +23,7 @@
|
||||
#define APM_SHELL_PRIORITY 57
|
||||
#define APM_OVERTIME_PRIORITY 10
|
||||
#define APM_STARTUP_PRIORITY 10
|
||||
#define APM_SCRIPTING_PRIORITY 1
|
||||
|
||||
/* how long to boost priority of the main thread for each main
|
||||
loop. This needs to be long enough for all interrupt-level drivers
|
||||
|
Loading…
Reference in New Issue
Block a user