Scheduler.h 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168
  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. #pragma once
  18. #include <AP_HAL/AP_HAL.h>
  19. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  20. #include "AP_HAL_ChibiOS_Namespace.h"
  21. #define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS 8
  22. #define APM_MONITOR_PRIORITY 183
  23. #define APM_MAIN_PRIORITY 180
  24. #define APM_TIMER_PRIORITY 181
  25. #define APM_RCIN_PRIORITY 177
  26. #define APM_UART_PRIORITY 60
  27. #define APM_STORAGE_PRIORITY 59
  28. #define APM_IO_PRIORITY 58
  29. #define APM_STARTUP_PRIORITY 10
  30. #define APM_SCRIPTING_PRIORITY LOWPRIO
  31. /*
  32. boost priority handling
  33. */
  34. #ifndef APM_MAIN_PRIORITY_BOOST
  35. #define APM_MAIN_PRIORITY_BOOST 182
  36. #endif
  37. #ifndef APM_SPI_PRIORITY
  38. // SPI priority needs to be above main priority to ensure fast sampling of IMUs can keep up
  39. // with the data rate
  40. #define APM_SPI_PRIORITY 181
  41. #endif
  42. #ifndef APM_CAN_PRIORITY
  43. #define APM_CAN_PRIORITY 178
  44. #endif
  45. #ifndef APM_I2C_PRIORITY
  46. #define APM_I2C_PRIORITY 176
  47. #endif
  48. #ifndef TIMER_THD_WA_SIZE
  49. #define TIMER_THD_WA_SIZE 2048
  50. #endif
  51. #ifndef RCIN_THD_WA_SIZE
  52. #define RCIN_THD_WA_SIZE 512
  53. #endif
  54. #ifndef IO_THD_WA_SIZE
  55. #define IO_THD_WA_SIZE 2048
  56. #endif
  57. #ifndef STORAGE_THD_WA_SIZE
  58. #define STORAGE_THD_WA_SIZE 2048
  59. #endif
  60. #ifndef MONITOR_THD_WA_SIZE
  61. #define MONITOR_THD_WA_SIZE 512
  62. #endif
  63. /* Scheduler implementation: */
  64. class ChibiOS::Scheduler : public AP_HAL::Scheduler {
  65. public:
  66. Scheduler();
  67. /* AP_HAL::Scheduler methods */
  68. void init() override;
  69. void delay(uint16_t ms) override;
  70. void delay_microseconds(uint16_t us) override;
  71. void delay_microseconds_boost(uint16_t us) override;
  72. void boost_end(void) override;
  73. void register_timer_process(AP_HAL::MemberProc) override;
  74. void register_io_process(AP_HAL::MemberProc) override;
  75. void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
  76. void reboot(bool hold_in_bootloader) override;
  77. bool in_main_thread() const override { return get_main_thread() == chThdGetSelfX(); }
  78. void system_initialized() override;
  79. void hal_initialized() { _hal_initialized = true; }
  80. bool check_called_boost(void);
  81. /*
  82. inform the scheduler that we are calling an operation from the
  83. main thread that may take an extended amount of time. This can
  84. be used to prevent watchdog reset during expected long delays
  85. A value of zero cancels the previous expected delay
  86. */
  87. void expect_delay_ms(uint32_t ms) override;
  88. /*
  89. disable interrupts and return a context that can be used to
  90. restore the interrupt state. This can be used to protect
  91. critical regions
  92. */
  93. void *disable_interrupts_save(void) override;
  94. /*
  95. restore interrupt state from disable_interrupts_save()
  96. */
  97. void restore_interrupts(void *) override;
  98. /*
  99. create a new thread
  100. */
  101. bool thread_create(AP_HAL::MemberProc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) override;
  102. // pat the watchdog
  103. void watchdog_pat(void);
  104. private:
  105. bool _initialized;
  106. volatile bool _hal_initialized;
  107. AP_HAL::Proc _failsafe;
  108. bool _called_boost;
  109. bool _priority_boosted;
  110. uint32_t expect_delay_start;
  111. uint32_t expect_delay_length;
  112. uint32_t expect_delay_nesting;
  113. AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
  114. uint8_t _num_timer_procs;
  115. volatile bool _in_timer_proc;
  116. AP_HAL::MemberProc _io_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
  117. uint8_t _num_io_procs;
  118. volatile bool _in_io_proc;
  119. uint32_t last_watchdog_pat_ms;
  120. thread_t* _timer_thread_ctx;
  121. thread_t* _rcin_thread_ctx;
  122. thread_t* _io_thread_ctx;
  123. thread_t* _storage_thread_ctx;
  124. thread_t* _monitor_thread_ctx;
  125. #if CH_CFG_USE_SEMAPHORES == TRUE
  126. binary_semaphore_t _timer_semaphore;
  127. binary_semaphore_t _io_semaphore;
  128. #endif
  129. static void _timer_thread(void *arg);
  130. static void _rcin_thread(void *arg);
  131. static void _io_thread(void *arg);
  132. static void _storage_thread(void *arg);
  133. static void _uart_thread(void *arg);
  134. static void _monitor_thread(void *arg);
  135. void _run_timers();
  136. void _run_io(void);
  137. static void thread_create_trampoline(void *ctx);
  138. };
  139. #endif