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_PX4
5 #include "AP_HAL_PX4_Namespace.h"
6 #include <sys/time.h>
7 #include <signal.h>
8 #include <pthread.h>
9 #include <systemlib/perf_counter.h>
10 
11 #define PX4_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:
46  PX4Scheduler();
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  /*
67  disable interrupts and return a context that can be used to
68  restore the interrupt state. This can be used to protect
69  critical regions
70  */
71  void *disable_interrupts_save(void) override;
72 
73  /*
74  restore interrupt state from disable_interrupts_save()
75  */
76  void restore_interrupts(void *) override;
77 
78 private:
80  volatile bool _hal_initialized;
82  uint16_t _min_delay_cb_ms;
84 
85  volatile bool _timer_suspended;
86 
89  volatile bool _in_timer_proc;
90 
92  uint8_t _num_io_procs;
93  volatile bool _in_io_proc;
94 
95  volatile bool _timer_event_missed;
96 
98  pthread_t _timer_thread_ctx;
99  pthread_t _io_thread_ctx;
101  pthread_t _uart_thread_ctx;
103 
106  uint8_t uavcan_number;
107  };
108 
109  static void *_timer_thread(void *arg);
110  static void *_io_thread(void *arg);
111  static void *_storage_thread(void *arg);
112  static void *_uart_thread(void *arg);
113  static void *_uavcan_thread(void *arg);
114 
115  void _run_timers(bool called_from_timer_thread);
116  void _run_io(void);
117 
118  void delay_microseconds_semaphore(uint16_t us);
119 
120  perf_counter_t _perf_timers;
121  perf_counter_t _perf_io_timers;
122  perf_counter_t _perf_storage_timer;
123  perf_counter_t _perf_delay;
124 };
125 #endif
uint8_t _num_io_procs
Definition: Scheduler.h:92
bool in_main_thread() const override
Definition: Scheduler.cpp:437
uint8_t _num_timer_procs
Definition: Scheduler.h:88
volatile bool _timer_suspended
Definition: Scheduler.h:85
pthread_t _uart_thread_ctx
Definition: Scheduler.h:101
#define PX4_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:11
pthread_t _timer_thread_ctx
Definition: Scheduler.h:98
perf_counter_t _perf_delay
Definition: Scheduler.h:123
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:82
void(* Proc)(void)
perf_counter_t _perf_timers
Definition: Scheduler.h:120
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
Definition: Scheduler.cpp:228
static void * _uavcan_thread(void *arg)
pid_t _main_task_pid
Definition: Scheduler.h:97
void delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:134
volatile bool _hal_initialized
Definition: Scheduler.h:80
void create_uavcan_thread() override
Definition: Scheduler.cpp:93
static void * _uart_thread(void *arg)
Definition: Scheduler.cpp:344
void * disable_interrupts_save(void) override
Definition: Scheduler.cpp:457
void _run_timers(bool called_from_timer_thread)
Definition: Scheduler.cpp:259
pthread_t _uavcan_thread_ctx
Definition: Scheduler.h:102
void _run_io(void)
Definition: Scheduler.cpp:325
void reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:247
pthread_t _storage_thread_ctx
Definition: Scheduler.h:100
void hal_initialized()
Definition: Scheduler.h:62
static void * _timer_thread(void *arg)
Definition: Scheduler.cpp:290
volatile bool _in_timer_proc
Definition: Scheduler.h:89
void suspend_timer_procs()
Definition: Scheduler.cpp:233
pthread_t _io_thread_ctx
Definition: Scheduler.h:99
perf_counter_t _perf_storage_timer
Definition: Scheduler.h:122
static void * _storage_thread(void *arg)
Definition: Scheduler.cpp:387
static void * _io_thread(void *arg)
Definition: Scheduler.cpp:367
AP_HAL::Proc _delay_cb
Definition: Scheduler.h:81
perf_counter_t _perf_io_timers
Definition: Scheduler.h:121
AP_HAL::Proc _failsafe
Definition: Scheduler.h:83
void system_initialized()
Definition: Scheduler.cpp:442
void register_timer_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:196
volatile bool _timer_event_missed
Definition: Scheduler.h:95
void resume_timer_procs()
Definition: Scheduler.cpp:238
AP_HAL::MemberProc _timer_proc[PX4_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:87
void register_io_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:212
void delay_microseconds_semaphore(uint16_t us)
Definition: Scheduler.cpp:124
void delay_microseconds_boost(uint16_t us)
Definition: Scheduler.cpp:164
void restore_interrupts(void *) override
Definition: Scheduler.cpp:465
volatile bool _in_io_proc
Definition: Scheduler.h:93
AP_HAL::MemberProc _io_proc[PX4_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:91
void delay(uint16_t ms)
Definition: Scheduler.cpp:174