mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_BattMonitor: Maxell cell voltages timeout after 5sec
This commit is contained in:
parent
51cab958b9
commit
0edc341231
@ -5,7 +5,6 @@
|
||||
#include "AP_BattMonitor_SMBus_Maxell.h"
|
||||
#include <utility>
|
||||
|
||||
#define BATTMONITOR_SMBUS_MAXELL_NUM_CELLS 6
|
||||
uint8_t maxell_cell_ids[] = { 0x3f, // cell 1
|
||||
0x3e, // cell 2
|
||||
0x3d, // cell 3
|
||||
@ -60,7 +59,8 @@ void AP_BattMonitor_SMBus_Maxell::timer()
|
||||
if (read_word(maxell_cell_ids[i], data)) {
|
||||
_has_cell_voltages = true;
|
||||
_state.cell_voltages.cells[i] = data;
|
||||
} else {
|
||||
_last_cell_update_ms[i] = tnow;
|
||||
} else if ((tnow - _last_cell_update_ms[i]) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) {
|
||||
_state.cell_voltages.cells[i] = UINT16_MAX;
|
||||
}
|
||||
}
|
||||
|
@ -6,6 +6,8 @@
|
||||
#include "AP_BattMonitor_SMBus.h"
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
#define BATTMONITOR_SMBUS_MAXELL_NUM_CELLS 6
|
||||
|
||||
class AP_BattMonitor_SMBus_Maxell : public AP_BattMonitor_SMBus
|
||||
{
|
||||
public:
|
||||
@ -28,4 +30,5 @@ private:
|
||||
uint8_t read_block(uint8_t reg, uint8_t* data, bool append_zero) const;
|
||||
|
||||
uint8_t _pec_confirmed; // count of the number of times PEC has been confirmed as working
|
||||
uint32_t _last_cell_update_ms[BATTMONITOR_SMBUS_MAXELL_NUM_CELLS]; // system time of last successful read of cell voltage
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user