cc6298e7ac
Checks for the highest cell for 15 seconds and then reduces the cell voltage calls to cover only those cells that actually exist also renames SMBus _last_cell_update_us
34 lines
1.3 KiB
C++
34 lines
1.3 KiB
C++
#pragma once
|
|
|
|
#include "AP_BattMonitor_SMBus.h"
|
|
|
|
#define BATTMONITOR_SMBUS_NUM_CELLS_MAX 12
|
|
|
|
class AP_BattMonitor_SMBus_Generic : public AP_BattMonitor_SMBus
|
|
{
|
|
public:
|
|
|
|
// Constructor
|
|
AP_BattMonitor_SMBus_Generic(AP_BattMonitor &mon,
|
|
AP_BattMonitor::BattMonitor_State &mon_state,
|
|
AP_BattMonitor_Params ¶ms,
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
|
|
|
private:
|
|
|
|
void timer(void) override;
|
|
|
|
// check if PEC supported with the version value in SpecificationInfo() function
|
|
// returns true once PEC is confirmed as working or not working
|
|
bool check_pec_support();
|
|
|
|
// read_block - returns number of characters read if successful, zero if unsuccessful
|
|
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_us[BATTMONITOR_SMBUS_NUM_CELLS_MAX]; // system time of last successful read of cell voltage
|
|
uint32_t _cell_count_check_start_us; // system time we started attempting to count the number of cells
|
|
uint8_t _cell_count; // number of cells returning voltages
|
|
bool _cell_count_fixed; // true when cell count check is complete
|
|
};
|