APM:Libraries
Scheduler.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <pthread.h>
4 
5 #include "AP_HAL_Linux.h"
6 #include "Semaphores.h"
7 #include "Thread.h"
8 
9 #define LINUX_SCHEDULER_MAX_TIMER_PROCS 10
10 #define LINUX_SCHEDULER_MAX_TIMESLICED_PROCS 10
11 #define LINUX_SCHEDULER_MAX_IO_PROCS 10
12 
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
16 
17 namespace Linux {
18 
19 class Scheduler : public AP_HAL::Scheduler {
20 public:
21  Scheduler();
22 
23  static Scheduler *from(AP_HAL::Scheduler *scheduler) {
24  return static_cast<Scheduler*>(scheduler);
25  }
26 
27  void init();
28  void delay(uint16_t ms);
29  void delay_microseconds(uint16_t us);
30 
31  void register_timer_process(AP_HAL::MemberProc);
32  void register_io_process(AP_HAL::MemberProc);
33  void suspend_timer_procs();
34  void resume_timer_procs();
35 
36  bool in_main_thread() const override;
37 
38  void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
39 
40  void system_initialized();
41 
42  void reboot(bool hold_in_bootloader);
43 
44  void stop_clock(uint64_t time_usec);
45 
46  uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }
47 
48  void microsleep(uint32_t usec);
49 
50  void teardown();
51 
52 private:
54  public:
55  SchedulerThread(Thread::task_t t, Scheduler &sched)
56  : PeriodicThread(t)
57  , _sched(sched)
58  { }
59 
60  protected:
61  bool _run() override;
62 
64  };
65 
66  void _wait_all_threads();
67 
68  void _debug_stack();
69 
71 
73  pthread_barrier_t _initialized_barrier;
74 
77  volatile bool _in_timer_proc;
78 
80  uint8_t _num_io_procs;
81 
87 
88  void _timer_task();
89  void _io_task();
90  void _rcin_task();
91  void _uart_task();
92  void _tonealarm_task();
93 
94  void _run_io();
95  void _run_uarts();
96 
99  pthread_t _main_ctx;
100 
103 };
104 
105 }
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:75
uint64_t _last_stack_debug_msec
Definition: Scheduler.h:98
SchedulerThread(Thread::task_t t, Scheduler &sched)
Definition: Scheduler.h:55
void microsleep(uint32_t usec)
Definition: Scheduler.cpp:135
static Scheduler * from(AP_HAL::Scheduler *scheduler)
Definition: Scheduler.h:23
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
Definition: Scheduler.cpp:206
void _wait_all_threads()
Definition: Scheduler.cpp:324
SchedulerThread _timer_thread
Definition: Scheduler.h:82
void(* Proc)(void)
void reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:343
uint64_t stopped_clock_usec() const
Definition: Scheduler.h:46
Semaphore _io_semaphore
Definition: Scheduler.h:102
void delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:165
SchedulerThread _tonealarm_thread
Definition: Scheduler.h:86
uint64_t _stopped_clock_usec
Definition: Scheduler.h:97
SchedulerThread _uart_thread
Definition: Scheduler.h:85
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS]
Definition: Scheduler.h:79
volatile bool _in_timer_proc
Definition: Scheduler.h:77
uint8_t _num_timer_procs
Definition: Scheduler.h:76
AP_HAL::Proc _failsafe
Definition: Scheduler.h:70
void register_io_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:190
#define LINUX_SCHEDULER_MAX_IO_PROCS
Definition: Scheduler.h:11
SchedulerThread _rcin_thread
Definition: Scheduler.h:84
void _tonealarm_task()
Definition: Scheduler.cpp:304
void suspend_timer_procs()
Definition: Scheduler.cpp:211
#define LINUX_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:9
void stop_clock(uint64_t time_usec)
Definition: Scheduler.cpp:348
void resume_timer_procs()
Definition: Scheduler.cpp:218
uint8_t _num_io_procs
Definition: Scheduler.h:80
void register_timer_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:173
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
pthread_barrier_t _initialized_barrier
Definition: Scheduler.h:73
bool in_main_thread() const override
Definition: Scheduler.cpp:319
Semaphore _timer_semaphore
Definition: Scheduler.h:101
void system_initialized()
Definition: Scheduler.cpp:332
pthread_t _main_ctx
Definition: Scheduler.h:99
void delay(uint16_t ms)
Definition: Scheduler.cpp:143
SchedulerThread _io_thread
Definition: Scheduler.h:83