AP_HAL_Linux: Scheduler: make microsleep() public

This will be used outside of scheduler class.
This commit is contained in:
Lucas De Marchi 2016-02-01 20:17:54 -02:00
parent 8ecf54bf75
commit 5e9b45ebc2
2 changed files with 10 additions and 9 deletions

View File

@ -137,7 +137,7 @@ void Scheduler::init()
iter->start_routine); iter->start_routine);
} }
void Scheduler::_microsleep(uint32_t usec) void Scheduler::microsleep(uint32_t usec)
{ {
struct timespec ts; struct timespec ts;
ts.tv_sec = 0; ts.tv_sec = 0;
@ -154,7 +154,7 @@ void Scheduler::delay(uint16_t ms)
while ((AP_HAL::millis64() - start) < ms) { while ((AP_HAL::millis64() - start) < ms) {
// this yields the CPU to other apps // this yields the CPU to other apps
_microsleep(1000); microsleep(1000);
if (_min_delay_cb_ms <= ms) { if (_min_delay_cb_ms <= ms) {
if (_delay_cb) { if (_delay_cb) {
_delay_cb(); _delay_cb();
@ -168,7 +168,7 @@ void Scheduler::delay_microseconds(uint16_t us)
if (_stopped_clock_usec) { if (_stopped_clock_usec) {
return; return;
} }
_microsleep(us); microsleep(us);
} }
void Scheduler::register_delay_callback(AP_HAL::Proc proc, void Scheduler::register_delay_callback(AP_HAL::Proc proc,
@ -365,7 +365,7 @@ void *Scheduler::_timer_thread(void* arg)
// we've lost sync - restart // we've lost sync - restart
next_run_usec = AP_HAL::micros64(); next_run_usec = AP_HAL::micros64();
} else { } else {
sched->_microsleep(dt); sched->microsleep(dt);
} }
next_run_usec += 1000; next_run_usec += 1000;
// run registered timers // run registered timers
@ -408,7 +408,7 @@ void *Scheduler::_rcin_thread(void *arg)
poll(NULL, 0, 1); poll(NULL, 0, 1);
} }
while (true) { while (true) {
sched->_microsleep(APM_LINUX_RCIN_PERIOD); sched->microsleep(APM_LINUX_RCIN_PERIOD);
#if !HAL_LINUX_UARTS_ON_TIMER_THREAD #if !HAL_LINUX_UARTS_ON_TIMER_THREAD
RCInput::from(hal.rcin)->_timer_tick(); RCInput::from(hal.rcin)->_timer_tick();
#endif #endif
@ -444,7 +444,7 @@ void *Scheduler::_uart_thread(void* arg)
poll(NULL, 0, 1); poll(NULL, 0, 1);
} }
while (true) { while (true) {
sched->_microsleep(APM_LINUX_UART_PERIOD); sched->microsleep(APM_LINUX_UART_PERIOD);
#if !HAL_LINUX_UARTS_ON_TIMER_THREAD #if !HAL_LINUX_UARTS_ON_TIMER_THREAD
_run_uarts(); _run_uarts();
#endif #endif
@ -460,7 +460,7 @@ void *Scheduler::_tonealarm_thread(void* arg)
poll(NULL, 0, 1); poll(NULL, 0, 1);
} }
while (true) { while (true) {
sched->_microsleep(APM_LINUX_TONEALARM_PERIOD); sched->microsleep(APM_LINUX_TONEALARM_PERIOD);
// process tone command // process tone command
Util::from(hal.util)->_toneAlarm_timer_tick(); Util::from(hal.util)->_toneAlarm_timer_tick();
@ -476,7 +476,7 @@ void *Scheduler::_io_thread(void* arg)
poll(NULL, 0, 1); poll(NULL, 0, 1);
} }
while (true) { while (true) {
sched->_microsleep(APM_LINUX_IO_PERIOD); sched->microsleep(APM_LINUX_IO_PERIOD);
// process any pending storage writes // process any pending storage writes
Storage::from(hal.storage)->_timer_tick(); Storage::from(hal.storage)->_timer_tick();

View File

@ -49,9 +49,10 @@ public:
uint64_t stopped_clock_usec() const { return _stopped_clock_usec; } uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }
void microsleep(uint32_t usec);
private: private:
void _timer_handler(int signum); void _timer_handler(int signum);
void _microsleep(uint32_t usec);
AP_HAL::Proc _delay_cb; AP_HAL::Proc _delay_cb;
uint16_t _min_delay_cb_ms; uint16_t _min_delay_cb_ms;