APM:Libraries
Scheduler.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3 
4 #include "AP_HAL_SITL.h"
5 #include "Scheduler.h"
6 #include "UARTDriver.h"
7 #include <sys/time.h>
8 #include <fenv.h>
9 
10 using namespace HALSITL;
11 
12 extern const AP_HAL::HAL& hal;
13 
14 
16 volatile bool Scheduler::_timer_suspended = false;
17 volatile bool Scheduler::_timer_event_missed = false;
18 
19 AP_HAL::MemberProc Scheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
20 uint8_t Scheduler::_num_timer_procs = 0;
21 bool Scheduler::_in_timer_proc = false;
22 
23 AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
24 uint8_t Scheduler::_num_io_procs = 0;
25 bool Scheduler::_in_io_proc = false;
26 bool Scheduler::_should_reboot = false;
27 
29  _sitlState(sitlState),
30  _stopped_clock_usec(0)
31 {
32 }
33 
34 void Scheduler::init()
35 {
36 }
37 
38 void Scheduler::delay_microseconds(uint16_t usec)
39 {
40  uint64_t start = AP_HAL::micros64();
41  do {
42  uint64_t dtime = AP_HAL::micros64() - start;
43  if (dtime >= usec) {
44  break;
45  }
46  _sitlState->wait_clock(start + usec);
47  } while (true);
48 }
49 
50 void Scheduler::delay(uint16_t ms)
51 {
52  while (ms > 0) {
53  delay_microseconds(1000);
54  ms--;
55  if (_min_delay_cb_ms <= ms) {
56  call_delay_cb();
57  }
58  }
59 }
60 
61 void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
62 {
63  for (uint8_t i = 0; i < _num_timer_procs; i++) {
64  if (_timer_proc[i] == proc) {
65  return;
66  }
67  }
68 
69  if (_num_timer_procs < SITL_SCHEDULER_MAX_TIMER_PROCS) {
71  _num_timer_procs++;
72  }
73 }
74 
75 void Scheduler::register_io_process(AP_HAL::MemberProc proc)
76 {
77  for (uint8_t i = 0; i < _num_io_procs; i++) {
78  if (_io_proc[i] == proc) {
79  return;
80  }
81  }
82 
83  if (_num_io_procs < SITL_SCHEDULER_MAX_TIMER_PROCS) {
84  _io_proc[_num_io_procs] = proc;
85  _num_io_procs++;
86  }
87 }
88 
89 void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
90 {
91  _failsafe = failsafe;
92 }
93 
95  _timer_suspended = true;
96 }
97 
99  _timer_suspended = false;
100  if (_timer_event_missed) {
101  _timer_event_missed = false;
102  _run_timer_procs(false);
103  }
104 }
105 
107  if (_initialized) {
109  "PANIC: scheduler system initialized called more than once");
110  }
111  int exceptions = FE_OVERFLOW | FE_DIVBYZERO;
112 #ifndef __i386__
113  // i386 with gcc doesn't work with FE_INVALID
114  exceptions |= FE_INVALID;
115 #endif
116  if (_sitlState->_sitl == nullptr || _sitlState->_sitl->float_exception) {
117  feenableexcept(exceptions);
118  } else {
119  feclearexcept(exceptions);
120  }
121  _initialized = true;
122 }
123 
125  if (_nested_atomic_ctr == 0) {
126  hal.uartA->printf("NESTED ATOMIC ERROR\n");
127  } else {
129  }
130 }
131 
132 void Scheduler::reboot(bool hold_in_bootloader)
133 {
134  _should_reboot = true;
135 }
136 
137 void Scheduler::_run_timer_procs(bool called_from_isr)
138 {
139  if (_in_timer_proc) {
140  // the timer calls took longer than the period of the
141  // timer. This is bad, and may indicate a serious
142  // driver failure. We can't just call the drivers
143  // again, as we could run out of stack. So we only
144  // call the _failsafe call. It's job is to detect if
145  // the drivers or the main loop are indeed dead and to
146  // activate whatever failsafe it thinks may help if
147  // need be. We assume the failsafe code can't
148  // block. If it does then we will recurse and die when
149  // we run out of stack
150  if (_failsafe != nullptr) {
151  _failsafe();
152  }
153  return;
154  }
155  _in_timer_proc = true;
156 
157  if (!_timer_suspended) {
158  // now call the timer based drivers
159  for (int i = 0; i < _num_timer_procs; i++) {
160  if (_timer_proc[i]) {
161  _timer_proc[i]();
162  }
163  }
164  } else if (called_from_isr) {
165  _timer_event_missed = true;
166  }
167 
168  // and the failsafe, if one is setup
169  if (_failsafe != nullptr) {
170  _failsafe();
171  }
172 
173  _in_timer_proc = false;
174 }
175 
176 void Scheduler::_run_io_procs(bool called_from_isr)
177 {
178  if (_in_io_proc) {
179  return;
180  }
181  _in_io_proc = true;
182 
183  if (!_timer_suspended) {
184  // now call the IO based drivers
185  for (int i = 0; i < _num_io_procs; i++) {
186  if (_io_proc[i]) {
187  _io_proc[i]();
188  }
189  }
190  } else if (called_from_isr) {
191  _timer_event_missed = true;
192  }
193 
194  _in_io_proc = false;
195 
196  hal.uartA->_timer_tick();
197  hal.uartB->_timer_tick();
198  hal.uartC->_timer_tick();
199  hal.uartD->_timer_tick();
200  hal.uartE->_timer_tick();
201  hal.uartF->_timer_tick();
202 }
203 
204 /*
205  set simulation timestamp
206  */
207 void Scheduler::stop_clock(uint64_t time_usec)
208 {
209  _stopped_clock_usec = time_usec;
210  if (time_usec - _last_io_run > 10000) {
211  _last_io_run = time_usec;
212  _run_io_procs(false);
213  }
214 }
215 
216 #endif
static uint8_t _num_io_procs
Definition: Scheduler.h:67
AP_HAL::UARTDriver * uartE
Definition: HAL.h:104
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void stop_clock(uint64_t time_usec)
Definition: Scheduler.cpp:207
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 suspend_timer_procs()
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
void register_timer_process(AP_HAL::MemberProc)
void(* Proc)(void)
SITL_State * _sitlState
Definition: Scheduler.h:56
AP_Int8 float_exception
Definition: SITL.h:135
virtual void _timer_tick(void)
Definition: UARTDriver.h:72
AP_HAL::UARTDriver * uartC
Definition: HAL.h:102
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t _nested_atomic_ctr
Definition: Scheduler.h:57
AP_HAL::UARTDriver * uartF
Definition: HAL.h:105
static volatile bool _timer_suspended
Definition: Scheduler.h:62
static AP_HAL::MemberProc _timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS]
Definition: Scheduler.h:64
AP_HAL::UARTDriver * uartD
Definition: HAL.h:103
static volatile bool _timer_event_missed
Definition: Scheduler.h:63
uint64_t micros64()
Definition: system.cpp:162
static void _run_timer_procs(bool called_from_isr)
virtual void call_delay_cb()
Definition: Scheduler.cpp:12
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:88
void delay_microseconds(uint16_t us)
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
AP_HAL::UARTDriver * uartA
Definition: HAL.h:100
void reboot(bool hold_in_bootloader)
SITL::SITL * _sitl
Definition: SITL_State.h:165
static SITL_State sitlState
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void wait_clock(uint64_t wait_time_usec)
Definition: SITL_State.cpp:187
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