Browse Source

AP_HAL_ChibiOS: Handle scripting priority

mission-4.1.18
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
11ab6c59e1
  1. 1
      libraries/AP_HAL_ChibiOS/Scheduler.cpp
  2. 1
      libraries/AP_HAL_ChibiOS/Scheduler.h

1
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -419,6 +419,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ @@ -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) {

1
libraries/AP_HAL_ChibiOS/Scheduler.h

@ -29,6 +29,7 @@ @@ -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…
Cancel
Save