ardupilot/libraries/AP_HAL_Linux/Scheduler.h

110 lines
2.8 KiB
C
Raw Normal View History

#pragma once
2013-09-22 03:01:24 -03:00
#include <pthread.h>
#include "AP_HAL_Linux.h"
#include "Semaphores.h"
#include "Thread.h"
#define LINUX_SCHEDULER_MAX_TIMER_PROCS 10
#define LINUX_SCHEDULER_MAX_TIMESLICED_PROCS 10
#define LINUX_SCHEDULER_MAX_IO_PROCS 10
2016-07-19 10:01:47 -03:00
#define AP_LINUX_SENSORS_STACK_SIZE 256 * 1024
#define AP_LINUX_SENSORS_SCHED_POLICY SCHED_FIFO
#define AP_LINUX_SENSORS_SCHED_PRIO 12
namespace Linux {
class Scheduler : public AP_HAL::Scheduler {
2013-09-22 03:01:24 -03:00
public:
Scheduler();
static Scheduler *from(AP_HAL::Scheduler *scheduler) {
return static_cast<Scheduler*>(scheduler);
}
void init() override;
void delay(uint16_t ms) override;
void delay_microseconds(uint16_t us) override;
2013-09-22 03:01:24 -03:00
void register_timer_process(AP_HAL::MemberProc) override;
void register_io_process(AP_HAL::MemberProc) override;
2013-09-22 03:01:24 -03:00
bool in_main_thread() const override;
2013-09-22 03:01:24 -03:00
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
2013-09-22 03:01:24 -03:00
void set_system_initialized() override;
bool is_system_initialized() override { return _initialized; };
2013-09-22 03:01:24 -03:00
void reboot(bool hold_in_bootloader) override;
2013-09-22 03:01:24 -03:00
void stop_clock(uint64_t time_usec) override;
2013-12-29 18:31:33 -04:00
uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }
void microsleep(uint32_t usec);
void teardown();
2018-07-06 21:25:39 -03:00
/*
create a new thread
*/
bool thread_create(AP_HAL::MemberProc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) override;
2013-09-22 03:01:24 -03:00
private:
class SchedulerThread : public PeriodicThread {
public:
SchedulerThread(Thread::task_t t, Scheduler &sched)
: PeriodicThread(t)
, _sched(sched)
{ }
protected:
bool _run() override;
Scheduler &_sched;
};
2016-11-15 22:20:31 -04:00
void init_realtime();
void _wait_all_threads();
void _debug_stack();
AP_HAL::Proc _failsafe;
bool _initialized;
pthread_barrier_t _initialized_barrier;
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS];
uint8_t _num_timer_procs;
volatile bool _in_timer_proc;
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS];
uint8_t _num_io_procs;
SchedulerThread _timer_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_timer_task, void), *this};
SchedulerThread _io_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_io_task, void), *this};
SchedulerThread _rcin_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_rcin_task, void), *this};
SchedulerThread _uart_thread{FUNCTOR_BIND_MEMBER(&Scheduler::_uart_task, void), *this};
void _timer_task();
void _io_task();
void _rcin_task();
void _uart_task();
void _run_io();
void _run_uarts();
2013-12-31 05:05:07 -04:00
uint64_t _stopped_clock_usec;
uint64_t _last_stack_debug_msec;
pthread_t _main_ctx;
Semaphore _io_semaphore;
2013-09-22 03:01:24 -03:00
};
}