mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_BattMonitor: Limit the scope of possible corruption if the NeoDesigns gets a bad cell count
This commit is contained in:
parent
699e61da57
commit
f854477efe
@ -24,7 +24,7 @@ void AP_BattMonitor_SMBus_NeoDesign::timer()
|
|||||||
// Get the cell count once, it's not likely to change in flight
|
// Get the cell count once, it's not likely to change in flight
|
||||||
if (_cell_count == 0) {
|
if (_cell_count == 0) {
|
||||||
if (read_word(BATTMONITOR_ND_CELL_COUNT, data)) {
|
if (read_word(BATTMONITOR_ND_CELL_COUNT, data)) {
|
||||||
_cell_count = data;
|
_cell_count = MIN(data, max_cell_count); // never read in more cells then we can store
|
||||||
} else {
|
} else {
|
||||||
return; // something wrong, don't try anything else
|
return; // something wrong, don't try anything else
|
||||||
}
|
}
|
||||||
|
@ -15,4 +15,6 @@ private:
|
|||||||
void timer(void) override;
|
void timer(void) override;
|
||||||
|
|
||||||
uint8_t _cell_count;
|
uint8_t _cell_count;
|
||||||
|
|
||||||
|
static const constexpr uint8_t max_cell_count = 10;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user