APM:Libraries
Scheduler.cpp
Go to the documentation of this file.
1 #include "Scheduler.h"
2 
3 #include <algorithm>
4 #include <errno.h>
5 #include <poll.h>
6 #include <stdio.h>
7 #include <stdlib.h>
8 #include <sys/mman.h>
9 #include <sys/time.h>
10 #include <unistd.h>
11 
12 #include <AP_HAL/AP_HAL.h>
14 
15 #include "RCInput.h"
16 #include "SPIUARTDriver.h"
17 #include "Storage.h"
18 #include "UARTDriver.h"
19 #include "Util.h"
20 
21 #if HAL_WITH_UAVCAN
22 #include "CAN.h"
23 #endif
24 
25 using namespace Linux;
26 
27 extern const AP_HAL::HAL& hal;
28 
29 #define APM_LINUX_TIMER_PRIORITY 15
30 #define APM_LINUX_UART_PRIORITY 14
31 #define APM_LINUX_RCIN_PRIORITY 13
32 #define APM_LINUX_MAIN_PRIORITY 12
33 #define APM_LINUX_TONEALARM_PRIORITY 11
34 #define APM_LINUX_IO_PRIORITY 10
35 
36 #define APM_LINUX_TIMER_RATE 1000
37 #define APM_LINUX_UART_RATE 100
38 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
39  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
40  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
41  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
42  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
43 #define APM_LINUX_RCIN_RATE 2000
44 #define APM_LINUX_TONEALARM_RATE 100
45 #define APM_LINUX_IO_RATE 50
46 #else
47 #define APM_LINUX_RCIN_RATE 100
48 #define APM_LINUX_TONEALARM_RATE 100
49 #define APM_LINUX_IO_RATE 50
50 #endif
51 
52 #define SCHED_THREAD(name_, UPPER_NAME_) \
53  { \
54  .name = "ap-" #name_, \
55  .thread = &_##name_##_thread, \
56  .policy = SCHED_FIFO, \
57  .prio = APM_LINUX_##UPPER_NAME_##_PRIORITY, \
58  .rate = APM_LINUX_##UPPER_NAME_##_RATE, \
59  }
60 
62 { }
63 
65 {
66  int ret;
67  const struct sched_table {
68  const char *name;
69  SchedulerThread *thread;
70  int policy;
71  int prio;
72  uint32_t rate;
73  } sched_table[] = {
74  SCHED_THREAD(timer, TIMER),
75  SCHED_THREAD(uart, UART),
76  SCHED_THREAD(rcin, RCIN),
77  SCHED_THREAD(tonealarm, TONEALARM),
78  SCHED_THREAD(io, IO),
79  };
80 
81  _main_ctx = pthread_self();
82 
83 #if !APM_BUILD_TYPE(APM_BUILD_Replay)
84  // we don't run Replay in real-time...
85  mlockall(MCL_CURRENT|MCL_FUTURE);
86 
87  struct sched_param param = { .sched_priority = APM_LINUX_MAIN_PRIORITY };
88  if (sched_setscheduler(0, SCHED_FIFO, &param) == -1) {
89  AP_HAL::panic("Scheduler: failed to set scheduling parameters: %s",
90  strerror(errno));
91  }
92 #endif
93 
94  /* set barrier to N + 1 threads: worker threads + main */
95  unsigned n_threads = ARRAY_SIZE(sched_table) + 1;
96  ret = pthread_barrier_init(&_initialized_barrier, nullptr, n_threads);
97  if (ret) {
98  AP_HAL::panic("Scheduler: Failed to initialise barrier object: %s",
99  strerror(ret));
100  }
101 
102  for (size_t i = 0; i < ARRAY_SIZE(sched_table); i++) {
103  const struct sched_table *t = &sched_table[i];
104 
105  t->thread->set_rate(t->rate);
106  t->thread->set_stack_size(1024 * 1024);
107  t->thread->start(t->name, t->policy, t->prio);
108  }
109 
110 #if defined(DEBUG_STACK) && DEBUG_STACK
112 #endif
113 }
114 
116 {
117  uint64_t now = AP_HAL::millis64();
118 
119  if (now - _last_stack_debug_msec > 5000) {
120  fprintf(stderr, "Stack Usage:\n"
121  "\ttimer = %zu\n"
122  "\tio = %zu\n"
123  "\trcin = %zu\n"
124  "\tuart = %zu\n"
125  "\ttone = %zu\n",
132  }
133 }
134 
135 void Scheduler::microsleep(uint32_t usec)
136 {
137  struct timespec ts;
138  ts.tv_sec = 0;
139  ts.tv_nsec = usec*1000UL;
140  while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ;
141 }
142 
143 void Scheduler::delay(uint16_t ms)
144 {
145  if (_stopped_clock_usec) {
146  return;
147  }
148 
149  if (!in_main_thread()) {
150  fprintf(stderr, "Scheduler::delay() called outside main thread\n");
151  return;
152  }
153 
154  uint64_t start = AP_HAL::millis64();
155 
156  while ((AP_HAL::millis64() - start) < ms) {
157  // this yields the CPU to other apps
158  microsleep(1000);
159  if (_min_delay_cb_ms <= ms) {
160  call_delay_cb();
161  }
162  }
163 }
164 
166 {
167  if (_stopped_clock_usec) {
168  return;
169  }
170  microsleep(us);
171 }
172 
173 void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
174 {
175  for (uint8_t i = 0; i < _num_timer_procs; i++) {
176  if (_timer_proc[i] == proc) {
177  return;
178  }
179  }
180 
181  if (_num_timer_procs >= LINUX_SCHEDULER_MAX_TIMER_PROCS) {
182  hal.console->printf("Out of timer processes\n");
183  return;
184  }
185 
187  _num_timer_procs++;
188 }
189 
190 void Scheduler::register_io_process(AP_HAL::MemberProc proc)
191 {
192  for (uint8_t i = 0; i < _num_io_procs; i++) {
193  if (_io_proc[i] == proc) {
194  return;
195  }
196  }
197 
198  if (_num_io_procs < LINUX_SCHEDULER_MAX_IO_PROCS) {
199  _io_proc[_num_io_procs] = proc;
200  _num_io_procs++;
201  } else {
202  hal.console->printf("Out of IO processes\n");
203  }
204 }
205 
206 void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
207 {
208  _failsafe = failsafe;
209 }
210 
212 {
214  printf("Failed to take timer semaphore\n");
215  }
216 }
217 
219 {
221 }
222 
224 {
225  int i;
226 
227  if (_in_timer_proc) {
228  return;
229  }
230  _in_timer_proc = true;
231 
233  printf("Failed to take timer semaphore in %s\n", __PRETTY_FUNCTION__);
234  return;
235  }
236 
237  // now call the timer based drivers
238  for (i = 0; i < _num_timer_procs; i++) {
239  if (_timer_proc[i]) {
240  _timer_proc[i]();
241  }
242  }
243 
245 
246  // and the failsafe, if one is setup
247  if (_failsafe != nullptr) {
248  _failsafe();
249  }
250 
251  _in_timer_proc = false;
252 
253 #if HAL_WITH_UAVCAN
254 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
255  for (i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
256  if(hal.can_mgr[i] != nullptr) {
258  }
259  }
260 #endif
261 #endif
262 }
263 
265 {
267  return;
268  }
269 
270  // now call the IO based drivers
271  for (int i = 0; i < _num_io_procs; i++) {
272  if (_io_proc[i]) {
273  _io_proc[i]();
274  }
275  }
276 
278 }
279 
280 /*
281  run timers for all UARTs
282  */
284 {
285  // process any pending serial bytes
286  hal.uartA->_timer_tick();
287  hal.uartB->_timer_tick();
288  hal.uartC->_timer_tick();
289  hal.uartD->_timer_tick();
290  hal.uartE->_timer_tick();
291  hal.uartF->_timer_tick();
292 }
293 
295 {
297 }
298 
300 {
301  _run_uarts();
302 }
303 
305 {
306  // process tone command
308 }
309 
311 {
312  // process any pending storage writes
313  hal.storage->_timer_tick();
314 
315  // run registered IO processes
316  _run_io();
317 }
318 
320 {
321  return pthread_equal(pthread_self(), _main_ctx);
322 }
323 
325 {
326  int r = pthread_barrier_wait(&_initialized_barrier);
327  if (r == PTHREAD_BARRIER_SERIAL_THREAD) {
328  pthread_barrier_destroy(&_initialized_barrier);
329  }
330 }
331 
333 {
334  if (_initialized) {
335  AP_HAL::panic("PANIC: scheduler::system_initialized called more than once");
336  }
337 
338  _initialized = true;
339 
341 }
342 
343 void Scheduler::reboot(bool hold_in_bootloader)
344 {
345  exit(1);
346 }
347 
348 void Scheduler::stop_clock(uint64_t time_usec)
349 {
350  if (time_usec >= _stopped_clock_usec) {
351  _stopped_clock_usec = time_usec;
352  _run_io();
353  }
354 }
355 
357 {
358  _sched._wait_all_threads();
359 
360  return PeriodicThread::_run();
361 }
362 
364 {
366  _io_thread.stop();
367  _rcin_thread.stop();
368  _uart_thread.stop();
370 
372  _io_thread.join();
373  _rcin_thread.join();
374  _uart_thread.join();
376 }
bool join()
Definition: Thread.cpp:208
int printf(const char *fmt,...)
Definition: stdio.c:113
AP_HAL::MemberProc _timer_proc[LINUX_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:75
void _toneAlarm_timer_tick()
Definition: Util.cpp:76
uint64_t _last_stack_debug_msec
Definition: Scheduler.h:98
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
void microsleep(uint32_t usec)
Definition: Scheduler.cpp:135
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define APM_LINUX_MAIN_PRIORITY
Definition: Scheduler.cpp:32
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
Definition: Scheduler.cpp:206
void _wait_all_threads()
Definition: Scheduler.cpp:324
AP_HAL::Util * util
Definition: HAL.h:115
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
SchedulerThread _timer_thread
Definition: Scheduler.h:82
void(* Proc)(void)
uint32_t timer
void reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:343
Semaphore _io_semaphore
Definition: Scheduler.h:102
const char * name
Definition: BusTest.cpp:11
bool _run() override
Definition: Thread.cpp:247
uint64_t millis64()
Definition: system.cpp:167
void delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:165
SchedulerThread _tonealarm_thread
Definition: Scheduler.h:86
AP_HAL::CANManager ** can_mgr
Definition: HAL.h:120
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:14
virtual void _timer_tick(void)
Definition: UARTDriver.h:72
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
static Util * from(AP_HAL::Util *util)
Definition: Util.h:27
uint64_t _stopped_clock_usec
Definition: Scheduler.h:97
SchedulerThread _uart_thread
Definition: Scheduler.h:85
virtual void _timer_tick(void)
Definition: Storage.h:11
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
AP_HAL::MemberProc _io_proc[LINUX_SCHEDULER_MAX_IO_PROCS]
Definition: Scheduler.h:79
volatile bool _in_timer_proc
Definition: Scheduler.h:77
uint8_t _num_timer_procs
Definition: Scheduler.h:76
AP_HAL::Proc _failsafe
Definition: Scheduler.h:70
AP_HAL::UARTDriver * uartF
Definition: HAL.h:105
void register_io_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:190
#define LINUX_SCHEDULER_MAX_IO_PROCS
Definition: Scheduler.h:11
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
#define SCHED_THREAD(name_, UPPER_NAME_)
Definition: Scheduler.cpp:52
static CANManager * from(AP_HAL::CANManager *can)
Definition: CAN.h:175
AP_HAL::UARTDriver * uartD
Definition: HAL.h:103
AP_HAL::Storage * storage
Definition: HAL.h:109
static RCInput * from(AP_HAL::RCInput *rcinput)
Definition: RCInput.h:15
virtual void call_delay_cb()
Definition: Scheduler.cpp:12
SchedulerThread _rcin_thread
Definition: Scheduler.h:84
void _tonealarm_task()
Definition: Scheduler.cpp:304
void suspend_timer_procs()
Definition: Scheduler.cpp:211
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:88
virtual void _timer_tick()
Definition: RCInput.h:34
#define LINUX_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:9
void stop_clock(uint64_t time_usec)
Definition: Scheduler.cpp:348
bool stop() override
Definition: Thread.cpp:274
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
void resume_timer_procs()
Definition: Scheduler.cpp:218
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
uint8_t _num_io_procs
Definition: Scheduler.h:80
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
void register_timer_process(AP_HAL::MemberProc)
Definition: Scheduler.cpp:173
size_t get_stack_usage()
Definition: Thread.cpp:126
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_HAL::RCInput * rcin
Definition: HAL.h:112
pthread_barrier_t _initialized_barrier
Definition: Scheduler.h:73
bool in_main_thread() const override
Definition: Scheduler.cpp:319
Semaphore _timer_semaphore
Definition: Scheduler.h:101
void system_initialized()
Definition: Scheduler.cpp:332
#define UART
Definition: RC_UART.cpp:13
pthread_t _main_ctx
Definition: Scheduler.h:99
void delay(uint16_t ms)
Definition: Scheduler.cpp:143
SchedulerThread _io_thread
Definition: Scheduler.h:83