From 9639add30633962e6ad746a258b38368dd1d6f92 Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Fri, 20 Nov 2015 12:14:09 +0900 Subject: [PATCH] AP_RPM: use millis/micros/panic functions --- libraries/AP_RPM/AP_RPM.cpp | 2 +- libraries/AP_RPM/RPM_PX4_PWM.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index a5b14d8c02..cea636ef42 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -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; diff --git a/libraries/AP_RPM/RPM_PX4_PWM.cpp b/libraries/AP_RPM/RPM_PX4_PWM.cpp index fce7b5b3ee..8c4ea129a9 100644 --- a/libraries/AP_RPM/RPM_PX4_PWM.cpp +++ b/libraries/AP_RPM/RPM_PX4_PWM.cpp @@ -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(); } }