9 #define LINUX_SCHEDULER_MAX_TIMER_PROCS 10 10 #define LINUX_SCHEDULER_MAX_TIMESLICED_PROCS 10 11 #define LINUX_SCHEDULER_MAX_IO_PROCS 10 13 #define AP_LINUX_SENSORS_STACK_SIZE 256 * 1024 14 #define AP_LINUX_SENSORS_SCHED_POLICY SCHED_FIFO 15 #define AP_LINUX_SENSORS_SCHED_PRIO 12 24 return static_cast<Scheduler*
>(scheduler);
28 void delay(uint16_t ms);
42 void reboot(
bool hold_in_bootloader);
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS]
uint64_t _last_stack_debug_msec
SchedulerThread(Thread::task_t t, Scheduler &sched)
void microsleep(uint32_t usec)
static Scheduler * from(AP_HAL::Scheduler *scheduler)
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
SchedulerThread _timer_thread
void reboot(bool hold_in_bootloader)
uint64_t stopped_clock_usec() const
void delay_microseconds(uint16_t us)
SchedulerThread _tonealarm_thread
uint64_t _stopped_clock_usec
SchedulerThread _uart_thread
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS]
volatile bool _in_timer_proc
void register_io_process(AP_HAL::MemberProc)
#define LINUX_SCHEDULER_MAX_IO_PROCS
SchedulerThread _rcin_thread
void suspend_timer_procs()
#define LINUX_SCHEDULER_MAX_TIMER_PROCS
void stop_clock(uint64_t time_usec)
void resume_timer_procs()
void register_timer_process(AP_HAL::MemberProc)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
pthread_barrier_t _initialized_barrier
bool in_main_thread() const override
Semaphore _timer_semaphore
void system_initialized()
SchedulerThread _io_thread