mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: cope with InfoAux without nominal voltage
allows for reset of remaining charge from GCS or lua
This commit is contained in:
parent
532ab09c72
commit
aaa4e0268a
|
@ -47,6 +47,9 @@ bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const
|
||||||
if (!has_current() || !_state.healthy) {
|
if (!has_current() || !_state.healthy) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
if (isnan(_state.consumed_mah) || _params._pack_capacity <= 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
|
const float mah_remaining = _params._pack_capacity - _state.consumed_mah;
|
||||||
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
|
percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX);
|
||||||
|
|
|
@ -153,21 +153,22 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_aux(const ardupilot_equipment_
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(_sem_battmon);
|
WITH_SEMAPHORE(_sem_battmon);
|
||||||
uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len);
|
uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len);
|
||||||
float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage;
|
|
||||||
float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage;
|
|
||||||
|
|
||||||
_cycle_count = msg.cycle_count;
|
_cycle_count = msg.cycle_count;
|
||||||
for (uint8_t i = 0; i < cell_count; i++) {
|
for (uint8_t i = 0; i < cell_count; i++) {
|
||||||
_interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000;
|
_interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000;
|
||||||
}
|
}
|
||||||
_interim_state.is_powering_off = msg.is_powering_off;
|
_interim_state.is_powering_off = msg.is_powering_off;
|
||||||
_interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000;
|
if (!isnan(msg.nominal_voltage) && msg.nominal_voltage > 0) {
|
||||||
_interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh;
|
float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage;
|
||||||
_interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600);
|
float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage;
|
||||||
_interim_state.has_time_remaining = true;
|
_interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000;
|
||||||
|
_interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh;
|
||||||
|
_interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600);
|
||||||
|
_interim_state.has_time_remaining = true;
|
||||||
|
}
|
||||||
|
|
||||||
_has_cell_voltages = true;
|
_has_cell_voltages = true;
|
||||||
_has_time_remaining = true;
|
|
||||||
_has_battery_info_aux = true;
|
_has_battery_info_aux = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue