mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: add assertion to avoid memory over-read
This commit is contained in:
parent
4a8f7d232a
commit
bf10b454d1
|
@ -81,6 +81,12 @@ void AP_BattMonitor_SMBus_Generic::timer()
|
|||
}
|
||||
}
|
||||
|
||||
// we loop over something limted by
|
||||
// BATTMONITOR_SMBUS_NUM_CELLS_MAX but assign into something
|
||||
// limited by AP_BATT_MONITOR_CELLS_MAX - so make sure we won't
|
||||
// over-write:
|
||||
static_assert(BATTMONITOR_SMBUS_NUM_CELLS_MAX <= ARRAY_SIZE(_state.cell_voltages.cells), "BATTMONITOR_SMBUS_NUM_CELLS_MAX must be <= number of cells in state voltages");
|
||||
|
||||
// read cell voltages
|
||||
for (uint8_t i = 0; i < (_cell_count_fixed ? _cell_count : BATTMONITOR_SMBUS_NUM_CELLS_MAX); i++) {
|
||||
if (read_word(smbus_cell_ids[i], data) && (data > 0) && (data < UINT16_MAX)) {
|
||||
|
|
Loading…
Reference in New Issue