APM:Libraries
Scheduler.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
6 #include <sys/time.h>
7 #include <signal.h>
8 #include <pthread.h>
9 #include <systemlib/perf_counter.h>
10 
11 #define VRBRAIN_SCHEDULER_MAX_TIMER_PROCS 8
12 
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
25 
26 /* how long to boost priority of the main thread for each main
27  loop. This needs to be long enough for all interrupt-level drivers
28  (mostly SPI drivers) to run, and for the main loop of the vehicle
29  code to start the AHRS update.
30 
31  Priority boosting of the main thread in delay_microseconds_boost()
32  avoids the problem that drivers in hpwork all happen to run right
33  at the start of the period where the main vehicle loop is calling
34  wait_for_sample(). That causes main loop timing jitter, which
35  reduces performance. Using the priority boost the main loop
36  temporarily runs at a priority higher than hpwork and the timer
37  thread, which results in much more consistent loop timing.
38 */
39 #define APM_MAIN_PRIORITY_BOOST_USEC 150
40 
41 #define APM_MAIN_THREAD_STACK_SIZE 8192
42 
43 /* Scheduler implementation: */
45 public:
47  /* AP_HAL::Scheduler methods */
48 
49  void init();
50  void delay(uint16_t ms);
51  void delay_microseconds(uint16_t us);
52  void delay_microseconds_boost(uint16_t us);
53  void register_timer_process(AP_HAL::MemberProc);
54  void register_io_process(AP_HAL::MemberProc);
55  void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
56  void suspend_timer_procs();
57  void resume_timer_procs();
58  void reboot(bool hold_in_bootloader);
59 
60  bool in_main_thread() const override;
61  void system_initialized();
62  void hal_initialized() { _hal_initialized = true; }
63 
64  void create_uavcan_thread() override;
65 
66 private:
68  volatile bool _hal_initialized;
70 
71  volatile bool _timer_suspended;
72 
75  volatile bool _in_timer_proc;
76 
78  uint8_t _num_io_procs;
79  volatile bool _in_io_proc;
80 
81  volatile bool _timer_event_missed;
82 
84  pthread_t _timer_thread_ctx;
85  pthread_t _io_thread_ctx;
87  pthread_t _uart_thread_ctx;
88  pthread_t _uavcan_thread_ctx;
89 
92  uint8_t uavcan_number;
93  };
94 
95  static void *_timer_thread(void *arg);
96  static void *_io_thread(void *arg);
97  static void *_storage_thread(void *arg);
98  static void *_uart_thread(void *arg);
99  static void *_uavcan_thread(void *arg);
100 
101  void _run_timers(bool called_from_timer_thread);
102  void _run_io(void);
103 
104  void delay_microseconds_semaphore(uint16_t us);
105 
106  perf_counter_t _perf_timers;
107  perf_counter_t _perf_io_timers;
108  perf_counter_t _perf_storage_timer;
109  perf_counter_t _perf_delay;
110 };
111 #endif
perf_counter_t _perf_timers
Definition: Scheduler.h:106
void create_uavcan_thread() override
Definition: Scheduler.cpp:93
AP_HAL::Proc _failsafe
Definition: Scheduler.h:69
static void * _uavcan_thread(void *arg)
volatile bool _in_io_proc
Definition: Scheduler.h:79
#define VRBRAIN_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:11
static void * _timer_thread(void *arg)
Definition: Scheduler.cpp:290
void(* Proc)(void)
static void * _uart_thread(void *arg)
Definition: Scheduler.cpp:344
volatile bool _timer_suspended
Definition: Scheduler.h:71
void delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:134
AP_HAL::MemberProc _io_proc[VRBRAIN_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:77
void register_io_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:212
static void * _storage_thread(void *arg)
Definition: Scheduler.cpp:387
volatile bool _in_timer_proc
Definition: Scheduler.h:75
void _run_timers(bool called_from_timer_thread)
Definition: Scheduler.cpp:259
volatile bool _hal_initialized
Definition: Scheduler.h:68
pthread_t _uavcan_thread_ctx
Definition: Scheduler.h:88
AP_HAL::MemberProc _timer_proc[VRBRAIN_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:73
pthread_t _storage_thread_ctx
Definition: Scheduler.h:86
void reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:247
perf_counter_t _perf_storage_timer
Definition: Scheduler.h:108
void delay_microseconds_boost(uint16_t us)
Definition: Scheduler.cpp:164
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
Definition: Scheduler.cpp:228
volatile bool _timer_event_missed
Definition: Scheduler.h:81
perf_counter_t _perf_delay
Definition: Scheduler.h:109
bool in_main_thread() const override
Definition: Scheduler.cpp:437
void delay_microseconds_semaphore(uint16_t us)
Definition: Scheduler.cpp:124
perf_counter_t _perf_io_timers
Definition: Scheduler.h:107
pthread_t _uart_thread_ctx
Definition: Scheduler.h:87
pthread_t _timer_thread_ctx
Definition: Scheduler.h:84
void delay(uint16_t ms)
Definition: Scheduler.cpp:174
void register_timer_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:196
static void * _io_thread(void *arg)
Definition: Scheduler.cpp:367