25 using namespace Linux;
29 #define APM_LINUX_TIMER_PRIORITY 15 30 #define APM_LINUX_UART_PRIORITY 14 31 #define APM_LINUX_RCIN_PRIORITY 13 32 #define APM_LINUX_MAIN_PRIORITY 12 33 #define APM_LINUX_TONEALARM_PRIORITY 11 34 #define APM_LINUX_IO_PRIORITY 10 36 #define APM_LINUX_TIMER_RATE 1000 37 #define APM_LINUX_UART_RATE 100 38 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ 39 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \ 40 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ 41 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \ 42 CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI 43 #define APM_LINUX_RCIN_RATE 2000 44 #define APM_LINUX_TONEALARM_RATE 100 45 #define APM_LINUX_IO_RATE 50 47 #define APM_LINUX_RCIN_RATE 100 48 #define APM_LINUX_TONEALARM_RATE 100 49 #define APM_LINUX_IO_RATE 50 52 #define SCHED_THREAD(name_, UPPER_NAME_) \ 54 .name = "ap-" #name_, \ 55 .thread = &_##name_##_thread, \ 56 .policy = SCHED_FIFO, \ 57 .prio = APM_LINUX_##UPPER_NAME_##_PRIORITY, \ 58 .rate = APM_LINUX_##UPPER_NAME_##_RATE, \ 67 const struct sched_table {
83 #if !APM_BUILD_TYPE(APM_BUILD_Replay) 85 mlockall(MCL_CURRENT|MCL_FUTURE);
88 if (sched_setscheduler(0, SCHED_FIFO, ¶m) == -1) {
89 AP_HAL::panic(
"Scheduler: failed to set scheduling parameters: %s",
95 unsigned n_threads =
ARRAY_SIZE(sched_table) + 1;
98 AP_HAL::panic(
"Scheduler: Failed to initialise barrier object: %s",
102 for (
size_t i = 0; i <
ARRAY_SIZE(sched_table); i++) {
103 const struct sched_table *t = &sched_table[i];
105 t->thread->set_rate(t->rate);
106 t->thread->set_stack_size(1024 * 1024);
107 t->thread->start(t->name, t->policy, t->prio);
110 #if defined(DEBUG_STACK) && DEBUG_STACK 120 fprintf(stderr,
"Stack Usage:\n" 139 ts.tv_nsec = usec*1000UL;
140 while (nanosleep(&ts, &ts) == -1 &&
errno == EINTR) ;
150 fprintf(stderr,
"Scheduler::delay() called outside main thread\n");
214 printf(
"Failed to take timer semaphore\n");
233 printf(
"Failed to take timer semaphore in %s\n", __PRETTY_FUNCTION__);
254 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX 255 for (i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
256 if(hal.
can_mgr[i] !=
nullptr) {
321 return pthread_equal(pthread_self(),
_main_ctx);
327 if (r == PTHREAD_BARRIER_SERIAL_THREAD) {
335 AP_HAL::panic(
"PANIC: scheduler::system_initialized called more than once");
358 _sched._wait_all_threads();
int printf(const char *fmt,...)
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS]
void _toneAlarm_timer_tick()
uint64_t _last_stack_debug_msec
AP_HAL::UARTDriver * uartE
void microsleep(uint32_t usec)
AP_HAL::UARTDriver * console
#define APM_LINUX_MAIN_PRIORITY
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
AP_HAL::UARTDriver * uartB
#define HAL_SEMAPHORE_BLOCK_FOREVER
SchedulerThread _timer_thread
void reboot(bool hold_in_bootloader)
void delay_microseconds(uint16_t us)
SchedulerThread _tonealarm_thread
AP_HAL::CANManager ** can_mgr
bool take(uint32_t timeout_ms)
virtual void _timer_tick(void)
AP_HAL::UARTDriver * uartC
static Util * from(AP_HAL::Util *util)
uint64_t _stopped_clock_usec
SchedulerThread _uart_thread
virtual void _timer_tick(void)
virtual void printf(const char *,...) FMT_PRINTF(2
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS]
volatile bool _in_timer_proc
AP_HAL::UARTDriver * uartF
void register_io_process(AP_HAL::MemberProc)
#define LINUX_SCHEDULER_MAX_IO_PROCS
static const AP_HAL::HAL & hal
#define SCHED_THREAD(name_, UPPER_NAME_)
static CANManager * from(AP_HAL::CANManager *can)
AP_HAL::UARTDriver * uartD
AP_HAL::Storage * storage
virtual void call_delay_cb()
SchedulerThread _rcin_thread
void suspend_timer_procs()
uint16_t _min_delay_cb_ms
#define LINUX_SCHEDULER_MAX_TIMER_PROCS
void stop_clock(uint64_t time_usec)
AP_HAL::UARTDriver * uartA
void resume_timer_procs()
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
void register_timer_process(AP_HAL::MemberProc)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void panic(const char *errormsg,...) FMT_PRINTF(1
pthread_barrier_t _initialized_barrier
bool in_main_thread() const override
Semaphore _timer_semaphore
void system_initialized()
SchedulerThread _io_thread