mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: Fetch remaining capacity
This commit is contained in:
parent
c389dd93d7
commit
f026438f22
|
@ -2,7 +2,8 @@
|
|||
|
||||
#define AP_BATTMONITOR_SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation
|
||||
|
||||
#define BATTMONITOR_SMBUS_TEMP 0x08 // temperature register
|
||||
#define BATTMONITOR_SMBUS_TEMP 0x08 // temperature register
|
||||
#define BATTMONITOR_SMBUS_REMAINING_CAPACITY 0x0F // remaining capacity
|
||||
#define BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY 0x10 // full charge capacity
|
||||
#define BATTMONITOR_SMBUS_SERIAL 0x1C // serial number
|
||||
|
||||
|
@ -46,6 +47,24 @@ bool AP_BattMonitor_SMBus::read_full_charge_capacity(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
// reads the remaining capacity
|
||||
// returns true if the read was succesful, which is only considered to be the
|
||||
// we know the full charge capacity
|
||||
bool AP_BattMonitor_SMBus::read_remaining_capacity(void)
|
||||
{
|
||||
int32_t capacity = get_capacity();
|
||||
|
||||
if (capacity > 0) {
|
||||
uint16_t data;
|
||||
if (read_word(BATTMONITOR_SMBUS_REMAINING_CAPACITY, data)) {
|
||||
_state.current_total_mah = MAX(0, capacity - data);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
// reads the temperature word from the battery
|
||||
// returns true if the read was successful
|
||||
bool AP_BattMonitor_SMBus::read_temp(void)
|
||||
|
|
|
@ -32,6 +32,11 @@ protected:
|
|||
// returns true if the read was successful, or if we already knew the pack capacity
|
||||
bool read_full_charge_capacity(void);
|
||||
|
||||
// reads the remaining capacity
|
||||
// returns true if the read was succesful, which is only considered to be the
|
||||
// we know the full charge capacity
|
||||
bool read_remaining_capacity(void);
|
||||
|
||||
// reads the temperature word from the battery
|
||||
// returns true if the read was successful
|
||||
bool read_temp(void);
|
||||
|
|
|
@ -84,6 +84,9 @@ void AP_BattMonitor_SMBus_Maxell::timer()
|
|||
|
||||
read_full_charge_capacity();
|
||||
|
||||
// FIXME: Preform current integration if the remaining capacity can't be requested
|
||||
read_remaining_capacity();
|
||||
|
||||
read_temp();
|
||||
|
||||
read_serial_number();
|
||||
|
|
|
@ -6,7 +6,6 @@
|
|||
#include "AP_BattMonitor_SMBus_Solo.h"
|
||||
#include <utility>
|
||||
|
||||
#define BATTMONITOR_SMBUS_SOLO_REMAINING_CAPACITY 0x0f // predicted remaining battery capacity in milliamps
|
||||
#define BATTMONITOR_SMBUS_SOLO_MANUFACTURE_DATA 0x23 /// manufacturer data
|
||||
#define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE 0x28 // cell voltage register
|
||||
#define BATTMONITOR_SMBUS_SOLO_CURRENT 0x2a // current register
|
||||
|
@ -39,7 +38,6 @@ AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon,
|
|||
|
||||
void AP_BattMonitor_SMBus_Solo::timer()
|
||||
{
|
||||
uint16_t data;
|
||||
uint8_t buff[8];
|
||||
uint32_t tnow = AP_HAL::micros();
|
||||
|
||||
|
@ -74,14 +72,8 @@ void AP_BattMonitor_SMBus_Solo::timer()
|
|||
_state.last_time_micros = tnow;
|
||||
}
|
||||
|
||||
if (read_full_charge_capacity()) {
|
||||
// only read remaining capacity once we have the full capacity
|
||||
if (get_capacity() > 0) {
|
||||
if (read_word(BATTMONITOR_SMBUS_SOLO_REMAINING_CAPACITY, data)) {
|
||||
_state.current_total_mah = MAX(0, get_capacity() - data);
|
||||
}
|
||||
}
|
||||
}
|
||||
read_full_charge_capacity();
|
||||
read_remaining_capacity();
|
||||
|
||||
// read the button press indicator
|
||||
if (read_block(BATTMONITOR_SMBUS_SOLO_MANUFACTURE_DATA, buff, 6, false) == 6) {
|
||||
|
|
Loading…
Reference in New Issue