AP_BattMonitor: add has_temperature method to Backend
This commit is contained in:
parent
b92b343d4e
commit
dfa8e55622
@ -488,12 +488,13 @@ const AP_BattMonitor::cells & AP_BattMonitor::get_cell_voltages(const uint8_t in
|
||||
// returns true if there is a temperature reading
|
||||
bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance) const
|
||||
{
|
||||
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES) {
|
||||
if (instance >= AP_BATT_MONITOR_MAX_INSTANCES || drivers[instance] == nullptr) {
|
||||
return false;
|
||||
} else {
|
||||
temperature = state[instance].temperature;
|
||||
return (AP_HAL::millis() - state[instance].temperature_time) <= AP_BATT_MONITOR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
temperature = state[instance].temperature;
|
||||
|
||||
return drivers[instance]->has_temperature();
|
||||
}
|
||||
|
||||
// return true if cycle count can be provided and fills in cycles argument
|
||||
|
@ -43,6 +43,9 @@ public:
|
||||
// returns true if battery monitor provides individual cell voltages
|
||||
virtual bool has_cell_voltages() const { return false; }
|
||||
|
||||
// returns true if battery monitor provides temperature
|
||||
virtual bool has_temperature() const { return false; }
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t capacity_remaining_pct() const;
|
||||
|
||||
|
@ -84,10 +84,14 @@ bool AP_BattMonitor_SMBus::read_temp(void)
|
||||
{
|
||||
uint16_t 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;
|
||||
}
|
||||
|
||||
_has_temperature = false;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
@ -41,6 +41,8 @@ public:
|
||||
|
||||
bool has_cell_voltages() const override { return _has_cell_voltages; }
|
||||
|
||||
bool has_temperature() const override { return _has_temperature; }
|
||||
|
||||
// all smart batteries are expected to provide current
|
||||
bool has_current() const override { return true; }
|
||||
|
||||
@ -95,6 +97,7 @@ protected:
|
||||
bool _has_cell_voltages; // smbus backends flag this as true once they have received 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
|
||||
bool _has_temperature;
|
||||
|
||||
virtual void timer(void) = 0; // timer function to read from the battery
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user