APM:Libraries
Scheduler.cpp
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 #include <AP_HAL/AP_HAL.h>
18 
19 #include "AP_HAL_ChibiOS.h"
20 #include "Scheduler.h"
21 #include "Util.h"
22 
25 #include <AP_HAL_ChibiOS/Storage.h>
27 #include <AP_HAL_ChibiOS/RCInput.h>
28 #include <AP_HAL_ChibiOS/CAN.h>
29 
32 #include "shared_dma.h"
33 #include "sdcard.h"
34 
35 #if CH_CFG_USE_DYNAMIC == TRUE
36 
37 using namespace ChibiOS;
38 
39 extern const AP_HAL::HAL& hal;
40 THD_WORKING_AREA(_timer_thread_wa, 2048);
41 THD_WORKING_AREA(_rcin_thread_wa, 512);
42 #ifdef HAL_PWM_ALARM
43 THD_WORKING_AREA(_toneAlarm_thread_wa, 512);
44 #endif
45 THD_WORKING_AREA(_io_thread_wa, 2048);
46 THD_WORKING_AREA(_storage_thread_wa, 2048);
47 #if HAL_WITH_UAVCAN
48 THD_WORKING_AREA(_uavcan_thread_wa, 4096);
49 #endif
50 
52 {}
53 
55 {
56  // setup the timer thread - this will call tasks at 1kHz
57  _timer_thread_ctx = chThdCreateStatic(_timer_thread_wa,
58  sizeof(_timer_thread_wa),
59  APM_TIMER_PRIORITY, /* Initial priority. */
60  _timer_thread, /* Thread function. */
61  this); /* Thread parameter. */
62 
63  // setup the uavcan thread - this will call tasks at 1kHz
64 #if HAL_WITH_UAVCAN
65  _uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa,
66  sizeof(_uavcan_thread_wa),
67  APM_UAVCAN_PRIORITY, /* Initial priority. */
68  _uavcan_thread, /* Thread function. */
69  this); /* Thread parameter. */
70 #endif
71  // setup the RCIN thread - this will call tasks at 1kHz
72  _rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
73  sizeof(_rcin_thread_wa),
74  APM_RCIN_PRIORITY, /* Initial priority. */
75  _rcin_thread, /* Thread function. */
76  this); /* Thread parameter. */
77 
78  // the toneAlarm thread runs at a medium priority
79 #ifdef HAL_PWM_ALARM
80  _toneAlarm_thread_ctx = chThdCreateStatic(_toneAlarm_thread_wa,
81  sizeof(_toneAlarm_thread_wa),
82  APM_TONEALARM_PRIORITY, /* Initial priority. */
83  _toneAlarm_thread, /* Thread function. */
84  this); /* Thread parameter. */
85 #endif
86  // the IO thread runs at lower priority
87  _io_thread_ctx = chThdCreateStatic(_io_thread_wa,
88  sizeof(_io_thread_wa),
89  APM_IO_PRIORITY, /* Initial priority. */
90  _io_thread, /* Thread function. */
91  this); /* Thread parameter. */
92 
93  // the storage thread runs at just above IO priority
94  _storage_thread_ctx = chThdCreateStatic(_storage_thread_wa,
95  sizeof(_storage_thread_wa),
96  APM_STORAGE_PRIORITY, /* Initial priority. */
97  _storage_thread, /* Thread function. */
98  this); /* Thread parameter. */
99 }
100 
101 
102 void Scheduler::delay_microseconds(uint16_t usec)
103 {
104  if (usec == 0) { //chibios faults with 0us sleep
105  return;
106  }
107  uint32_t ticks;
108  if (usec >= 4096) {
109  // we need to use 64 bit calculations for tick conversions
110  ticks = US2ST64(usec);
111  } else {
112  ticks = US2ST(usec);
113  }
114  if (ticks == 0) {
115  // calling with ticks == 0 causes a hard fault on ChibiOS
116  ticks = 1;
117  }
118  chThdSleep(ticks); //Suspends Thread for desired microseconds
119 }
120 
121 /*
122  wrapper around sem_post that boosts main thread priority
123  */
124 static void set_high_priority()
125 {
126 #if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
128 #endif
129 }
130 
131 /*
132  return the main thread to normal priority
133  */
135 {
136 #if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
138  _priority_boosted = false;
140  }
141 #endif
142 }
143 
144 /*
145  a variant of delay_microseconds that boosts priority to
146  APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
147  microseconds when the time completes. This significantly improves
148  the regularity of timing of the main loop
149  */
151 {
152  if (in_main_thread()) {
154  _priority_boosted = true;
155  }
156  delay_microseconds(usec); //Suspends Thread for desired microseconds
157  _called_boost = true;
158 }
159 
160 /*
161  return true if delay_microseconds_boost() has been called since last check
162  */
164 {
165  if (!_called_boost) {
166  return false;
167  }
168  _called_boost = false;
169  return true;
170 }
171 
172 void Scheduler::delay(uint16_t ms)
173 {
174  if (!in_main_thread()) {
175  //chprintf("ERROR: delay() from timer process\n");
176  return;
177  }
178  uint64_t start = AP_HAL::micros64();
179 
180  while ((AP_HAL::micros64() - start)/1000 < ms) {
181  delay_microseconds(1000);
182  if (_min_delay_cb_ms <= ms) {
183  call_delay_cb();
184  }
185  }
186 }
187 
188 void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
189 {
190  for (uint8_t i = 0; i < _num_timer_procs; i++) {
191  if (_timer_proc[i] == proc) {
192  return;
193  }
194  }
195 
196  if (_num_timer_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
198  _num_timer_procs++;
199  } else {
200  hal.console->printf("Out of timer processes\n");
201  }
202 }
203 
204 void Scheduler::register_io_process(AP_HAL::MemberProc proc)
205 {
206  for (uint8_t i = 0; i < _num_io_procs; i++) {
207  if (_io_proc[i] == proc) {
208  return;
209  }
210  }
211 
212  if (_num_io_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
213  _io_proc[_num_io_procs] = proc;
214  _num_io_procs++;
215  } else {
216  hal.console->printf("Out of IO processes\n");
217  }
218 }
219 
220 void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
221 {
222  _failsafe = failsafe;
223 }
224 
226 {
227  _timer_suspended = true;
228 }
229 
231 {
232  _timer_suspended = false;
233  if (_timer_event_missed == true) {
234  _run_timers(false);
235  _timer_event_missed = false;
236  }
237 }
238 extern void Reset_Handler();
239 void Scheduler::reboot(bool hold_in_bootloader)
240 {
241  // disarm motors to ensure they are off during a bootloader upload
242  hal.rcout->force_safety_on();
244 
245  // stop sdcard driver, if active
246  sdcard_stop();
247 
248  // lock all shared DMA channels. This has the effect of waiting
249  // till the sensor buses are idle
251 
252  // disable interrupts
254 
255  // wait for 1ms to ensure all pending DMAs are complete
256  uint32_t start_us = AP_HAL::micros();
257  while (AP_HAL::micros() - start_us < 1000) ; // busy loop
258 
259  // reboot
260  NVIC_SystemReset();
261 }
262 
263 void Scheduler::_run_timers(bool called_from_timer_thread)
264 {
265  if (_in_timer_proc) {
266  return;
267  }
268  _in_timer_proc = true;
269 
270  if (!_timer_suspended) {
271  // now call the timer based drivers
272  for (int i = 0; i < _num_timer_procs; i++) {
273  if (_timer_proc[i]) {
274  _timer_proc[i]();
275  }
276  }
277  } else if (called_from_timer_thread) {
278  _timer_event_missed = true;
279  }
280 
281  // and the failsafe, if one is setup
282  if (_failsafe != nullptr) {
283  _failsafe();
284  }
285 
286 #if HAL_USE_ADC == TRUE
287  // process analog input
288  ((AnalogIn *)hal.analogin)->_timer_tick();
289 #endif
290 
291  _in_timer_proc = false;
292 }
293 
295 {
296  Scheduler *sched = (Scheduler *)arg;
297  chRegSetThreadName("apm_timer");
298 
299  while (!sched->_hal_initialized) {
300  sched->delay_microseconds(1000);
301  }
302  while (true) {
303  sched->delay_microseconds(1000);
304 
305  // run registered timers
306  sched->_run_timers(true);
307 
308  // process any pending RC output requests
309  hal.rcout->timer_tick();
310  }
311 }
312 #if HAL_WITH_UAVCAN
313 void Scheduler::_uavcan_thread(void *arg)
314 {
315  Scheduler *sched = (Scheduler *)arg;
316  chRegSetThreadName("apm_uavcan");
317  while (!sched->_hal_initialized) {
318  sched->delay_microseconds(20000);
319  }
320  while (true) {
321  sched->delay_microseconds(100);
322  for (int i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
323  if(hal.can_mgr[i] != nullptr) {
324  CANManager::from(hal.can_mgr[i])->_timer_tick();
325  }
326  }
327  }
328 }
329 #endif
330 
331 void Scheduler::_rcin_thread(void *arg)
332 {
333  Scheduler *sched = (Scheduler *)arg;
334  chRegSetThreadName("apm_rcin");
335  while (!sched->_hal_initialized) {
336  sched->delay_microseconds(20000);
337  }
338  while (true) {
339  sched->delay_microseconds(2500);
340  ((RCInput *)hal.rcin)->_timer_tick();
341  }
342 }
343 #ifdef HAL_PWM_ALARM
344 
345 void Scheduler::_toneAlarm_thread(void *arg)
346 {
347  Scheduler *sched = (Scheduler *)arg;
348  chRegSetThreadName("toneAlarm");
349  while (!sched->_hal_initialized) {
350  sched->delay_microseconds(20000);
351  }
352  while (true) {
353  sched->delay_microseconds(20000);
354 
355  // process tone command
357  }
358 }
359 #endif
361 {
362  if (_in_io_proc) {
363  return;
364  }
365  _in_io_proc = true;
366 
367  if (!_timer_suspended) {
368  // now call the IO based drivers
369  for (int i = 0; i < _num_io_procs; i++) {
370  if (_io_proc[i]) {
371  _io_proc[i]();
372  }
373  }
374  }
375 
376  _in_io_proc = false;
377 }
378 
379 void Scheduler::_io_thread(void* arg)
380 {
381  Scheduler *sched = (Scheduler *)arg;
382  chRegSetThreadName("apm_io");
383  while (!sched->_hal_initialized) {
384  sched->delay_microseconds(1000);
385  }
386  while (true) {
387  sched->delay_microseconds(1000);
388 
389  // run registered IO processes
390  sched->_run_io();
391  }
392 }
393 
395 {
396  Scheduler *sched = (Scheduler *)arg;
397  chRegSetThreadName("apm_storage");
398  while (!sched->_hal_initialized) {
399  sched->delay_microseconds(10000);
400  }
401  while (true) {
402  sched->delay_microseconds(10000);
403 
404  // process any pending storage writes
405  hal.storage->_timer_tick();
406  }
407 }
408 
410 {
411  return get_main_thread() == chThdGetSelfX();
412 }
413 
415 {
416  if (_initialized) {
417  AP_HAL::panic("PANIC: scheduler::system_initialized called"
418  "more than once");
419  }
420  _initialized = true;
421 }
422 
423 /*
424  disable interrupts and return a context that can be used to
425  restore the interrupt state. This can be used to protect
426  critical regions
427 */
429 {
430  return (void *)(uintptr_t)chSysGetStatusAndLockX();
431 }
432 
433 /*
434  restore interrupt state from disable_interrupts_save()
435 */
437 {
438  chSysRestoreStatusX((syssts_t)(uintptr_t)state);
439 }
440 
441 #endif // CH_CFG_USE_DYNAMIC
#define APM_RCIN_PRIORITY
Definition: Scheduler.h:27
void suspend_timer_procs() override
Definition: Scheduler.cpp:225
void resume_timer_procs() override
Definition: Scheduler.cpp:230
virtual void force_safety_no_wait(void)
Definition: RCOutput.h:103
void delay_microseconds_boost(uint16_t us) override
Definition: Scheduler.cpp:150
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define APM_UAVCAN_PRIORITY
Definition: Scheduler.h:48
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual void _toneAlarm_timer_tick()
Definition: Util.h:80
thread_t * _rcin_thread_ctx
Definition: Scheduler.h:118
#define APM_MAIN_PRIORITY_BOOST
Definition: Scheduler.h:38
#define APM_MAIN_PRIORITY
Definition: Scheduler.h:25
void restore_interrupts(void *) override
Definition: Scheduler.cpp:436
volatile bool _timer_event_missed
Definition: Scheduler.h:115
AP_HAL::Util * util
Definition: HAL.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)
thread_t * get_main_thread()
static void _toneAlarm_thread(void *arg)
#define APM_IO_PRIORITY
Definition: Scheduler.h:31
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
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
#define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:23
void sdcard_stop(void)
Definition: sdcard.cpp:95
void hal_chibios_set_priority(uint8_t priority)
void delay(uint16_t ms) override
Definition: Scheduler.cpp:172
virtual void _timer_tick(void)
Definition: Storage.h:11
static void set_high_priority()
Definition: Scheduler.cpp:124
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool in_main_thread() const override
Definition: Scheduler.cpp:409
static void _timer_thread(void *arg)
Definition: Scheduler.cpp:294
virtual void timer_tick(void)
Definition: RCOutput.h:132
uint8_t _num_timer_procs
Definition: Scheduler.h:108
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
AP_HAL::Storage * storage
Definition: HAL.h:109
static void _rcin_thread(void *arg)
Definition: Scheduler.cpp:331
uint64_t micros64()
Definition: system.cpp:162
static int state
Definition: Util.cpp:20
thread_t * _toneAlarm_thread_ctx
Definition: Scheduler.h:121
#define APM_TONEALARM_PRIORITY
Definition: Scheduler.h:28
void _run_io(void)
Definition: Scheduler.cpp:360
virtual void call_delay_cb()
Definition: Scheduler.cpp:12
static Util * from(AP_HAL::Util *util)
Definition: Util.h:29
virtual bool force_safety_on(void)
Definition: RCOutput.h:93
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:88
thread_t * _storage_thread_ctx
Definition: Scheduler.h:120
static void lock_all(void)
Definition: shared_dma.cpp:182
void Reset_Handler()
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::RCOutput * rcout
Definition: HAL.h:113
#define APM_STORAGE_PRIORITY
Definition: Scheduler.h:30
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 panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_HAL::RCInput * rcin
Definition: HAL.h:112
#define APM_TIMER_PRIORITY
Definition: Scheduler.h:26
THD_WORKING_AREA(_timer_thread_wa, 2048)
void delay_microseconds(uint16_t us) override
Definition: Scheduler.cpp:102
uint32_t micros()
Definition: system.cpp:152
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
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108