Scheduler.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578
  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. #include "AP_HAL_ChibiOS.h"
  19. #include "Scheduler.h"
  20. #include "Util.h"
  21. #include <AP_HAL_ChibiOS/UARTDriver.h>
  22. #include <AP_HAL_ChibiOS/AnalogIn.h>
  23. #include <AP_HAL_ChibiOS/Storage.h>
  24. #include <AP_HAL_ChibiOS/RCOutput.h>
  25. #include <AP_HAL_ChibiOS/RCInput.h>
  26. #include <AP_HAL_ChibiOS/CAN.h>
  27. #include <AP_InternalError/AP_InternalError.h>
  28. #if CH_CFG_USE_DYNAMIC == TRUE
  29. #include <AP_Logger/AP_Logger.h>
  30. #include <AP_Scheduler/AP_Scheduler.h>
  31. #include <AP_BoardConfig/AP_BoardConfig.h>
  32. #include "hwdef/common/stm32_util.h"
  33. #include "hwdef/common/watchdog.h"
  34. #include "shared_dma.h"
  35. #include "sdcard.h"
  36. #if HAL_WITH_IO_MCU
  37. #include <AP_IOMCU/AP_IOMCU.h>
  38. extern AP_IOMCU iomcu;
  39. #endif
  40. using namespace ChibiOS;
  41. extern const AP_HAL::HAL& hal;
  42. #ifndef HAL_NO_TIMER_THREAD
  43. THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE);
  44. #endif
  45. #ifndef HAL_NO_RCIN_THREAD
  46. THD_WORKING_AREA(_rcin_thread_wa, RCIN_THD_WA_SIZE);
  47. #endif
  48. #ifndef HAL_USE_EMPTY_IO
  49. THD_WORKING_AREA(_io_thread_wa, IO_THD_WA_SIZE);
  50. #endif
  51. #ifndef HAL_USE_EMPTY_STORAGE
  52. THD_WORKING_AREA(_storage_thread_wa, STORAGE_THD_WA_SIZE);
  53. #endif
  54. #ifndef HAL_NO_MONITOR_THREAD
  55. THD_WORKING_AREA(_monitor_thread_wa, MONITOR_THD_WA_SIZE);
  56. #endif
  57. Scheduler::Scheduler()
  58. {
  59. }
  60. void Scheduler::init()
  61. {
  62. chBSemObjectInit(&_timer_semaphore, false);
  63. chBSemObjectInit(&_io_semaphore, false);
  64. #ifndef HAL_NO_MONITOR_THREAD
  65. // setup the monitor thread - this is used to detect software lockups
  66. _monitor_thread_ctx = chThdCreateStatic(_monitor_thread_wa,
  67. sizeof(_monitor_thread_wa),
  68. APM_MONITOR_PRIORITY, /* Initial priority. */
  69. _monitor_thread, /* Thread function. */
  70. this); /* Thread parameter. */
  71. #endif
  72. #ifndef HAL_NO_TIMER_THREAD
  73. // setup the timer thread - this will call tasks at 1kHz
  74. _timer_thread_ctx = chThdCreateStatic(_timer_thread_wa,
  75. sizeof(_timer_thread_wa),
  76. APM_TIMER_PRIORITY, /* Initial priority. */
  77. _timer_thread, /* Thread function. */
  78. this); /* Thread parameter. */
  79. #endif
  80. #ifndef HAL_NO_RCIN_THREAD
  81. // setup the RCIN thread - this will call tasks at 1kHz
  82. _rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
  83. sizeof(_rcin_thread_wa),
  84. APM_RCIN_PRIORITY, /* Initial priority. */
  85. _rcin_thread, /* Thread function. */
  86. this); /* Thread parameter. */
  87. #endif
  88. #ifndef HAL_USE_EMPTY_IO
  89. // the IO thread runs at lower priority
  90. _io_thread_ctx = chThdCreateStatic(_io_thread_wa,
  91. sizeof(_io_thread_wa),
  92. APM_IO_PRIORITY, /* Initial priority. */
  93. _io_thread, /* Thread function. */
  94. this); /* Thread parameter. */
  95. #endif
  96. #ifndef HAL_USE_EMPTY_STORAGE
  97. // the storage thread runs at just above IO priority
  98. _storage_thread_ctx = chThdCreateStatic(_storage_thread_wa,
  99. sizeof(_storage_thread_wa),
  100. APM_STORAGE_PRIORITY, /* Initial priority. */
  101. _storage_thread, /* Thread function. */
  102. this); /* Thread parameter. */
  103. #endif
  104. }
  105. void Scheduler::delay_microseconds(uint16_t usec)
  106. {
  107. if (usec == 0) { //chibios faults with 0us sleep
  108. return;
  109. }
  110. uint32_t ticks;
  111. ticks = chTimeUS2I(usec);
  112. if (ticks == 0) {
  113. // calling with ticks == 0 causes a hard fault on ChibiOS
  114. ticks = 1;
  115. }
  116. chThdSleep(ticks); //Suspends Thread for desired microseconds
  117. }
  118. /*
  119. wrapper around sem_post that boosts main thread priority
  120. */
  121. static void set_high_priority()
  122. {
  123. #if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
  124. hal_chibios_set_priority(APM_MAIN_PRIORITY_BOOST);
  125. #endif
  126. }
  127. /*
  128. return the main thread to normal priority
  129. */
  130. void Scheduler::boost_end(void)
  131. {
  132. #if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
  133. if (in_main_thread() && _priority_boosted) {
  134. _priority_boosted = false;
  135. hal_chibios_set_priority(APM_MAIN_PRIORITY);
  136. }
  137. #endif
  138. }
  139. /*
  140. a variant of delay_microseconds that boosts priority to
  141. APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
  142. microseconds when the time completes. This significantly improves
  143. the regularity of timing of the main loop
  144. */
  145. void Scheduler::delay_microseconds_boost(uint16_t usec)
  146. {
  147. if (!_priority_boosted && in_main_thread()) {
  148. set_high_priority();
  149. _priority_boosted = true;
  150. _called_boost = true;
  151. }
  152. delay_microseconds(usec); //Suspends Thread for desired microseconds
  153. }
  154. /*
  155. return true if delay_microseconds_boost() has been called since last check
  156. */
  157. bool Scheduler::check_called_boost(void)
  158. {
  159. if (!_called_boost) {
  160. return false;
  161. }
  162. _called_boost = false;
  163. return true;
  164. }
  165. void Scheduler::delay(uint16_t ms)
  166. {
  167. uint64_t start = AP_HAL::micros64();
  168. while ((AP_HAL::micros64() - start)/1000 < ms) {
  169. delay_microseconds(1000);
  170. if (_min_delay_cb_ms <= ms) {
  171. if (in_main_thread()) {
  172. call_delay_cb();
  173. }
  174. }
  175. }
  176. }
  177. void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
  178. {
  179. chBSemWait(&_timer_semaphore);
  180. for (uint8_t i = 0; i < _num_timer_procs; i++) {
  181. if (_timer_proc[i] == proc) {
  182. chBSemSignal(&_timer_semaphore);
  183. return;
  184. }
  185. }
  186. if (_num_timer_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
  187. _timer_proc[_num_timer_procs] = proc;
  188. _num_timer_procs++;
  189. } else {
  190. hal.console->printf("Out of timer processes\n");
  191. }
  192. chBSemSignal(&_timer_semaphore);
  193. }
  194. void Scheduler::register_io_process(AP_HAL::MemberProc proc)
  195. {
  196. chBSemWait(&_io_semaphore);
  197. for (uint8_t i = 0; i < _num_io_procs; i++) {
  198. if (_io_proc[i] == proc) {
  199. chBSemSignal(&_io_semaphore);
  200. return;
  201. }
  202. }
  203. if (_num_io_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
  204. _io_proc[_num_io_procs] = proc;
  205. _num_io_procs++;
  206. } else {
  207. hal.console->printf("Out of IO processes\n");
  208. }
  209. chBSemSignal(&_io_semaphore);
  210. }
  211. void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
  212. {
  213. _failsafe = failsafe;
  214. }
  215. void Scheduler::reboot(bool hold_in_bootloader)
  216. {
  217. // disarm motors to ensure they are off during a bootloader upload
  218. hal.rcout->force_safety_on();
  219. #if HAL_WITH_IO_MCU
  220. if (AP_BoardConfig::io_enabled()) {
  221. iomcu.shutdown();
  222. }
  223. #endif
  224. #ifndef HAL_NO_LOGGING
  225. //stop logging
  226. if (AP_Logger::get_singleton()) {
  227. AP::logger().StopLogging();
  228. }
  229. // stop sdcard driver, if active
  230. sdcard_stop();
  231. #endif
  232. #if !defined(NO_FASTBOOT)
  233. // setup RTC for fast reboot
  234. set_fast_reboot(hold_in_bootloader?RTC_BOOT_HOLD:RTC_BOOT_FAST);
  235. #endif
  236. // disable all interrupt sources
  237. port_disable();
  238. // reboot
  239. NVIC_SystemReset();
  240. }
  241. void Scheduler::_run_timers()
  242. {
  243. if (_in_timer_proc) {
  244. return;
  245. }
  246. _in_timer_proc = true;
  247. int num_procs = 0;
  248. chBSemWait(&_timer_semaphore);
  249. num_procs = _num_timer_procs;
  250. chBSemSignal(&_timer_semaphore);
  251. // now call the timer based drivers
  252. for (int i = 0; i < num_procs; i++) {
  253. if (_timer_proc[i]) {
  254. _timer_proc[i]();
  255. }
  256. }
  257. // and the failsafe, if one is setup
  258. if (_failsafe != nullptr) {
  259. _failsafe();
  260. }
  261. #if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER)
  262. // process analog input
  263. ((AnalogIn *)hal.analogin)->_timer_tick();
  264. #endif
  265. _in_timer_proc = false;
  266. }
  267. void Scheduler::_timer_thread(void *arg)
  268. {
  269. Scheduler *sched = (Scheduler *)arg;
  270. chRegSetThreadName("apm_timer");
  271. while (!sched->_hal_initialized) {
  272. sched->delay_microseconds(1000);
  273. }
  274. while (true) {
  275. sched->delay_microseconds(1000);
  276. // run registered timers
  277. sched->_run_timers();
  278. // process any pending RC output requests
  279. hal.rcout->timer_tick();
  280. if (sched->expect_delay_start != 0) {
  281. uint32_t now = AP_HAL::millis();
  282. if (now - sched->expect_delay_start <= sched->expect_delay_length) {
  283. sched->watchdog_pat();
  284. }
  285. }
  286. }
  287. }
  288. #ifndef HAL_NO_MONITOR_THREAD
  289. void Scheduler::_monitor_thread(void *arg)
  290. {
  291. Scheduler *sched = (Scheduler *)arg;
  292. chRegSetThreadName("apm_monitor");
  293. while (!sched->_initialized) {
  294. sched->delay(100);
  295. }
  296. bool using_watchdog = AP_BoardConfig::watchdog_enabled();
  297. while (true) {
  298. sched->delay(100);
  299. if (using_watchdog) {
  300. stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4);
  301. }
  302. uint32_t now = AP_HAL::millis();
  303. uint32_t loop_delay = now - sched->last_watchdog_pat_ms;
  304. if (loop_delay >= 200) {
  305. // the main loop has been stuck for at least
  306. // 200ms. Starting logging the main loop state
  307. const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
  308. AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII",
  309. AP_HAL::micros64(),
  310. loop_delay,
  311. pd.scheduler_task,
  312. pd.internal_errors,
  313. pd.internal_error_count,
  314. pd.last_mavlink_msgid,
  315. pd.last_mavlink_cmd,
  316. pd.semaphore_line,
  317. pd.spi_count,
  318. pd.i2c_count);
  319. }
  320. if (loop_delay >= 500) {
  321. // at 500ms we declare an internal error
  322. AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck);
  323. }
  324. }
  325. }
  326. #endif // HAL_NO_MONITOR_THREAD
  327. void Scheduler::_rcin_thread(void *arg)
  328. {
  329. Scheduler *sched = (Scheduler *)arg;
  330. chRegSetThreadName("apm_rcin");
  331. while (!sched->_hal_initialized) {
  332. sched->delay_microseconds(20000);
  333. }
  334. while (true) {
  335. sched->delay_microseconds(1000);
  336. ((RCInput *)hal.rcin)->_timer_tick();
  337. }
  338. }
  339. void Scheduler::_run_io(void)
  340. {
  341. if (_in_io_proc) {
  342. return;
  343. }
  344. _in_io_proc = true;
  345. int num_procs = 0;
  346. chBSemWait(&_io_semaphore);
  347. num_procs = _num_io_procs;
  348. chBSemSignal(&_io_semaphore);
  349. // now call the IO based drivers
  350. for (int i = 0; i < num_procs; i++) {
  351. if (_io_proc[i]) {
  352. _io_proc[i]();
  353. }
  354. }
  355. _in_io_proc = false;
  356. }
  357. void Scheduler::_io_thread(void* arg)
  358. {
  359. Scheduler *sched = (Scheduler *)arg;
  360. chRegSetThreadName("apm_io");
  361. while (!sched->_hal_initialized) {
  362. sched->delay_microseconds(1000);
  363. }
  364. uint32_t last_sd_start_ms = AP_HAL::millis();
  365. while (true) {
  366. sched->delay_microseconds(1000);
  367. // run registered IO processes
  368. sched->_run_io();
  369. if (!hal.util->get_soft_armed()) {
  370. // if sdcard hasn't mounted then retry it every 3s in the IO
  371. // thread when disarmed
  372. uint32_t now = AP_HAL::millis();
  373. if (now - last_sd_start_ms > 3000) {
  374. last_sd_start_ms = now;
  375. sdcard_retry();
  376. }
  377. }
  378. }
  379. }
  380. void Scheduler::_storage_thread(void* arg)
  381. {
  382. Scheduler *sched = (Scheduler *)arg;
  383. chRegSetThreadName("apm_storage");
  384. while (!sched->_hal_initialized) {
  385. sched->delay_microseconds(10000);
  386. }
  387. while (true) {
  388. sched->delay_microseconds(10000);
  389. // process any pending storage writes
  390. hal.storage->_timer_tick();
  391. }
  392. }
  393. void Scheduler::system_initialized()
  394. {
  395. if (_initialized) {
  396. AP_HAL::panic("PANIC: scheduler::system_initialized called"
  397. "more than once");
  398. }
  399. _initialized = true;
  400. }
  401. /*
  402. disable interrupts and return a context that can be used to
  403. restore the interrupt state. This can be used to protect
  404. critical regions
  405. */
  406. void *Scheduler::disable_interrupts_save(void)
  407. {
  408. return (void *)(uintptr_t)chSysGetStatusAndLockX();
  409. }
  410. /*
  411. restore interrupt state from disable_interrupts_save()
  412. */
  413. void Scheduler::restore_interrupts(void *state)
  414. {
  415. chSysRestoreStatusX((syssts_t)(uintptr_t)state);
  416. }
  417. /*
  418. trampoline for thread create
  419. */
  420. void Scheduler::thread_create_trampoline(void *ctx)
  421. {
  422. AP_HAL::MemberProc *t = (AP_HAL::MemberProc *)ctx;
  423. (*t)();
  424. free(t);
  425. }
  426. /*
  427. create a new thread
  428. */
  429. bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
  430. {
  431. // take a copy of the MemberProc, it is freed after thread exits
  432. AP_HAL::MemberProc *tproc = (AP_HAL::MemberProc *)malloc(sizeof(proc));
  433. if (!tproc) {
  434. return false;
  435. }
  436. *tproc = proc;
  437. uint8_t thread_priority = APM_IO_PRIORITY;
  438. static const struct {
  439. priority_base base;
  440. uint8_t p;
  441. } priority_map[] = {
  442. { PRIORITY_BOOST, APM_MAIN_PRIORITY_BOOST},
  443. { PRIORITY_MAIN, APM_MAIN_PRIORITY},
  444. { PRIORITY_SPI, APM_SPI_PRIORITY},
  445. { PRIORITY_I2C, APM_I2C_PRIORITY},
  446. { PRIORITY_CAN, APM_CAN_PRIORITY},
  447. { PRIORITY_TIMER, APM_TIMER_PRIORITY},
  448. { PRIORITY_RCIN, APM_RCIN_PRIORITY},
  449. { PRIORITY_IO, APM_IO_PRIORITY},
  450. { PRIORITY_UART, APM_UART_PRIORITY},
  451. { PRIORITY_STORAGE, APM_STORAGE_PRIORITY},
  452. { PRIORITY_SCRIPTING, APM_SCRIPTING_PRIORITY},
  453. };
  454. for (uint8_t i=0; i<ARRAY_SIZE(priority_map); i++) {
  455. if (priority_map[i].base == base) {
  456. thread_priority = constrain_int16(priority_map[i].p + priority, LOWPRIO, HIGHPRIO);
  457. break;
  458. }
  459. }
  460. thread_t *thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(stack_size),
  461. name,
  462. thread_priority,
  463. thread_create_trampoline,
  464. tproc);
  465. if (thread_ctx == nullptr) {
  466. free(tproc);
  467. return false;
  468. }
  469. return true;
  470. }
  471. /*
  472. inform the scheduler that we are calling an operation from the
  473. main thread that may take an extended amount of time. This can
  474. be used to prevent watchdog reset during expected long delays
  475. A value of zero cancels the previous expected delay
  476. */
  477. void Scheduler::expect_delay_ms(uint32_t ms)
  478. {
  479. if (!in_main_thread()) {
  480. // only for main thread
  481. return;
  482. }
  483. if (ms == 0) {
  484. if (expect_delay_nesting > 0) {
  485. expect_delay_nesting--;
  486. }
  487. if (expect_delay_nesting == 0) {
  488. expect_delay_start = 0;
  489. }
  490. } else {
  491. uint32_t now = AP_HAL::millis();
  492. if (expect_delay_start != 0) {
  493. // we already have a delay running, possibly extend it
  494. uint32_t done = now - expect_delay_start;
  495. if (expect_delay_length > done) {
  496. ms = MAX(ms, expect_delay_length - done);
  497. }
  498. }
  499. expect_delay_start = now;
  500. expect_delay_length = ms;
  501. expect_delay_nesting++;
  502. // also put our priority below timer thread if we are boosted
  503. boost_end();
  504. }
  505. }
  506. // pat the watchdog
  507. void Scheduler::watchdog_pat(void)
  508. {
  509. stm32_watchdog_pat();
  510. last_watchdog_pat_ms = AP_HAL::millis();
  511. }
  512. #endif // CH_CFG_USE_DYNAMIC