mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: Added cells 11...14 voltage information (13 and 14 are 0 for now)
This commit is contained in:
parent
89f0ed2f8f
commit
1d0e7d2974
|
@ -207,16 +207,20 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
|
||||||
float temp;
|
float temp;
|
||||||
bool got_temperature = battery.get_temperature(temp, instance);
|
bool got_temperature = battery.get_temperature(temp, instance);
|
||||||
|
|
||||||
// prepare array of individual cell voltage
|
// prepare arrays of individual cell voltages
|
||||||
uint16_t cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
|
uint16_t cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
|
||||||
|
uint16_t cell_volts_ext[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_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);
|
||||||
// copy the first 10 cells
|
// copy the first 10 cells
|
||||||
memcpy(cell_volts, batt_cells.cells, sizeof(cell_volts));
|
memcpy(cell_volts, batt_cells.cells, sizeof(cell_volts));
|
||||||
// 10th cell reports the lowest voltage of the last 3 cells
|
// 11 ... 14 use a second cell_volts_ext array
|
||||||
for (uint8_t i = MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i < ARRAY_SIZE(batt_cells.cells); i++) {
|
for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) {
|
||||||
cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN-1] = MIN(cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN-1],
|
if (MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i < uint8_t(ARRAY_SIZE(batt_cells.cells))) {
|
||||||
batt_cells.cells[i]);
|
cell_volts_ext[i] = batt_cells.cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i];
|
||||||
|
} else {
|
||||||
|
cell_volts_ext[i] = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
} 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
|
||||||
|
@ -232,6 +236,9 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
|
||||||
voltage -= 65534.0f;
|
voltage -= 65534.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) {
|
||||||
|
cell_volts_ext[i] = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
float current, consumed_mah, consumed_wh;
|
float current, consumed_mah, consumed_wh;
|
||||||
|
@ -259,7 +266,8 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
|
||||||
consumed_wh, // consumed energy in hJ (hecto-Joules)
|
consumed_wh, // consumed energy in hJ (hecto-Joules)
|
||||||
battery.capacity_remaining_pct(instance),
|
battery.capacity_remaining_pct(instance),
|
||||||
0, // time remaining, seconds (not provided)
|
0, // time remaining, seconds (not provided)
|
||||||
MAV_BATTERY_CHARGE_STATE_UNDEFINED);
|
MAV_BATTERY_CHARGE_STATE_UNDEFINED,
|
||||||
|
cell_volts_ext); // Cell 11..14 voltages
|
||||||
}
|
}
|
||||||
|
|
||||||
// returns true if all battery instances were reported
|
// returns true if all battery instances were reported
|
||||||
|
|
Loading…
Reference in New Issue