APM:Libraries
Scheduler.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <stdint.h>
4 
5 #include <AP_Common/AP_Common.h>
6 
7 #include "AP_HAL_Boards.h"
8 #include "AP_HAL_Namespace.h"
9 
10 
12 public:
13  Scheduler() {}
14  virtual void init() = 0;
15  virtual void delay(uint16_t ms) = 0;
16 
17  /*
18  delay for the given number of microseconds. This needs to be as
19  accurate as possible - preferably within 100 microseconds.
20  */
21  virtual void delay_microseconds(uint16_t us) = 0;
22 
23  /*
24  delay for the given number of microseconds. On supported
25  platforms this boosts the priority of the main thread for a
26  short time when the time completes. The aim is to ensure the
27  main thread runs at a higher priority than drivers for the start
28  of each loop
29  */
30  virtual void delay_microseconds_boost(uint16_t us) { delay_microseconds(us); }
31 
32  /*
33  end the priority boost from delay_microseconds_boost()
34  */
35  virtual void boost_end(void) {}
36 
37  // register a function to be called by the scheduler if it needs
38  // to sleep for more than min_time_ms
40  uint16_t min_time_ms);
41  // returns true if the Scheduler has called the delay callback
42  // function. If you are on the main thread that means your call
43  // stack has the scheduler on it somewhere.
44  virtual bool in_delay_callback() const { return _in_delay_callback; }
45 
46  // register a high priority timer task
47  virtual void register_timer_process(AP_HAL::MemberProc) = 0;
48 
49  // register a low priority IO task
50  virtual void register_io_process(AP_HAL::MemberProc) = 0;
51 
52  // suspend and resume both timer and IO processes
53  virtual void suspend_timer_procs() = 0;
54  virtual void resume_timer_procs() = 0;
55 
57  uint32_t period_us) = 0;
58 
59  virtual void system_initialized() = 0;
60 
61  virtual void reboot(bool hold_in_bootloader) = 0;
62 
66  virtual void stop_clock(uint64_t time_usec) {}
67 
68  virtual bool in_main_thread() const = 0;
69 
70  virtual void create_uavcan_thread() {};
71 
72  /*
73  disable interrupts and return a context that can be used to
74  restore the interrupt state. This can be used to protect
75  critical regions
76 
77  Warning: may not be implemented on all HALs
78  */
79  virtual void *disable_interrupts_save(void) { return nullptr; }
80 
81  /*
82  restore interrupt state from disable_interrupts_save()
83  */
84  virtual void restore_interrupts(void *) {}
85 
86  // called by subclasses when they need to delay for some time
87  virtual void call_delay_cb();
88  uint16_t _min_delay_cb_ms;
89 
90 private:
91 
94 
95 };
virtual void stop_clock(uint64_t time_usec)
Definition: Scheduler.h:66
AP_HAL::Proc _delay_cb
Definition: Scheduler.h:92
virtual void boost_end(void)
Definition: Scheduler.h:35
virtual bool in_main_thread() const =0
bool _in_delay_callback
Definition: Scheduler.h:93
virtual void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms)
Definition: Scheduler.cpp:5
void(* Proc)(void)
virtual void resume_timer_procs()=0
virtual void delay(uint16_t ms)=0
virtual void create_uavcan_thread()
Definition: Scheduler.h:70
virtual void init()=0
virtual void call_delay_cb()
Definition: Scheduler.cpp:12
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:88
virtual void suspend_timer_procs()=0
Common definitions and utility routines for the ArduPilot libraries.
virtual void register_timer_process(AP_HAL::MemberProc)=0
virtual void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)=0
virtual void reboot(bool hold_in_bootloader)=0
virtual void delay_microseconds_boost(uint16_t us)
Definition: Scheduler.h:30
virtual void register_io_process(AP_HAL::MemberProc)=0
virtual void delay_microseconds(uint16_t us)=0
virtual void restore_interrupts(void *)
Definition: Scheduler.h:84
virtual void * disable_interrupts_save(void)
Definition: Scheduler.h:79
virtual bool in_delay_callback() const
Definition: Scheduler.h:44
virtual void system_initialized()=0