Scheduler.h 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. #include "AP_HAL_SITL_Namespace.h"
  5. #include <sys/time.h>
  6. #include <pthread.h>
  7. #define SITL_SCHEDULER_MAX_TIMER_PROCS 8
  8. /* Scheduler implementation: */
  9. class HALSITL::Scheduler : public AP_HAL::Scheduler {
  10. public:
  11. explicit Scheduler(SITL_State *sitlState);
  12. static Scheduler *from(AP_HAL::Scheduler *scheduler) {
  13. return static_cast<HALSITL::Scheduler*>(scheduler);
  14. }
  15. /* AP_HAL::Scheduler methods */
  16. void init() override;
  17. void delay(uint16_t ms) override;
  18. void delay_microseconds(uint16_t us) override;
  19. void register_timer_process(AP_HAL::MemberProc) override;
  20. void register_io_process(AP_HAL::MemberProc) override;
  21. void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
  22. bool in_main_thread() const override;
  23. void system_initialized() override;
  24. void reboot(bool hold_in_bootloader) override;
  25. bool interrupts_are_blocked(void) {
  26. return _nested_atomic_ctr != 0;
  27. }
  28. void sitl_begin_atomic() {
  29. _nested_atomic_ctr++;
  30. }
  31. void sitl_end_atomic();
  32. static void timer_event() {
  33. _run_timer_procs();
  34. _run_io_procs();
  35. }
  36. uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }
  37. static void _run_io_procs();
  38. static bool _should_reboot;
  39. /*
  40. create a new thread
  41. */
  42. bool thread_create(AP_HAL::MemberProc, const char *name,
  43. uint32_t stack_size, priority_base base, int8_t priority) override;
  44. void set_in_semaphore_take_wait(bool value) { _in_semaphore_take_wait = value; }
  45. /*
  46. * semaphore_wait_hack_required - possibly move time input step
  47. * forward even if we are currently pretending to be the IO or timer
  48. * threads.
  49. */
  50. // a couple of helper functions to cope with SITL's time stepping
  51. bool semaphore_wait_hack_required();
  52. private:
  53. SITL_State *_sitlState;
  54. uint8_t _nested_atomic_ctr;
  55. static AP_HAL::Proc _failsafe;
  56. static void _run_timer_procs();
  57. static volatile bool _timer_event_missed;
  58. static AP_HAL::MemberProc _timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS];
  59. static AP_HAL::MemberProc _io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS];
  60. static uint8_t _num_timer_procs;
  61. static uint8_t _num_io_procs;
  62. static bool _in_timer_proc;
  63. static bool _in_io_proc;
  64. // boolean set by the Semaphore code to indicate it's currently
  65. // waiting for a take-timeout to occur.
  66. static bool _in_semaphore_take_wait;
  67. void stop_clock(uint64_t time_usec) override;
  68. static void *thread_create_trampoline(void *ctx);
  69. static void check_thread_stacks(void);
  70. bool _initialized;
  71. uint64_t _stopped_clock_usec;
  72. uint64_t _last_io_run;
  73. pthread_t _main_ctx;
  74. static HAL_Semaphore _thread_sem;
  75. struct thread_attr {
  76. struct thread_attr *next;
  77. AP_HAL::MemberProc *f;
  78. pthread_attr_t attr;
  79. uint32_t stack_size;
  80. void *stack;
  81. const uint8_t *stack_min;
  82. const char *name;
  83. };
  84. static struct thread_attr *threads;
  85. static const uint8_t stackfill = 0xEB;
  86. };
  87. #endif // CONFIG_HAL_BOARD