AP_BattMonitor: add cycle count for smbus batteries

This commit is contained in:
Randy Mackay 2019-12-11 09:55:20 +09:00
parent ede5cabbf5
commit 30a0f22d13
7 changed files with 55 additions and 6 deletions

View File

@ -446,6 +446,15 @@ bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance)
} }
} }
// return true if cycle count can be provided and fills in cycles argument
bool AP_BattMonitor::get_cycle_count(uint8_t instance, uint16_t &cycles) const
{
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES || (drivers[instance] == nullptr)) {
return false;
}
return drivers[instance]->get_cycle_count(cycles);
}
bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const
{ {
char temp_buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; char temp_buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};

View File

@ -152,9 +152,12 @@ public:
const cells & get_cell_voltages(const uint8_t instance) const; const cells & get_cell_voltages(const uint8_t instance) const;
// temperature // temperature
bool get_temperature(float &temperature) const { return get_temperature(temperature, AP_BATT_PRIMARY_INSTANCE); }; bool get_temperature(float &temperature) const { return get_temperature(temperature, AP_BATT_PRIMARY_INSTANCE); }
bool get_temperature(float &temperature, const uint8_t instance) const; bool get_temperature(float &temperature, const uint8_t instance) const;
// cycle count
bool get_cycle_count(uint8_t instance, uint16_t &cycles) const;
// get battery resistance estimate in ohms // get battery resistance estimate in ohms
float get_resistance() const { return get_resistance(AP_BATT_PRIMARY_INSTANCE); } float get_resistance() const { return get_resistance(AP_BATT_PRIMARY_INSTANCE); }
float get_resistance(uint8_t instance) const { return state[instance].resistance; } float get_resistance(uint8_t instance) const { return state[instance].resistance; }

View File

@ -46,6 +46,9 @@ public:
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100) /// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t capacity_remaining_pct() const; uint8_t capacity_remaining_pct() const;
// return true if cycle count can be provided and fills in cycles argument
virtual bool get_cycle_count(uint16_t &cycles) const { return false; }
/// get voltage with sag removed (based on battery current draw and resistance) /// get voltage with sag removed (based on battery current draw and resistance)
/// this will always be greater than or equal to the raw voltage /// this will always be greater than or equal to the raw voltage
float voltage_resting_estimate() const; float voltage_resting_estimate() const;

View File

