|
|
|
@ -10,39 +10,39 @@
@@ -10,39 +10,39 @@
|
|
|
|
|
/* Scheduler implementation: */ |
|
|
|
|
class HALSITL::Scheduler : public AP_HAL::Scheduler { |
|
|
|
|
public: |
|
|
|
|
Scheduler(SITL_State *sitlState); |
|
|
|
|
explicit Scheduler(SITL_State *sitlState); |
|
|
|
|
static Scheduler *from(AP_HAL::Scheduler *scheduler) { |
|
|
|
|
return static_cast<HALSITL::Scheduler*>(scheduler); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* AP_HAL::Scheduler methods */ |
|
|
|
|
|
|
|
|
|
void init(); |
|
|
|
|
void delay(uint16_t ms); |
|
|
|
|
void delay_microseconds(uint16_t us); |
|
|
|
|
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms); |
|
|
|
|
void init(); |
|
|
|
|
void delay(uint16_t ms); |
|
|
|
|
void delay_microseconds(uint16_t us); |
|
|
|
|
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms); |
|
|
|
|
|
|
|
|
|
void register_timer_process(AP_HAL::MemberProc); |
|
|
|
|
void register_io_process(AP_HAL::MemberProc); |
|
|
|
|
void suspend_timer_procs(); |
|
|
|
|
void resume_timer_procs(); |
|
|
|
|
void register_timer_process(AP_HAL::MemberProc); |
|
|
|
|
void register_io_process(AP_HAL::MemberProc); |
|
|
|
|
void suspend_timer_procs(); |
|
|
|
|
void resume_timer_procs(); |
|
|
|
|
|
|
|
|
|
bool in_timerprocess(); |
|
|
|
|
bool in_timerprocess(); |
|
|
|
|
|
|
|
|
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us); |
|
|
|
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us); |
|
|
|
|
|
|
|
|
|
void system_initialized(); |
|
|
|
|
void system_initialized(); |
|
|
|
|
|
|
|
|
|
void reboot(bool hold_in_bootloader); |
|
|
|
|
void reboot(bool hold_in_bootloader); |
|
|
|
|
|
|
|
|
|
bool interrupts_are_blocked(void) { |
|
|
|
|
bool interrupts_are_blocked(void) { |
|
|
|
|
return _nested_atomic_ctr != 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void sitl_begin_atomic() { |
|
|
|
|
void sitl_begin_atomic() { |
|
|
|
|
_nested_atomic_ctr++; |
|
|
|
|
} |
|
|
|
|
void sitl_end_atomic(); |
|
|
|
|
void sitl_end_atomic(); |
|
|
|
|
|
|
|
|
|
static void timer_event() { |
|
|
|
|
_run_timer_procs(true); |
|
|
|
@ -67,16 +67,12 @@ private:
@@ -67,16 +67,12 @@ private:
|
|
|
|
|
static AP_HAL::MemberProc _io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS]; |
|
|
|
|
static uint8_t _num_timer_procs; |
|
|
|
|
static uint8_t _num_io_procs; |
|
|
|
|
static bool _in_timer_proc; |
|
|
|
|
static bool _in_io_proc; |
|
|
|
|
static bool _in_timer_proc; |
|
|
|
|
static bool _in_io_proc; |
|
|
|
|
|
|
|
|
|
void stop_clock(uint64_t time_usec); |
|
|
|
|
|
|
|
|
|
bool _initialized; |
|
|
|
|
uint64_t _stopped_clock_usec; |
|
|
|
|
}; |
|
|
|
|
#endif // CONFIG_HAL_BOARD
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|
|
|
|
|