From 5b069247799eea4bf7f0516b7e3ece5856ccc741 Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Fri, 20 Nov 2015 12:13:34 +0900 Subject: [PATCH] AP_OpticalFlow: use millis/micros/panic functions --- libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp | 2 +- libraries/AP_OpticalFlow/OpticalFlow.cpp | 2 +- libraries/AP_OpticalFlow/OpticalFlow_backend.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp index 65585eec3a..fbf77d3461 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp @@ -154,7 +154,7 @@ void AP_OpticalFlow_Linux::update(void) } // throttle reads to no more than 10hz - uint32_t now = hal.scheduler->millis(); + uint32_t now = AP_HAL::millis(); if (now - last_read_ms < 100) { return; } diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 26dd323b4b..46e93a3970 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -75,7 +75,7 @@ void OpticalFlow::update(void) backend->update(); } // only healthy if the data is less than 0.5s old - _flags.healthy = (hal.scheduler->millis() - _last_update_ms < 500); + _flags.healthy = (AP_HAL::millis() - _last_update_ms < 500); } void OpticalFlow::setHIL(const struct OpticalFlow::OpticalFlow_state &state) diff --git a/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp b/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp index 3ebb13079b..b9bb708bba 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp @@ -22,5 +22,5 @@ extern const AP_HAL::HAL& hal; void OpticalFlow_backend::_update_frontend(const struct OpticalFlow::OpticalFlow_state &state) { frontend._state = state; - frontend._last_update_ms = hal.scheduler->millis(); + frontend._last_update_ms = AP_HAL::millis(); }