Browse Source

AP_BattMonitor: Limit the scope of possible corruption if the NeoDesigns gets a bad cell count

zr-v5.1
Michael du Breuil 4 years ago committed by Andrew Tridgell
parent
commit
f854477efe
  1. 2
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.cpp
  2. 2
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.h

2
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.cpp

@ -24,7 +24,7 @@ void AP_BattMonitor_SMBus_NeoDesign::timer() @@ -24,7 +24,7 @@ void AP_BattMonitor_SMBus_NeoDesign::timer()
// Get the cell count once, it's not likely to change in flight
if (_cell_count == 0) {
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 {
return; // something wrong, don't try anything else
}

2
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.h

@ -15,4 +15,6 @@ private: @@ -15,4 +15,6 @@ private:
void timer(void) override;
uint8_t _cell_count;
static const constexpr uint8_t max_cell_count = 10;
};

Loading…
Cancel
Save