mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-15 20:34:03 -04:00
AP_BattMonitor: use millis/micros/panic functions
This commit is contained in:
parent
8cce3067f4
commit
9eb945d24f
@ -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)) {
|
||||
|
@ -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
|
||||
|
@ -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) {
|
||||
|
@ -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)) {
|
||||
|
@ -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;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user