Browse Source

AP_RPM: use millis/micros/panic functions

master
Caio Marcelo de Oliveira Filho 9 years ago committed by Randy Mackay
parent
commit
9639add306
  1. 2
      libraries/AP_RPM/AP_RPM.cpp
  2. 2
      libraries/AP_RPM/RPM_PX4_PWM.cpp

2
libraries/AP_RPM/AP_RPM.cpp

@ -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;

2
libraries/AP_RPM/RPM_PX4_PWM.cpp

@ -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();
} }
} }

Loading…
Cancel
Save