APM:Libraries
Scheduler.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
6 #include <sys/time.h>
7 
8 #define SITL_SCHEDULER_MAX_TIMER_PROCS 4
9 
10 /* Scheduler implementation: */
12 public:
13  explicit Scheduler(SITL_State *sitlState);
14  static Scheduler *from(AP_HAL::Scheduler *scheduler) {
15  return static_cast<HALSITL::Scheduler*>(scheduler);
16  }
17 
18  /* AP_HAL::Scheduler methods */
19 
20  void init();
21  void delay(uint16_t ms);
22  void delay_microseconds(uint16_t us);
23 
24  void register_timer_process(AP_HAL::MemberProc);
25  void register_io_process(AP_HAL::MemberProc);
26  void suspend_timer_procs();
27  void resume_timer_procs();
28 
29  void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us);
30 
31  bool in_main_thread() const override { return !_in_timer_proc && !_in_io_proc; };
32  void system_initialized();
33 
34  void reboot(bool hold_in_bootloader);
35 
37  return _nested_atomic_ctr != 0;
38  }
39 
42  }
43  void sitl_end_atomic();
44 
45  static void timer_event() {
46  _run_timer_procs(true);
47  _run_io_procs(true);
48  }
49 
50  uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }
51 
52  static void _run_io_procs(bool called_from_isr);
53  static bool _should_reboot;
54 
55 private:
59 
60  static void _run_timer_procs(bool called_from_isr);
61 
62  static volatile bool _timer_suspended;
63  static volatile bool _timer_event_missed;
64  static AP_HAL::MemberProc _timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS];
65  static AP_HAL::MemberProc _io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS];
66  static uint8_t _num_timer_procs;
67  static uint8_t _num_io_procs;
68  static bool _in_timer_proc;
69  static bool _in_io_proc;
70 
71  void stop_clock(uint64_t time_usec);
72 
75  uint64_t _last_io_run;
76 };
77 #endif // CONFIG_HAL_BOARD
static uint8_t _num_io_procs
Definition: Scheduler.h:67
uint64_t stopped_clock_usec() const
Definition: Scheduler.h:50
void stop_clock(uint64_t time_usec)
Definition: Scheduler.cpp:207
bool interrupts_are_blocked(void)
Definition: Scheduler.h:36
static AP_HAL::MemberProc _io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:65
static bool _should_reboot
Definition: Scheduler.h:53
void delay(uint16_t ms)
static bool _in_timer_proc
Definition: Scheduler.h:68
void sitl_begin_atomic()
Definition: Scheduler.h:40
void suspend_timer_procs()
void register_timer_process(AP_HAL::MemberProc)
void(* Proc)(void)
SITL_State * _sitlState
Definition: Scheduler.h:56
uint8_t _nested_atomic_ctr
Definition: Scheduler.h:57
static volatile bool _timer_suspended
Definition: Scheduler.h:62
static AP_HAL::MemberProc _timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:64
static Scheduler * from(AP_HAL::Scheduler *scheduler)
Definition: Scheduler.h:14
static volatile bool _timer_event_missed
Definition: Scheduler.h:63
static void _run_timer_procs(bool called_from_isr)
static void timer_event()
Definition: Scheduler.h:45
void delay_microseconds(uint16_t us)
bool in_main_thread() const override
Definition: Scheduler.h:31
static void _run_io_procs(bool called_from_isr)
Definition: Scheduler.cpp:176
uint64_t _last_io_run
Definition: Scheduler.h:75
static uint8_t _num_timer_procs
Definition: Scheduler.h:66
static AP_HAL::Proc _failsafe
Definition: Scheduler.h:58
#define SITL_SCHEDULER_MAX_TIMER_PROCS
Definition: Scheduler.h:8
void reboot(bool hold_in_bootloader)
static SITL_State sitlState
void register_io_process(AP_HAL::MemberProc)
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)
uint64_t _stopped_clock_usec
Definition: Scheduler.h:74
static bool _in_io_proc
Definition: Scheduler.h:69