lib/battery: Fix cell voltages with >10S

Signed-off-by: Alex Mikhalev <alex@corvus-robotics.com>
This commit is contained in:
Alex Mikhalev
2021-02-26 23:47:00 -07:00
committed by Daniel Agar
parent 9d0c966b15
commit d01806a0c6

View File

@@ -158,9 +158,11 @@ void Battery::updateBatteryStatus(const hrt_abstime &timestamp, float voltage_v,
static constexpr int uorb_max_cells = sizeof(_battery_status.voltage_cell_v) / sizeof(
_battery_status.voltage_cell_v[0]);
int max_cells = math::min(_battery_status.cell_count, uorb_max_cells);
// Fill cell voltages with average values to work around MAVLink BATTERY_STATUS not allowing to report just total voltage
for (int i = 0; (i < _battery_status.cell_count) && (i < uorb_max_cells); i++) {
_battery_status.voltage_cell_v[i] = _battery_status.voltage_filtered_v / _battery_status.cell_count;
for (int i = 0; i < max_cells; i++) {
_battery_status.voltage_cell_v[i] = _battery_status.voltage_filtered_v / max_cells;
}
}