|
|
@ -2,8 +2,10 @@ |
|
|
|
|
|
|
|
|
|
|
|
#define AP_BATTMONITOR_SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation
|
|
|
|
#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_SERIAL 0x1C // serial number
|
|
|
|
#define BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY 0x10 // full charge capacity
|
|
|
|
|
|
|
|
#define BATTMONITOR_SMBUS_SERIAL 0x1C // serial number
|
|
|
|
|
|
|
|
|
|
|
|
AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon, |
|
|
|
AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon, |
|
|
|
AP_BattMonitor::BattMonitor_State &mon_state, |
|
|
|
AP_BattMonitor::BattMonitor_State &mon_state, |
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev) |
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev) |
|
|
@ -11,6 +13,7 @@ AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon, |
|
|
|
_dev(std::move(dev)) |
|
|
|
_dev(std::move(dev)) |
|
|
|
{ |
|
|
|
{ |
|
|
|
_mon._serial_numbers[_state.instance] = AP_BATT_SERIAL_NUMBER_DEFAULT; |
|
|
|
_mon._serial_numbers[_state.instance] = AP_BATT_SERIAL_NUMBER_DEFAULT; |
|
|
|
|
|
|
|
_mon._pack_capacity[_state.instance] = 0; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/// read the battery_voltage and current, should be called at 10hz
|
|
|
|
/// read the battery_voltage and current, should be called at 10hz
|
|
|
@ -22,6 +25,25 @@ void AP_BattMonitor_SMBus::read(void) |
|
|
|
if (_serial_number != _mon._serial_numbers[_state.instance]) { |
|
|
|
if (_serial_number != _mon._serial_numbers[_state.instance]) { |
|
|
|
_mon._serial_numbers[_state.instance].set_and_notify(_serial_number); |
|
|
|
_mon._serial_numbers[_state.instance].set_and_notify(_serial_number); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (_full_charge_capacity != _mon._pack_capacity[_state.instance]) { |
|
|
|
|
|
|
|
_mon._pack_capacity[_state.instance].set_and_notify(_full_charge_capacity); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// reads the pack full charge capacity
|
|
|
|
|
|
|
|
// returns true if the read was successful, or if we already knew the pack capacity
|
|
|
|
|
|
|
|
bool AP_BattMonitor_SMBus::read_full_charge_capacity(void) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
uint16_t data; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (_full_charge_capacity != 0) { |
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} else if (read_word(BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY, data)) { |
|
|
|
|
|
|
|
_full_charge_capacity = data; |
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
return false; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// reads the temperature word from the battery
|
|
|
|
// reads the temperature word from the battery
|
|
|
|