mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: confirm pec support before attempting to read voltage
Previously we checked PEC support continuously at 10hz. With this change PEC support (or lack of support) is determined first before we try to read from the battery. Once determined, we do not repeat the checks. Also simplified logic to determine PEC support based on version (should have no functional effect) Also renamed get_pec_support to check_pec_support Also renamed _pec_confirm to _pec_confirmed
This commit is contained in:
parent
884892be16
commit
dcc4f69f7c
|
@ -15,12 +15,7 @@ extern const AP_HAL::HAL& hal;
|
|||
#define BATTMONITOR_SMBUS_MAXELL_SPECIFICATION_INFO 0x1a // specification info
|
||||
#define BATTMONITOR_SMBUS_MAXELL_MANUFACTURE_NAME 0x20 // manufacturer name
|
||||
|
||||
#define BATTMONITOR_SMBUS_10_PEC_NOT_SUPPORT 0x10 // Smart Battery Specification v1.0
|
||||
#define BATTMONITOR_SMBUS_11_PEC_NOT_SUPPORT 0x21 // Smart Battery Specification v1.1 without PEC support
|
||||
#define BATTMONITOR_SMBUS_11_PEC_SUPPORT 0x31 // Smart Battery Specification v1.1 with PEC support
|
||||
|
||||
// A Block Read or Write is allowed to transfer a maximum of 32 data bytes.
|
||||
#define READ_BLOCK_MAXIMUM_TRANSFER 0x20
|
||||
#define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes.
|
||||
|
||||
#define SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation
|
||||
|
||||
|
@ -64,9 +59,9 @@ void AP_BattMonitor_SMBus_Maxell::read()
|
|||
|
||||
void AP_BattMonitor_SMBus_Maxell::timer()
|
||||
{
|
||||
// _pec_confirmed set true after confirming if it support PEC
|
||||
if (!_pec_confirmed) {
|
||||
_pec_confirmed = get_pec_support();
|
||||
// check if PEC is supported
|
||||
if (!check_pec_support()) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint16_t data;
|
||||
|
@ -106,7 +101,7 @@ bool AP_BattMonitor_SMBus_Maxell::read_word(uint8_t reg, uint16_t& data) const
|
|||
}
|
||||
|
||||
// check PEC
|
||||
if (_pec_support) {
|
||||
if (_pec_supported) {
|
||||
const uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, 2);
|
||||
if (pec != buff[2]) {
|
||||
return false;
|
||||
|
@ -131,7 +126,7 @@ uint8_t AP_BattMonitor_SMBus_Maxell::read_block(uint8_t reg, uint8_t* data, bool
|
|||
}
|
||||
|
||||
// sanity check length returned by smbus
|
||||
if (bufflen == 0 || bufflen > READ_BLOCK_MAXIMUM_TRANSFER) {
|
||||
if (bufflen == 0 || bufflen > SMBUS_READ_BLOCK_MAXIMUM_TRANSFER) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -145,7 +140,7 @@ uint8_t AP_BattMonitor_SMBus_Maxell::read_block(uint8_t reg, uint8_t* data, bool
|
|||
}
|
||||
|
||||
// check PEC
|
||||
if (_pec_support) {
|
||||
if (_pec_supported) {
|
||||
uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1);
|
||||
if (pec != buff[bufflen+1]) {
|
||||
return 0;
|
||||
|
@ -164,44 +159,46 @@ uint8_t AP_BattMonitor_SMBus_Maxell::read_block(uint8_t reg, uint8_t* data, bool
|
|||
return bufflen;
|
||||
}
|
||||
|
||||
// get PEC support using the version value in SpecificationInfo
|
||||
bool AP_BattMonitor_SMBus_Maxell::get_pec_support()
|
||||
// check if PEC supported with the version value in SpecificationInfo() function
|
||||
// returns true once PEC is confirmed as working or not working
|
||||
bool AP_BattMonitor_SMBus_Maxell::check_pec_support()
|
||||
{
|
||||
uint16_t data;
|
||||
uint8_t buff[READ_BLOCK_MAXIMUM_TRANSFER + 1];
|
||||
// exit immediately if we have already confirmed pec support
|
||||
if (_pec_confirmed) {
|
||||
return true;
|
||||
}
|
||||
|
||||
// specification info
|
||||
uint16_t data;
|
||||
if (!read_word(BATTMONITOR_SMBUS_MAXELL_SPECIFICATION_INFO, data)) {
|
||||
_pec_support = false;
|
||||
return false;
|
||||
}
|
||||
|
||||
// determine _pec_support is false when SpecInfo indicates no PEC support
|
||||
if (((data & 0xFF) == BATTMONITOR_SMBUS_10_PEC_NOT_SUPPORT) || ((data & 0xFF) == BATTMONITOR_SMBUS_11_PEC_NOT_SUPPORT)) {
|
||||
_pec_support = false;
|
||||
return true;
|
||||
} else if ((data & 0xFF) != BATTMONITOR_SMBUS_11_PEC_SUPPORT) {
|
||||
_pec_support = false;
|
||||
return false;
|
||||
}
|
||||
// extract version
|
||||
uint8_t version = (data & 0xF0) >> 4;
|
||||
|
||||
// At first, set true. In the second time, determine it.
|
||||
// This confirm to get the correct value with PEC support
|
||||
if (_pec_support) {
|
||||
// version less than 0011b (i.e. 3) do not support PEC
|
||||
if (version < 3) {
|
||||
_pec_supported = false;
|
||||
_pec_confirmed = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// manufacturer name
|
||||
// check manufacturer name
|
||||
uint8_t buff[SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1];
|
||||
if (read_block(BATTMONITOR_SMBUS_MAXELL_MANUFACTURE_NAME, buff, true)) {
|
||||
// In Hitachi maxell battery, specification info is 0x31 (SBSv1.1 with PEC support) but PEC isn't support
|
||||
// Hitachi maxell batteries do not support PEC
|
||||
if (strcmp((char*)buff, "Hitachi maxell") == 0) {
|
||||
_pec_support = false;
|
||||
_pec_supported = false;
|
||||
_pec_confirmed = true;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
_pec_support = true;
|
||||
return false;
|
||||
// assume all other batteries support PEC
|
||||
_pec_supported = true;
|
||||
_pec_confirmed = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
/// get_PEC - calculate packet error correction code of buffer
|
||||
|
|
|
@ -22,17 +22,13 @@ private:
|
|||
|
||||
void timer(void);
|
||||
|
||||
bool _pec_support = false;
|
||||
|
||||
// it sets true after check if PEC is used
|
||||
bool _pec_confirmed = false;
|
||||
|
||||
// read word from register
|
||||
// returns true if read was successful, false if failed
|
||||
bool read_word(uint8_t reg, uint16_t& data) const;
|
||||
|
||||
// get PEC support with the version value in SpecificationInfo() function
|
||||
bool get_pec_support();
|
||||
// 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;
|
||||
|
@ -42,4 +38,6 @@ private:
|
|||
uint8_t get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const;
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
||||
uint8_t _pec_confirmed; // count of the number of times PEC has been confirmed as working
|
||||
bool _pec_supported; // true if pec is supported
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue