mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: use millis/micros/panic functions
This commit is contained in:
parent
26c06ae3a9
commit
9639add306
|
@ -118,7 +118,7 @@ bool AP_RPM::healthy(uint8_t instance) const
|
|||
return false;
|
||||
}
|
||||
// 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 true;
|
||||
|
|
|
@ -92,7 +92,7 @@ void AP_RPM_PX4_PWM::update(void)
|
|||
|
||||
if (count != 0) {
|
||||
state.rate_rpm = sum / count;
|
||||
state.last_reading_ms = hal.scheduler->millis();
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue