mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: added PRIORITY_NET
This commit is contained in:
parent
9456b585fa
commit
936bbeda88
|
@ -697,6 +697,7 @@ uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority
|
|||
{ PRIORITY_UART, APM_UART_PRIORITY},
|
||||
{ PRIORITY_STORAGE, APM_STORAGE_PRIORITY},
|
||||
{ PRIORITY_SCRIPTING, APM_SCRIPTING_PRIORITY},
|
||||
{ PRIORITY_NET, APM_NET_PRIORITY},
|
||||
};
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(priority_map); i++) {
|
||||
if (priority_map[i].base == base) {
|
||||
|
|
|
@ -28,6 +28,7 @@
|
|||
#define APM_RCOUT_PRIORITY 181
|
||||
#define APM_LED_PRIORITY 60
|
||||
#define APM_UART_PRIORITY 60
|
||||
#define APM_NET_PRIORITY 60
|
||||
#define APM_UART_UNBUFFERED_PRIORITY 181
|
||||
#define APM_STORAGE_PRIORITY 59
|
||||
#define APM_IO_PRIORITY 58
|
||||
|
|
Loading…
Reference in New Issue