Scheduler.cpp 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395
  1. #include "Scheduler.h"
  2. #include <algorithm>
  3. #include <errno.h>
  4. #include <poll.h>
  5. #include <stdio.h>
  6. #include <stdlib.h>
  7. #include <sys/mman.h>
  8. #include <sys/time.h>
  9. #include <unistd.h>
  10. #include <AP_HAL/AP_HAL.h>
  11. #include <AP_Math/AP_Math.h>
  12. #include <AP_Vehicle/AP_Vehicle_Type.h>
  13. #include "RCInput.h"
  14. #include "SPIUARTDriver.h"
  15. #include "Storage.h"
  16. #include "UARTDriver.h"
  17. #include "Util.h"
  18. using namespace Linux;
  19. extern const AP_HAL::HAL& hal;
  20. #define APM_LINUX_MAX_PRIORITY 20
  21. #define APM_LINUX_TIMER_PRIORITY 15
  22. #define APM_LINUX_UART_PRIORITY 14
  23. #define APM_LINUX_RCIN_PRIORITY 13
  24. #define APM_LINUX_MAIN_PRIORITY 12
  25. #define APM_LINUX_IO_PRIORITY 10
  26. #define APM_LINUX_SCRIPTING_PRIORITY 1
  27. #define APM_LINUX_TIMER_RATE 1000
  28. #define APM_LINUX_UART_RATE 100
  29. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
  30. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
  31. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
  32. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
  33. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
  34. #define APM_LINUX_RCIN_RATE 500
  35. #define APM_LINUX_IO_RATE 50
  36. #else
  37. #define APM_LINUX_RCIN_RATE 100
  38. #define APM_LINUX_IO_RATE 50
  39. #endif
  40. #define SCHED_THREAD(name_, UPPER_NAME_) \
  41. { \
  42. .name = "ap-" #name_, \
  43. .thread = &_##name_##_thread, \
  44. .policy = SCHED_FIFO, \
  45. .prio = APM_LINUX_##UPPER_NAME_##_PRIORITY, \
  46. .rate = APM_LINUX_##UPPER_NAME_##_RATE, \
  47. }
  48. Scheduler::Scheduler()
  49. { }
  50. void Scheduler::init_realtime()
  51. {
  52. #if APM_BUILD_TYPE(APM_BUILD_Replay)
  53. // we don't run Replay in real-time...
  54. return;
  55. #endif
  56. #if APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
  57. // we opportunistically run examples/tools in realtime
  58. if (geteuid() != 0) {
  59. fprintf(stderr, "WARNING: not running as root. Will not use realtime scheduling\n");
  60. return;
  61. }
  62. #endif
  63. mlockall(MCL_CURRENT|MCL_FUTURE);
  64. struct sched_param param = { .sched_priority = APM_LINUX_MAIN_PRIORITY };
  65. if (sched_setscheduler(0, SCHED_FIFO, &param) == -1) {
  66. AP_HAL::panic("Scheduler: failed to set scheduling parameters: %s",
  67. strerror(errno));
  68. }
  69. }
  70. void Scheduler::init()
  71. {
  72. int ret;
  73. const struct sched_table {
  74. const char *name;
  75. SchedulerThread *thread;
  76. int policy;
  77. int prio;
  78. uint32_t rate;
  79. } sched_table[] = {
  80. SCHED_THREAD(timer, TIMER),
  81. SCHED_THREAD(uart, UART),
  82. SCHED_THREAD(rcin, RCIN),
  83. SCHED_THREAD(io, IO),
  84. };
  85. _main_ctx = pthread_self();
  86. init_realtime();
  87. /* set barrier to N + 1 threads: worker threads + main */
  88. unsigned n_threads = ARRAY_SIZE(sched_table) + 1;
  89. ret = pthread_barrier_init(&_initialized_barrier, nullptr, n_threads);
  90. if (ret) {
  91. AP_HAL::panic("Scheduler: Failed to initialise barrier object: %s",
  92. strerror(ret));
  93. }
  94. for (size_t i = 0; i < ARRAY_SIZE(sched_table); i++) {
  95. const struct sched_table *t = &sched_table[i];
  96. t->thread->set_rate(t->rate);
  97. t->thread->set_stack_size(1024 * 1024);
  98. t->thread->start(t->name, t->policy, t->prio);
  99. }
  100. #if defined(DEBUG_STACK) && DEBUG_STACK
  101. register_timer_process(FUNCTOR_BIND_MEMBER(&Scheduler::_debug_stack, void));
  102. #endif
  103. }
  104. void Scheduler::_debug_stack()
  105. {
  106. uint64_t now = AP_HAL::millis64();
  107. if (now - _last_stack_debug_msec > 5000) {
  108. fprintf(stderr, "Stack Usage:\n"
  109. "\ttimer = %zu\n"
  110. "\tio = %zu\n"
  111. "\trcin = %zu\n"
  112. "\tuart = %zu\n",
  113. _timer_thread.get_stack_usage(),
  114. _io_thread.get_stack_usage(),
  115. _rcin_thread.get_stack_usage(),
  116. _uart_thread.get_stack_usage());
  117. _last_stack_debug_msec = now;
  118. }
  119. }
  120. void Scheduler::microsleep(uint32_t usec)
  121. {
  122. struct timespec ts;
  123. ts.tv_sec = 0;
  124. ts.tv_nsec = usec*1000UL;
  125. while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ;
  126. }
  127. void Scheduler::delay(uint16_t ms)
  128. {
  129. if (_stopped_clock_usec) {
  130. return;
  131. }
  132. uint64_t start = AP_HAL::millis64();
  133. while ((AP_HAL::millis64() - start) < ms) {
  134. // this yields the CPU to other apps
  135. microsleep(1000);
  136. if (in_main_thread() && _min_delay_cb_ms <= ms) {
  137. call_delay_cb();
  138. }
  139. }
  140. }
  141. void Scheduler::delay_microseconds(uint16_t us)
  142. {
  143. if (_stopped_clock_usec) {
  144. return;
  145. }
  146. microsleep(us);
  147. }
  148. void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
  149. {
  150. for (uint8_t i = 0; i < _num_timer_procs; i++) {
  151. if (_timer_proc[i] == proc) {
  152. return;
  153. }
  154. }
  155. if (_num_timer_procs >= LINUX_SCHEDULER_MAX_TIMER_PROCS) {
  156. hal.console->printf("Out of timer processes\n");
  157. return;
  158. }
  159. _timer_proc[_num_timer_procs] = proc;
  160. _num_timer_procs++;
  161. }
  162. void Scheduler::register_io_process(AP_HAL::MemberProc proc)
  163. {
  164. for (uint8_t i = 0; i < _num_io_procs; i++) {
  165. if (_io_proc[i] == proc) {
  166. return;
  167. }
  168. }
  169. if (_num_io_procs < LINUX_SCHEDULER_MAX_IO_PROCS) {
  170. _io_proc[_num_io_procs] = proc;
  171. _num_io_procs++;
  172. } else {
  173. hal.console->printf("Out of IO processes\n");
  174. }
  175. }
  176. void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
  177. {
  178. _failsafe = failsafe;
  179. }
  180. void Scheduler::_timer_task()
  181. {
  182. int i;
  183. if (_in_timer_proc) {
  184. return;
  185. }
  186. _in_timer_proc = true;
  187. // now call the timer based drivers
  188. for (i = 0; i < _num_timer_procs; i++) {
  189. if (_timer_proc[i]) {
  190. _timer_proc[i]();
  191. }
  192. }
  193. // and the failsafe, if one is setup
  194. if (_failsafe != nullptr) {
  195. _failsafe();
  196. }
  197. _in_timer_proc = false;
  198. }
  199. void Scheduler::_run_io(void)
  200. {
  201. if (!_io_semaphore.take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  202. return;
  203. }
  204. // now call the IO based drivers
  205. for (int i = 0; i < _num_io_procs; i++) {
  206. if (_io_proc[i]) {
  207. _io_proc[i]();
  208. }
  209. }
  210. _io_semaphore.give();
  211. }
  212. /*
  213. run timers for all UARTs
  214. */
  215. void Scheduler::_run_uarts()
  216. {
  217. // process any pending serial bytes
  218. hal.uartA->_timer_tick();
  219. hal.uartB->_timer_tick();
  220. hal.uartC->_timer_tick();
  221. hal.uartD->_timer_tick();
  222. hal.uartE->_timer_tick();
  223. hal.uartF->_timer_tick();
  224. hal.uartG->_timer_tick();
  225. hal.uartH->_timer_tick();
  226. }
  227. void Scheduler::_rcin_task()
  228. {
  229. RCInput::from(hal.rcin)->_timer_tick();
  230. }
  231. void Scheduler::_uart_task()
  232. {
  233. _run_uarts();
  234. }
  235. void Scheduler::_io_task()
  236. {
  237. // process any pending storage writes
  238. hal.storage->_timer_tick();
  239. // run registered IO processes
  240. _run_io();
  241. }
  242. bool Scheduler::in_main_thread() const
  243. {
  244. return pthread_equal(pthread_self(), _main_ctx);
  245. }
  246. void Scheduler::_wait_all_threads()
  247. {
  248. int r = pthread_barrier_wait(&_initialized_barrier);
  249. if (r == PTHREAD_BARRIER_SERIAL_THREAD) {
  250. pthread_barrier_destroy(&_initialized_barrier);
  251. }
  252. }
  253. void Scheduler::system_initialized()
  254. {
  255. if (_initialized) {
  256. AP_HAL::panic("PANIC: scheduler::system_initialized called more than once");
  257. }
  258. _initialized = true;
  259. _wait_all_threads();
  260. }
  261. void Scheduler::reboot(bool hold_in_bootloader)
  262. {
  263. exit(1);
  264. }
  265. void Scheduler::stop_clock(uint64_t time_usec)
  266. {
  267. if (time_usec >= _stopped_clock_usec) {
  268. _stopped_clock_usec = time_usec;
  269. _run_io();
  270. }
  271. }
  272. bool Scheduler::SchedulerThread::_run()
  273. {
  274. _sched._wait_all_threads();
  275. return PeriodicThread::_run();
  276. }
  277. void Scheduler::teardown()
  278. {
  279. _timer_thread.stop();
  280. _io_thread.stop();
  281. _rcin_thread.stop();
  282. _uart_thread.stop();
  283. _timer_thread.join();
  284. _io_thread.join();
  285. _rcin_thread.join();
  286. _uart_thread.join();
  287. }
  288. /*
  289. create a new thread
  290. */
  291. bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
  292. {
  293. Thread *thread = new Thread{(Thread::task_t)proc};
  294. if (!thread) {
  295. return false;
  296. }
  297. uint8_t thread_priority = APM_LINUX_IO_PRIORITY;
  298. static const struct {
  299. priority_base base;
  300. uint8_t p;
  301. } priority_map[] = {
  302. { PRIORITY_BOOST, APM_LINUX_MAIN_PRIORITY},
  303. { PRIORITY_MAIN, APM_LINUX_MAIN_PRIORITY},
  304. { PRIORITY_SPI, AP_LINUX_SENSORS_SCHED_PRIO},
  305. { PRIORITY_I2C, AP_LINUX_SENSORS_SCHED_PRIO},
  306. { PRIORITY_CAN, APM_LINUX_TIMER_PRIORITY},
  307. { PRIORITY_TIMER, APM_LINUX_TIMER_PRIORITY},
  308. { PRIORITY_RCIN, APM_LINUX_RCIN_PRIORITY},
  309. { PRIORITY_IO, APM_LINUX_IO_PRIORITY},
  310. { PRIORITY_UART, APM_LINUX_UART_PRIORITY},
  311. { PRIORITY_STORAGE, APM_LINUX_IO_PRIORITY},
  312. { PRIORITY_SCRIPTING, APM_LINUX_SCRIPTING_PRIORITY},
  313. };
  314. for (uint8_t i=0; i<ARRAY_SIZE(priority_map); i++) {
  315. if (priority_map[i].base == base) {
  316. thread_priority = constrain_int16(priority_map[i].p + priority, 1, APM_LINUX_MAX_PRIORITY);
  317. break;
  318. }
  319. }
  320. // Add 256k to HAL-independent requested stack size
  321. thread->set_stack_size(256 * 1024 + stack_size);
  322. /*
  323. * We should probably store the thread handlers and join() when exiting,
  324. * but let's the thread manage itself for now.
  325. */
  326. thread->set_auto_free(true);
  327. if (!thread->start(name, SCHED_FIFO, thread_priority)) {
  328. delete thread;
  329. return false;
  330. }
  331. return true;
  332. }