20 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS 23 #define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS 8 25 #define APM_MAIN_PRIORITY 180 26 #define APM_TIMER_PRIORITY 178 27 #define APM_RCIN_PRIORITY 177 28 #define APM_TONEALARM_PRIORITY 61 29 #define APM_UART_PRIORITY 60 30 #define APM_STORAGE_PRIORITY 59 31 #define APM_IO_PRIORITY 58 32 #define APM_STARTUP_PRIORITY 10 37 #ifndef APM_MAIN_PRIORITY_BOOST 38 #define APM_MAIN_PRIORITY_BOOST 182 41 #ifndef APM_SPI_PRIORITY 44 #define APM_SPI_PRIORITY 181 47 #ifndef APM_UAVCAN_PRIORITY 48 #define APM_UAVCAN_PRIORITY 178 51 #ifndef APM_CAN_PRIORITY 52 #define APM_CAN_PRIORITY 177 55 #ifndef APM_I2C_PRIORITY 56 #define APM_I2C_PRIORITY 176 59 #define APM_MAIN_THREAD_STACK_SIZE 8192 69 void delay(uint16_t ms)
override;
78 void reboot(
bool hold_in_bootloader)
override;
123 thread_t* _uavcan_thread_ctx;
132 static void _uavcan_thread(
void *arg);
void suspend_timer_procs() override
void resume_timer_procs() override
void delay_microseconds_boost(uint16_t us) override
thread_t * _rcin_thread_ctx
void restore_interrupts(void *) override
volatile bool _timer_event_missed
void register_timer_process(AP_HAL::MemberProc) override
static void _io_thread(void *arg)
volatile bool _in_timer_proc
static void _toneAlarm_thread(void *arg)
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override
volatile bool _hal_initialized
#define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS
void delay(uint16_t ms) override
bool in_main_thread() const override
static void _timer_thread(void *arg)
thread_t * _timer_thread_ctx
static void _storage_thread(void *arg)
bool check_called_boost(void)
volatile bool _in_io_proc
static void _rcin_thread(void *arg)
thread_t * _toneAlarm_thread_ctx
static void _uart_thread(void *arg)
thread_t * _storage_thread_ctx
volatile bool _timer_suspended
thread_t * _io_thread_ctx
void boost_end(void) override
AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS]
void register_io_process(AP_HAL::MemberProc) override
void reboot(bool hold_in_bootloader) override
void delay_microseconds(uint16_t us) override
void _run_timers(bool called_from_timer_thread)
void system_initialized()
void * disable_interrupts_save(void) override
AP_HAL::MemberProc _io_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS]