4 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 9 #include <systemlib/perf_counter.h> 11 #define VRBRAIN_SCHEDULER_MAX_TIMER_PROCS 8 13 #define APM_MAIN_PRIORITY_BOOST 241 14 #define APM_MAIN_PRIORITY 180 15 #define APM_TIMER_PRIORITY 181 16 #define APM_SPI_PRIORITY 242 17 #define APM_CAN_PRIORITY 179 18 #define APM_I2C_PRIORITY 178 19 #define APM_UART_PRIORITY 60 20 #define APM_STORAGE_PRIORITY 59 21 #define APM_IO_PRIORITY 58 22 #define APM_SHELL_PRIORITY 57 23 #define APM_OVERTIME_PRIORITY 10 24 #define APM_STARTUP_PRIORITY 10 39 #define APM_MAIN_PRIORITY_BOOST_USEC 150 41 #define APM_MAIN_THREAD_STACK_SIZE 8192 50 void delay(uint16_t ms);
58 void reboot(
bool hold_in_bootloader);
perf_counter_t _perf_timers
void create_uavcan_thread() override
static void * _uavcan_thread(void *arg)
volatile bool _in_io_proc
#define VRBRAIN_SCHEDULER_MAX_TIMER_PROCS
static void * _timer_thread(void *arg)
static void * _uart_thread(void *arg)
void system_initialized()
void resume_timer_procs()
volatile bool _timer_suspended
void delay_microseconds(uint16_t us)
AP_HAL::MemberProc _io_proc[VRBRAIN_SCHEDULER_MAX_TIMER_PROCS]
void register_io_process(AP_HAL::MemberProc)
static void * _storage_thread(void *arg)
volatile bool _in_timer_proc
void _run_timers(bool called_from_timer_thread)
volatile bool _hal_initialized
pthread_t _uavcan_thread_ctx
AP_HAL::MemberProc _timer_proc[VRBRAIN_SCHEDULER_MAX_TIMER_PROCS]
pthread_t _storage_thread_ctx
void reboot(bool hold_in_bootloader)
perf_counter_t _perf_storage_timer
void delay_microseconds_boost(uint16_t us)
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
volatile bool _timer_event_missed
perf_counter_t _perf_delay
bool in_main_thread() const override
void delay_microseconds_semaphore(uint16_t us)
void suspend_timer_procs()
perf_counter_t _perf_io_timers
pthread_t _uart_thread_ctx
pthread_t _timer_thread_ctx
void register_timer_process(AP_HAL::MemberProc)
static void * _io_thread(void *arg)