AP_RPM: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:14:09 +09:00 committed by Randy Mackay
parent 26c06ae3a9
commit 9639add306
2 changed files with 2 additions and 2 deletions

View File

@ -118,7 +118,7 @@ bool AP_RPM::healthy(uint8_t instance) const
return false; return false;
} }
// assume we get readings at at least 1Hz // assume we get readings at at least 1Hz
if (hal.scheduler->millis() - state[instance].last_reading_ms > 1000) { if (AP_HAL::millis() - state[instance].last_reading_ms > 1000) {
return false; return false;
} }
return true; return true;

View File

@ -92,7 +92,7 @@ void AP_RPM_PX4_PWM::update(void)
if (count != 0) { if (count != 0) {
state.rate_rpm = sum / count; state.rate_rpm = sum / count;
state.last_reading_ms = hal.scheduler->millis(); state.last_reading_ms = AP_HAL::millis();
} }
} }