GCS_MAVLink: send_battery_status uses memcpy for cell voltages

Co-authored-by: WickedShell <Wicked.Shell.Scripts@gmail.com>
This commit is contained in:
Randy Mackay 2020-06-24 08:22:01 +09:00
parent 77d6b19d86
commit 03ea646e50

View File

@ -203,13 +203,12 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
uint16_t cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]; uint16_t cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
if (battery.has_cell_voltages(instance)) { if (battery.has_cell_voltages(instance)) {
const AP_BattMonitor::cells& batt_cells = battery.get_cell_voltages(instance); const AP_BattMonitor::cells& batt_cells = battery.get_cell_voltages(instance);
for (uint8_t i = 0; i < ARRAY_SIZE(batt_cells.cells); i++) { // copy the first 10 cells
if (i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN) { memcpy(cell_volts, batt_cells.cells, sizeof(cell_volts));
cell_volts[i] = batt_cells.cells[i]; // 10th cell reports the lowest voltage of the last 3 cells
} else { for (uint8_t i = MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i < ARRAY_SIZE(batt_cells.cells); i++) {
// 10th cell reports the lowest voltage of the last 3 cells cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN-1] = MIN(cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN-1],
cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN-1] = MIN(cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN-1], batt_cells.cells[i]); batt_cells.cells[i]);
}
} }
} else { } else {
// for battery monitors that cannot provide voltages for individual cells the battery's total voltage is put into the first cell // for battery monitors that cannot provide voltages for individual cells the battery's total voltage is put into the first cell