AP_BattMonitor: SMBus remove unused bool returns

This commit is contained in:
Josh Henderson 2021-07-14 02:52:59 -04:00 committed by WickedShell
parent 0d64782220
commit 84fb03cb79
4 changed files with 32 additions and 48 deletions

View File

@ -46,71 +46,61 @@ void AP_BattMonitor_SMBus::read(void)
}
// 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)
// returns if we already knew the pack capacity
void AP_BattMonitor_SMBus::read_full_charge_capacity(void)
{
if (_full_charge_capacity != 0) {
return true;
return;
}
if (read_word(BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY, _full_charge_capacity)) {
_full_charge_capacity *= get_capacity_scaler();
return true;
}
return false;
}
// reads the remaining capacity
// returns true if the read was successful, which is only considered to be the
// we know the full charge capacity
bool AP_BattMonitor_SMBus::read_remaining_capacity(void)
// which will only be read if we know the full charge capacity (accounting for battery degradation)
void AP_BattMonitor_SMBus::read_remaining_capacity(void)
{
int32_t capacity = _params._pack_capacity;
if (capacity > 0) {
uint16_t data;
if (read_word(BATTMONITOR_SMBUS_REMAINING_CAPACITY, data)) {
_state.consumed_mah = MAX(0, capacity - (data * get_capacity_scaler()));
return true;
}
if (capacity <= 0) {
return;
}
return false;
uint16_t data;
if (read_word(BATTMONITOR_SMBUS_REMAINING_CAPACITY, data)) {
_state.consumed_mah = MAX(0, capacity - (data * get_capacity_scaler()));
}
}
// reads the temperature word from the battery
// returns true if the read was successful
bool AP_BattMonitor_SMBus::read_temp(void)
void AP_BattMonitor_SMBus::read_temp(void)
{
uint16_t data;
if (read_word(BATTMONITOR_SMBUS_TEMP, data)) {
if (!read_word(BATTMONITOR_SMBUS_TEMP, data)) {
_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
_state.temperature_time = AP_HAL::millis();
_state.temperature = ((float)(data - 2731)) * 0.1f;
return true;
return;
}
_has_temperature = false;
_has_temperature = true;
return false;
_state.temperature_time = AP_HAL::millis();
_state.temperature = (data * 0.1f) - C_TO_KELVIN;
}
// reads the serial number if it's not already known
// returns true if the read was successful or the number was already known
bool AP_BattMonitor_SMBus::read_serial_number(void)
// returns if the serial number was already known
void AP_BattMonitor_SMBus::read_serial_number(void)
{
uint16_t data;
// don't recheck the serial number if we already have it
if (_serial_number != -1) {
return true;
} else if (read_word(BATTMONITOR_SMBUS_SERIAL, data)) {
_serial_number = data;
return true;
return;
}
return false;
uint16_t data;
if (read_word(BATTMONITOR_SMBUS_SERIAL, data)) {
_serial_number = data;
}
}
// reads the battery's cycle count

View File

@ -59,24 +59,21 @@ protected:
void read(void) override;
// reads the pack full charge capacity
// returns true if the read was successful, or if we already knew the pack capacity
bool read_full_charge_capacity(void);
void read_full_charge_capacity(void);
// reads the remaining capacity
// returns true if the read was successful, which is only considered to be the
// we know the full charge capacity
bool read_remaining_capacity(void);
// which will only be read if we know the full charge capacity (accounting for battery degradation)
void read_remaining_capacity(void);
// return a scaler that should be multiplied by the battery's reported capacity numbers to arrive at the actual capacity in mAh
virtual uint16_t get_capacity_scaler() const { return 1; }
// reads the temperature word from the battery
// returns true if the read was successful
virtual bool read_temp(void);
virtual void read_temp(void);
// reads the serial number if it's not already known
// returns true if the read was successful, or the number was already known
bool read_serial_number(void);
// returns if the serial number was already known
void read_serial_number(void);
// reads the battery's cycle count
void read_cycle_count();

View File

@ -6,7 +6,7 @@
#define BATTMONITOR_SMBUS_TEMP_EXT 0x07
// return the maximum of the internal and external temperature sensors
bool AP_BattMonitor_SMBus_Rotoye::read_temp(void) {
void AP_BattMonitor_SMBus_Rotoye::read_temp(void) {
uint16_t t_int, t_ext;
@ -18,8 +18,5 @@ bool AP_BattMonitor_SMBus_Rotoye::read_temp(void) {
_state.temperature_time = AP_HAL::millis();
t = ((t_ext > t_int) ? t_ext : t_int);
_state.temperature = 0.1f * (float)t - C_TO_KELVIN;
return true;
}
return false;
}

View File

@ -9,6 +9,6 @@ class AP_BattMonitor_SMBus_Rotoye : public AP_BattMonitor_SMBus_Generic
private:
// Rotoye Batmon has two temperature readings
bool read_temp(void) override;
void read_temp(void) override;
};