APM:Libraries
Scheduler.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
3 
4 #include "AP_HAL_PX4.h"
5 #include "Scheduler.h"
6 
7 #include <unistd.h>
8 #include <stdlib.h>
9 #include <sched.h>
10 #include <errno.h>
11 #include <stdio.h>
12 #include <drivers/drv_hrt.h>
13 #include <nuttx/arch.h>
14 #include <systemlib/systemlib.h>
15 #include <pthread.h>
16 #include <poll.h>
17 
18 #include "UARTDriver.h"
19 #include "AnalogIn.h"
20 #include "Storage.h"
21 #include "RCOutput.h"
22 #include "RCInput.h"
23 
26 
27 #if HAL_WITH_UAVCAN
28 #include "CAN.h"
29 #include <AP_UAVCAN/AP_UAVCAN.h>
30 #endif
31 
32 using namespace PX4;
33 
34 extern const AP_HAL::HAL& hal;
35 
36 extern bool _px4_thread_should_exit;
37 
39  _perf_timers(perf_alloc(PC_ELAPSED, "APM_timers")),
40  _perf_io_timers(perf_alloc(PC_ELAPSED, "APM_IO_timers")),
41  _perf_storage_timer(perf_alloc(PC_ELAPSED, "APM_storage_timers")),
42  _perf_delay(perf_alloc(PC_ELAPSED, "APM_delay"))
43 {}
44 
46 {
47  _main_task_pid = getpid();
48 
49  // setup the timer thread - this will call tasks at 1kHz
50  pthread_attr_t thread_attr;
51  struct sched_param param;
52 
53  pthread_attr_init(&thread_attr);
54  pthread_attr_setstacksize(&thread_attr, 2048);
55 
56  param.sched_priority = APM_TIMER_PRIORITY;
57  (void)pthread_attr_setschedparam(&thread_attr, &param);
58  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
59 
60  pthread_create(&_timer_thread_ctx, &thread_attr, &PX4Scheduler::_timer_thread, this);
61 
62  // the UART thread runs at a medium priority
63  pthread_attr_init(&thread_attr);
64  pthread_attr_setstacksize(&thread_attr, 2048);
65 
66  param.sched_priority = APM_UART_PRIORITY;
67  (void)pthread_attr_setschedparam(&thread_attr, &param);
68  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
69 
70  pthread_create(&_uart_thread_ctx, &thread_attr, &PX4Scheduler::_uart_thread, this);
71 
72  // the IO thread runs at lower priority
73  pthread_attr_init(&thread_attr);
74  pthread_attr_setstacksize(&thread_attr, 2048);
75 
76  param.sched_priority = APM_IO_PRIORITY;
77  (void)pthread_attr_setschedparam(&thread_attr, &param);
78  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
79 
80  pthread_create(&_io_thread_ctx, &thread_attr, &PX4Scheduler::_io_thread, this);
81 
82  // the storage thread runs at just above IO priority
83  pthread_attr_init(&thread_attr);
84  pthread_attr_setstacksize(&thread_attr, 1024);
85 
86  param.sched_priority = APM_STORAGE_PRIORITY;
87  (void)pthread_attr_setschedparam(&thread_attr, &param);
88  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
89 
90  pthread_create(&_storage_thread_ctx, &thread_attr, &PX4Scheduler::_storage_thread, this);
91 }
92 
94 {
95 #if HAL_WITH_UAVCAN
96  pthread_attr_t thread_attr;
97  struct sched_param param;
98 
99  //the UAVCAN thread runs at medium priority
100  pthread_attr_init(&thread_attr);
101  pthread_attr_setstacksize(&thread_attr, 8192);
102 
103  param.sched_priority = APM_CAN_PRIORITY;
104  (void) pthread_attr_setschedparam(&thread_attr, &param);
105  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
106 
107  for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
108  if (hal.can_mgr[i] != nullptr) {
109  if (hal.can_mgr[i]->get_UAVCAN() != nullptr) {
111  arg->sched = this;
112  arg->uavcan_number = i;
113 
114  pthread_create(&_uavcan_thread_ctx, &thread_attr, &PX4Scheduler::_uavcan_thread, arg);
115  }
116  }
117  }
118 #endif
119 }
120 
125 {
126  sem_t wait_semaphore;
127  struct hrt_call wait_call;
128  sem_init(&wait_semaphore, 0, 0);
129  memset(&wait_call, 0, sizeof(wait_call));
130  hrt_call_after(&wait_call, usec, (hrt_callout)sem_post, &wait_semaphore);
131  sem_wait(&wait_semaphore);
132 }
133 
135 {
136  perf_begin(_perf_delay);
138  perf_end(_perf_delay);
139 }
140 
141 /*
142  wrapper around sem_post that boosts main thread priority
143  */
144 static void sem_post_boost(sem_t *sem)
145 {
147  sem_post(sem);
148 }
149 
150 /*
151  return the main thread to normal priority
152  */
153 static void set_normal_priority(void *sem)
154 {
156 }
157 
158 /*
159  a variant of delay_microseconds that boosts priority to
160  APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
161  microseconds when the time completes. This significantly improves
162  the regularity of timing of the main loop as it takes
163  */
165 {
166  sem_t wait_semaphore;
167  static struct hrt_call wait_call;
168  sem_init(&wait_semaphore, 0, 0);
169  hrt_call_after(&wait_call, usec, (hrt_callout)sem_post_boost, &wait_semaphore);
170  sem_wait(&wait_semaphore);
171  hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, nullptr);
172 }
173 
174 void PX4Scheduler::delay(uint16_t ms)
175 {
176  if (!in_main_thread()) {
177  ::printf("ERROR: delay() from timer process\n");
178  return;
179  }
180  perf_begin(_perf_delay);
181  uint64_t start = AP_HAL::micros64();
182 
183  while ((AP_HAL::micros64() - start)/1000 < ms &&
186  if (_min_delay_cb_ms <= ms) {
187  call_delay_cb();
188  }
189  }
190  perf_end(_perf_delay);
192  exit(1);
193  }
194 }
195 
196 void PX4Scheduler::register_timer_process(AP_HAL::MemberProc proc)
197 {
198  for (uint8_t i = 0; i < _num_timer_procs; i++) {
199  if (_timer_proc[i] == proc) {
200  return;
201  }
202  }
203 
204  if (_num_timer_procs < PX4_SCHEDULER_MAX_TIMER_PROCS) {
206  _num_timer_procs++;
207  } else {
208  hal.console->printf("Out of timer processes\n");
209  }
210 }
211 
212 void PX4Scheduler::register_io_process(AP_HAL::MemberProc proc)
213 {
214  for (uint8_t i = 0; i < _num_io_procs; i++) {
215  if (_io_proc[i] == proc) {
216  return;
217  }
218  }
219 
220  if (_num_io_procs < PX4_SCHEDULER_MAX_TIMER_PROCS) {
221  _io_proc[_num_io_procs] = proc;
222  _num_io_procs++;
223  } else {
224  hal.console->printf("Out of IO processes\n");
225  }
226 }
227 
228 void PX4Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
229 {
230  _failsafe = failsafe;
231 }
232 
234 {
235  _timer_suspended = true;
236 }
237 
239 {
240  _timer_suspended = false;
241  if (_timer_event_missed == true) {
242  _run_timers(false);
243  _timer_event_missed = false;
244  }
245 }
246 
247 void PX4Scheduler::reboot(bool hold_in_bootloader)
248 {
249  // disarm motors to ensure they are off during a bootloader upload
250  hal.rcout->force_safety_on();
252 
253  // delay to ensure the async force_saftey operation completes
254  delay(500);
255 
256  px4_systemreset(hold_in_bootloader);
257 }
258 
259 void PX4Scheduler::_run_timers(bool called_from_timer_thread)
260 {
261  if (_in_timer_proc) {
262  return;
263  }
264  _in_timer_proc = true;
265 
266  if (!_timer_suspended) {
267  // now call the timer based drivers
268  for (int i = 0; i < _num_timer_procs; i++) {
269  if (_timer_proc[i]) {
270  _timer_proc[i]();
271  }
272  }
273  } else if (called_from_timer_thread) {
274  _timer_event_missed = true;
275  }
276 
277  // and the failsafe, if one is setup
278  if (_failsafe != nullptr) {
279  _failsafe();
280  }
281 
282  // process analog input
283  ((PX4AnalogIn *)hal.analogin)->_timer_tick();
284 
285  _in_timer_proc = false;
286 }
287 
288 extern bool px4_ran_overtime;
289 
291 {
292  PX4Scheduler *sched = (PX4Scheduler *)arg;
293  uint32_t last_ran_overtime = 0;
294 
295  pthread_setname_np(pthread_self(), "apm_timer");
296 
297  while (!sched->_hal_initialized) {
298  poll(nullptr, 0, 1);
299  }
300  while (!_px4_thread_should_exit) {
301  sched->delay_microseconds_semaphore(1000);
302 
303  // run registered timers
304  perf_begin(sched->_perf_timers);
305  sched->_run_timers(true);
306  perf_end(sched->_perf_timers);
307 
308  // process any pending RC output requests
309  hal.rcout->timer_tick();
310 
311  // process any pending RC input requests
312  ((PX4RCInput *)hal.rcin)->_timer_tick();
313 
314  if (px4_ran_overtime && AP_HAL::millis() - last_ran_overtime > 2000) {
315  last_ran_overtime = AP_HAL::millis();
316 #if 0
317  printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
318  hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
319 #endif
320  }
321  }
322  return nullptr;
323 }
324 
326 {
327  if (_in_io_proc) {
328  return;
329  }
330  _in_io_proc = true;
331 
332  if (!_timer_suspended) {
333  // now call the IO based drivers
334  for (int i = 0; i < _num_io_procs; i++) {
335  if (_io_proc[i]) {
336  _io_proc[i]();
337  }
338  }
339  }
340 
341  _in_io_proc = false;
342 }
343 
345 {
346  PX4Scheduler *sched = (PX4Scheduler *)arg;
347 
348  pthread_setname_np(pthread_self(), "apm_uart");
349 
350  while (!sched->_hal_initialized) {
351  poll(nullptr, 0, 1);
352  }
353  while (!_px4_thread_should_exit) {
354  sched->delay_microseconds_semaphore(1000);
355 
356  // process any pending serial bytes
357  hal.uartA->_timer_tick();
358  hal.uartB->_timer_tick();
359  hal.uartC->_timer_tick();
360  hal.uartD->_timer_tick();
361  hal.uartE->_timer_tick();
362  hal.uartF->_timer_tick();
363  }
364  return nullptr;
365 }
366 
367 void *PX4Scheduler::_io_thread(void *arg)
368 {
369  PX4Scheduler *sched = (PX4Scheduler *)arg;
370 
371  pthread_setname_np(pthread_self(), "apm_io");
372 
373  while (!sched->_hal_initialized) {
374  poll(nullptr, 0, 1);
375  }
376  while (!_px4_thread_should_exit) {
377  sched->delay_microseconds_semaphore(1000);
378 
379  // run registered IO processes
380  perf_begin(sched->_perf_io_timers);
381  sched->_run_io();
382  perf_end(sched->_perf_io_timers);
383  }
384  return nullptr;
385 }
386 
388 {
389  PX4Scheduler *sched = (PX4Scheduler *)arg;
390 
391  pthread_setname_np(pthread_self(), "apm_storage");
392 
393  while (!sched->_hal_initialized) {
394  poll(nullptr, 0, 1);
395  }
396  while (!_px4_thread_should_exit) {
397  sched->delay_microseconds_semaphore(10000);
398 
399  // process any pending storage writes
400  perf_begin(sched->_perf_storage_timer);
401  hal.storage->_timer_tick();
402  perf_end(sched->_perf_storage_timer);
403  }
404  return nullptr;
405 }
406 
407 #if HAL_WITH_UAVCAN
408 void *PX4Scheduler::_uavcan_thread(void *arg)
409 {
410  PX4Scheduler *sched = ((_uavcan_thread_arg *) arg)->sched;
411  uint8_t uavcan_number = ((_uavcan_thread_arg *) arg)->uavcan_number;
412 
413  char name[15];
414  snprintf(name, sizeof(name), "apm_uavcan:%u", uavcan_number);
415  pthread_setname_np(pthread_self(), name);
416 
417  while (!sched->_hal_initialized) {
418  poll(nullptr, 0, 1);
419  }
420 
421  while (!_px4_thread_should_exit) {
422  if (((PX4CANManager *)hal.can_mgr[uavcan_number])->is_initialized()) {
423  if (((PX4CANManager *)hal.can_mgr[uavcan_number])->get_UAVCAN() != nullptr) {
424  (((PX4CANManager *)hal.can_mgr[uavcan_number])->get_UAVCAN())->do_cyclic();
425  } else {
426  sched->delay_microseconds_semaphore(10000);
427  }
428  } else {
429  sched->delay_microseconds_semaphore(10000);
430  }
431  }
432 
433  return nullptr;
434 }
435 #endif
436 
438 {
439  return getpid() == _main_task_pid;
440 }
441 
443 {
444  if (_initialized) {
445  AP_HAL::panic("PANIC: scheduler::system_initialized called"
446  "more than once");
447  }
448  _initialized = true;
449 }
450 
451 
452 /*
453  disable interrupts and return a context that can be used to
454  restore the interrupt state. This can be used to protect
455  critical regions
456 */
458 {
459  return (void *)(uintptr_t)irqsave();
460 }
461 
462 /*
463  restore interrupt state from disable_interrupts_save()
464 */
466 {
467  irqrestore((irqstate_t)(uintptr_t)state);
468 }
469 
470 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
uint8_t _num_io_procs
Definition: Scheduler.h:92
bool in_main_thread() const override
Definition: Scheduler.cpp:437
static void set_normal_priority(void *sem)
Definition: Scheduler.cpp:153
uint8_t _num_timer_procs
Definition: Scheduler.h:88
virtual void force_safety_no_wait(void)
Definition: RCOutput.h:103
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
volatile bool _timer_suspended
Definition: Scheduler.h:85
pthread_t _uart_thread_ctx
Definition: Scheduler.h:101
#define APM_UART_PRIORITY
Definition: Scheduler.h:29
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define PX4_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:11
pthread_t _timer_thread_ctx
Definition: Scheduler.h:98
#define APM_MAIN_PRIORITY_BOOST
Definition: Scheduler.h:38
static int8_t current_task
Definition: AP_Scheduler.h:143
#define APM_MAIN_PRIORITY
Definition: Scheduler.h:25
perf_counter_t _perf_delay
Definition: Scheduler.h:123
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:82
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
void(* Proc)(void)
perf_counter_t _perf_timers
Definition: Scheduler.h:120
#define APM_IO_PRIORITY
Definition: Scheduler.h:31
const char * name
Definition: BusTest.cpp:11
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
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
virtual void _timer_tick(void)
Definition: UARTDriver.h:72
void create_uavcan_thread() override
Definition: Scheduler.cpp:93
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
virtual void _timer_tick(void)
Definition: Storage.h:11
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
static void * _uart_thread(void *arg)
Definition: Scheduler.cpp:344
void * disable_interrupts_save(void) override
Definition: Scheduler.cpp:457
virtual void timer_tick(void)
Definition: RCOutput.h:132
void _run_timers(bool called_from_timer_thread)
Definition: Scheduler.cpp:259
AP_HAL::UARTDriver * uartF
Definition: HAL.h:105
uint32_t millis()
Definition: system.cpp:157
AP_HAL::UARTDriver * uartD
Definition: HAL.h:103
AP_HAL::Storage * storage
Definition: HAL.h:109
pthread_t _uavcan_thread_ctx
Definition: Scheduler.h:102
uint64_t micros64()
Definition: system.cpp:162
static int state
Definition: Util.cpp:20
void _run_io(void)
Definition: Scheduler.cpp:325
void reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:247
virtual void call_delay_cb()
Definition: Scheduler.cpp:12
bool px4_ran_overtime
#define APM_MAIN_PRIORITY_BOOST_USEC
Definition: Scheduler.h:39
pthread_t _storage_thread_ctx
Definition: Scheduler.h:100
virtual bool force_safety_on(void)
Definition: RCOutput.h:93
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
void hal_px4_set_priority(uint8_t priority)
static void * _io_thread(void *arg)
Definition: Scheduler.cpp:367
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
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
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
volatile bool _timer_event_missed
Definition: Scheduler.h:95
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
void resume_timer_procs()
Definition: Scheduler.cpp:238
#define APM_STORAGE_PRIORITY
Definition: Scheduler.h:30
AP_HAL::MemberProc _timer_proc[PX4_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:87
static void sem_post_boost(sem_t *sem)
Definition: Scheduler.cpp:144
void register_io_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:212
void delay_microseconds_semaphore(uint16_t us)
Definition: Scheduler.cpp:124
bool _px4_thread_should_exit
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
void delay_microseconds_boost(uint16_t us)
Definition: Scheduler.cpp:164
#define APM_CAN_PRIORITY
Definition: Scheduler.h:52
void restore_interrupts(void *) override
Definition: Scheduler.cpp:465
volatile bool _in_io_proc
Definition: Scheduler.h:93
static const AP_HAL::HAL & hal
Definition: Device.cpp:29
AP_HAL::MemberProc _io_proc[PX4_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:91
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
void delay(uint16_t ms)
Definition: Scheduler.cpp:174