APM:Libraries
Scheduler.h
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #pragma once
18 
19 #include <AP_HAL/AP_HAL.h>
20 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
22 
23 #define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS 8
24 
25 #define APM_MAIN_PRIORITY 180
26 #define APM_TIMER_PRIORITY 178
27 #define APM_RCIN_PRIORITY 177
28 #define APM_TONEALARM_PRIORITY 61
29 #define APM_UART_PRIORITY 60
30 #define APM_STORAGE_PRIORITY 59
31 #define APM_IO_PRIORITY 58
32 #define APM_STARTUP_PRIORITY 10
33 
34 /*
35  boost priority handling
36  */
37 #ifndef APM_MAIN_PRIORITY_BOOST
38 #define APM_MAIN_PRIORITY_BOOST 182
39 #endif
40 
41 #ifndef APM_SPI_PRIORITY
42 // SPI priority needs to be above main priority to ensure fast sampling of IMUs can keep up
43 // with the data rate
44 #define APM_SPI_PRIORITY 181
45 #endif
46 
47 #ifndef APM_UAVCAN_PRIORITY
48 #define APM_UAVCAN_PRIORITY 178
49 #endif
50 
51 #ifndef APM_CAN_PRIORITY
52 #define APM_CAN_PRIORITY 177
53 #endif
54 
55 #ifndef APM_I2C_PRIORITY
56 #define APM_I2C_PRIORITY 176
57 #endif
58 
59 #define APM_MAIN_THREAD_STACK_SIZE 8192
60 
61 /* Scheduler implementation: */
63 public:
64  Scheduler();
65  /* AP_HAL::Scheduler methods */
66 
67 
68  void init();
69  void delay(uint16_t ms) override;
70  void delay_microseconds(uint16_t us) override;
71  void delay_microseconds_boost(uint16_t us) override;
72  void boost_end(void) override;
73  void register_timer_process(AP_HAL::MemberProc) override;
74  void register_io_process(AP_HAL::MemberProc) override;
75  void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
76  void suspend_timer_procs() override;
77  void resume_timer_procs() override;
78  void reboot(bool hold_in_bootloader) override;
79 
80  bool in_main_thread() const override;
81  void system_initialized();
82  void hal_initialized() { _hal_initialized = true; }
83 
84  bool check_called_boost(void);
85 
86  /*
87  disable interrupts and return a context that can be used to
88  restore the interrupt state. This can be used to protect
89  critical regions
90  */
91  void *disable_interrupts_save(void) override;
92 
93  /*
94  restore interrupt state from disable_interrupts_save()
95  */
96  void restore_interrupts(void *) override;
97 
98 private:
100  volatile bool _hal_initialized;
104 
105  volatile bool _timer_suspended;
106 
109  volatile bool _in_timer_proc;
110 
112  uint8_t _num_io_procs;
113  volatile bool _in_io_proc;
114 
115  volatile bool _timer_event_missed;
116 
117  thread_t* _timer_thread_ctx;
118  thread_t* _rcin_thread_ctx;
119  thread_t* _io_thread_ctx;
122 #if HAL_WITH_UAVCAN
123  thread_t* _uavcan_thread_ctx;
124 #endif
125  static void _timer_thread(void *arg);
126  static void _rcin_thread(void *arg);
127  static void _io_thread(void *arg);
128  static void _storage_thread(void *arg);
129  static void _uart_thread(void *arg);
130  static void _toneAlarm_thread(void *arg);
131 #if HAL_WITH_UAVCAN
132  static void _uavcan_thread(void *arg);
133 #endif
134  void _run_timers(bool called_from_timer_thread);
135  void _run_io(void);
136 };
137 #endif
void suspend_timer_procs() override
Definition: Scheduler.cpp:225
void resume_timer_procs() override
Definition: Scheduler.cpp:230
void delay_microseconds_boost(uint16_t us) override
Definition: Scheduler.cpp:150
thread_t * _rcin_thread_ctx
Definition: Scheduler.h:118
void restore_interrupts(void *) override
Definition: Scheduler.cpp:436
volatile bool _timer_event_missed
Definition: Scheduler.h:115
void register_timer_process(AP_HAL::MemberProc) override
Definition: Scheduler.cpp:188
static void _io_thread(void *arg)
Definition: Scheduler.cpp:379
volatile bool _in_timer_proc
Definition: Scheduler.h:109
void(* Proc)(void)
static void _toneAlarm_thread(void *arg)
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override
Definition: Scheduler.cpp:220
volatile bool _hal_initialized
Definition: Scheduler.h:100
uint8_t _num_io_procs
Definition: Scheduler.h:112
#define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:23
void delay(uint16_t ms) override
Definition: Scheduler.cpp:172
bool in_main_thread() const override
Definition: Scheduler.cpp:409
static void _timer_thread(void *arg)
Definition: Scheduler.cpp:294
uint8_t _num_timer_procs
Definition: Scheduler.h:108
void hal_initialized()
Definition: Scheduler.h:82
thread_t * _timer_thread_ctx
Definition: Scheduler.h:117
static void _storage_thread(void *arg)
Definition: Scheduler.cpp:394
bool check_called_boost(void)
Definition: Scheduler.cpp:163
volatile bool _in_io_proc
Definition: Scheduler.h:113
static void _rcin_thread(void *arg)
Definition: Scheduler.cpp:331
thread_t * _toneAlarm_thread_ctx
Definition: Scheduler.h:121
void _run_io(void)
Definition: Scheduler.cpp:360
static void _uart_thread(void *arg)
thread_t * _storage_thread_ctx
Definition: Scheduler.h:120
AP_HAL::Proc _failsafe
Definition: Scheduler.h:101
volatile bool _timer_suspended
Definition: Scheduler.h:105
thread_t * _io_thread_ctx
Definition: Scheduler.h:119
void boost_end(void) override
Definition: Scheduler.cpp:134
AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:107
void register_io_process(AP_HAL::MemberProc) override
Definition: Scheduler.cpp:204
void reboot(bool hold_in_bootloader) override
Definition: Scheduler.cpp:239
void delay_microseconds(uint16_t us) override
Definition: Scheduler.cpp:102
void _run_timers(bool called_from_timer_thread)
Definition: Scheduler.cpp:263
void system_initialized()
Definition: Scheduler.cpp:414
void * disable_interrupts_save(void) override
Definition: Scheduler.cpp:428
AP_HAL::MemberProc _io_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:111