From 9eb945d24f794455d2c3a3d850cf9b84abe1cc81 Mon Sep 17 00:00:00 2001 From: Caio Marcelo de Oliveira Filho Date: Fri, 20 Nov 2015 12:08:43 +0900 Subject: [PATCH] AP_BattMonitor: use millis/micros/panic functions --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor_SMBus_PX4.cpp | 4 ++-- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index c6747b73c1..35647883e8 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -276,7 +276,7 @@ bool AP_BattMonitor::exhausted(uint8_t instance, float low_voltage, float min_ca } // get current time - uint32_t tnow = hal.scheduler->millis(); + uint32_t tnow = AP_HAL::millis(); // check voltage if ((state[instance].voltage > 0.0f) && (low_voltage > 0) && (state[instance].voltage < low_voltage)) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp index 991d6bad19..e49196f010 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp @@ -31,7 +31,7 @@ AP_BattMonitor_Analog::read() // read current if (_mon.has_current(_state.instance)) { // calculate time since last current read - uint32_t tnow = hal.scheduler->micros(); + uint32_t tnow = AP_HAL::micros(); float dt = tnow - _state.last_time_micros; // this copes with changing the pin at runtime diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp index ae9d182db4..9927bab200 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp @@ -144,7 +144,7 @@ void AP_BattMonitor_Bebop::read(void) float remaining, vbat, vbat_raw; auto rcout = Linux::RCOutput_Bebop::from(hal.rcout); - tnow = hal.scheduler->micros(); + tnow = AP_HAL::micros(); ret = rcout->read_obs_data(data); if (ret < 0) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp index 011161ad75..ab96be6471 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp @@ -37,7 +37,7 @@ void AP_BattMonitor_SMBus_I2C::read() { uint16_t data; uint8_t buff[4]; - uint32_t tnow = hal.scheduler->micros(); + uint32_t tnow = AP_HAL::micros(); // read voltage if (read_word(BATTMONITOR_SMBUS_VOLTAGE, data)) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_PX4.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_PX4.cpp index 7f7fd0a272..f47745b657 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_PX4.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_PX4.cpp @@ -66,7 +66,7 @@ void AP_BattMonitor_SMBus_PX4::read() if (OK == orb_copy(ORB_ID(battery_status), _batt_sub, &batt_status)) { _state.voltage = batt_status.voltage_v; _state.current_amps = batt_status.current_a; - _state.last_time_micros = hal.scheduler->micros(); + _state.last_time_micros = AP_HAL::micros(); _state.current_total_mah = batt_status.discharged_mah; _state.healthy = true; @@ -81,7 +81,7 @@ void AP_BattMonitor_SMBus_PX4::read() } } else if (_state.healthy) { // timeout after 5 seconds - if ((hal.scheduler->micros() - _state.last_time_micros) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) { + if ((AP_HAL::micros() - _state.last_time_micros) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) { _state.healthy = false; } }