@ -13,12 +13,23 @@ AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon,
_params._pack_capacity = 0; _params._pack_capacity = 0;
} }
void AP_BattMonitor_SMBus::init(void) { void AP_BattMonitor_SMBus::init(void)
{
if (_dev) { if (_dev) {
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus::timer, void)); _dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus::timer, void));
} }
} }
// return true if cycle count can be provided and fills in cycles argument
bool AP_BattMonitor_SMBus::get_cycle_count(uint16_t &cycles) const
{
if (!_has_cycle_count) {
return false;
}
cycles = _cycle_count;
return true;
}
/// read the battery_voltage and current, should be called at 10hz /// read the battery_voltage and current, should be called at 10hz
void AP_BattMonitor_SMBus::read(void) void AP_BattMonitor_SMBus::read(void)
{ {
@ -83,7 +94,8 @@ bool AP_BattMonitor_SMBus::read_temp(void)
// reads the serial number if it's not already known // reads the serial number if it's not already known
// returns true if the read was successful or the number was already known // returns true if the read was successful or the number was already known
bool AP_BattMonitor_SMBus::read_serial_number(void) { bool AP_BattMonitor_SMBus::read_serial_number(void)
{
uint16_t data; uint16_t data;
// don't recheck the serial number if we already have it // don't recheck the serial number if we already have it
@ -97,6 +109,16 @@ bool AP_BattMonitor_SMBus::read_serial_number(void) {
return false; return false;
} }
// reads the battery's cycle count
void AP_BattMonitor_SMBus::read_cycle_count()
{
// only read cycle count once
if (_has_cycle_count) {
return;
}
_has_cycle_count = read_word(BATTMONITOR_SMBUS_CYCLE_COUNT, _cycle_count);
}
// read word from register // read word from register
// returns true if read was successful, false if failed // returns true if read was successful, false if failed
bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const

View File

@ -22,6 +22,7 @@ public:
BATTMONITOR_SMBUS_CURRENT = 0x0A, // Current BATTMONITOR_SMBUS_CURRENT = 0x0A, // Current
BATTMONITOR_SMBUS_REMAINING_CAPACITY = 0x0F, // Remaining Capacity BATTMONITOR_SMBUS_REMAINING_CAPACITY = 0x0F, // Remaining Capacity
BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY = 0x10, // Full Charge Capacity BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY = 0x10, // Full Charge Capacity
BATTMONITOR_SMBUS_CYCLE_COUNT = 0x17, // Cycle Count
BATTMONITOR_SMBUS_SPECIFICATION_INFO = 0x1A, // Specification Info BATTMONITOR_SMBUS_SPECIFICATION_INFO = 0x1A, // Specification Info
BATTMONITOR_SMBUS_SERIAL = 0x1C, // Serial Number BATTMONITOR_SMBUS_SERIAL = 0x1C, // Serial Number
BATTMONITOR_SMBUS_MANUFACTURE_NAME = 0x20, // Manufacture Name BATTMONITOR_SMBUS_MANUFACTURE_NAME = 0x20, // Manufacture Name
@ -45,6 +46,9 @@ public:
// don't allow reset of remaining capacity for SMBus // don't allow reset of remaining capacity for SMBus
bool reset_remaining(float percentage) override { return false; } bool reset_remaining(float percentage) override { return false; }
// return true if cycle count can be provided and fills in cycles argument
bool get_cycle_count(uint16_t &cycles) const override;
void init(void) override; void init(void) override;
protected: protected:
@ -68,6 +72,9 @@ protected:
// returns true if the read was successful, or the number was already known // returns true if the read was successful, or the number was already known
bool read_serial_number(void); bool read_serial_number(void);
// reads the battery's cycle count
void read_cycle_count();
// read word from register // read word from register
// returns true if read was successful, false if failed // returns true if read was successful, false if failed
bool read_word(uint8_t reg, uint16_t& data) const; bool read_word(uint8_t reg, uint16_t& data) const;
@ -81,8 +88,9 @@ protected:
int32_t _serial_number = -1; // battery serial number int32_t _serial_number = -1; // battery serial number
uint16_t _full_charge_capacity; // full charge capacity, used to stash the value before setting the parameter uint16_t _full_charge_capacity; // full charge capacity, used to stash the value before setting the parameter
bool _has_cell_voltages; // smbus backends flag this as true once they have received a valid cell voltage report
bool _has_cell_voltages; // smbus backends flag this as true once they have recieved a valid cell voltage report uint16_t _cycle_count = 0; // number of cycles the battery has experienced. An amount of discharge approximately equal to the value of DesignCapacity.
bool _has_cycle_count; // true if cycle count has been retrieved from the battery
virtual void timer(void) = 0; // timer function to read from the battery virtual void timer(void) = 0; // timer function to read from the battery

View File

@ -85,6 +85,8 @@ void AP_BattMonitor_SMBus_Maxell::timer()
read_temp(); read_temp();
read_serial_number(); read_serial_number();
read_cycle_count();
} }
// read_block - returns number of characters read if successful, zero if unsuccessful // read_block - returns number of characters read if successful, zero if unsuccessful

View File

@ -93,6 +93,8 @@ void AP_BattMonitor_SMBus_Solo::timer()
read_temp(); read_temp();
read_serial_number(); read_serial_number();
read_cycle_count();
} }
// read_block - returns number of characters read if successful, zero if unsuccessful // read_block - returns number of characters read if successful, zero if unsuccessful