mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_BattMonitor: move has_current to backend
This commit is contained in:
parent
f02bfab7fe
commit
989677ddfd
@ -243,12 +243,8 @@ bool AP_BattMonitor::is_powering_off(uint8_t instance) const {
|
||||
/// has_current - returns true if battery monitor instance provides current info
|
||||
bool AP_BattMonitor::has_current(uint8_t instance) const
|
||||
{
|
||||
// check for analog voltage and current monitor or smbus monitor
|
||||
if (instance < _num_instances && drivers[instance] != nullptr) {
|
||||
return (_monitoring[instance] == BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT ||
|
||||
_monitoring[instance] == BattMonitor_TYPE_SOLO ||
|
||||
_monitoring[instance] == BattMonitor_TYPE_BEBOP ||
|
||||
_monitoring[instance] == BattMonitor_TYPE_MAXELL);
|
||||
if (instance < _num_instances && drivers[instance] != nullptr && _monitoring[instance] != BattMonitor_TYPE_NONE) {
|
||||
return drivers[instance]->has_current();
|
||||
}
|
||||
|
||||
// not monitoring current
|
||||
|
@ -28,7 +28,7 @@ AP_BattMonitor_Analog::read()
|
||||
_state.voltage = _volt_pin_analog_source->voltage_average() * _mon._volt_multiplier[_state.instance];
|
||||
|
||||
// read current
|
||||
if (_mon.has_current(_state.instance)) {
|
||||
if (has_current()) {
|
||||
// calculate time since last current read
|
||||
uint32_t tnow = AP_HAL::micros();
|
||||
float dt = tnow - _state.last_time_micros;
|
||||
@ -49,3 +49,9 @@ AP_BattMonitor_Analog::read()
|
||||
_state.last_time_micros = tnow;
|
||||
}
|
||||
}
|
||||
|
||||
/// return true if battery provides current info
|
||||
bool AP_BattMonitor_Analog::has_current() const
|
||||
{
|
||||
return (_mon.get_type(_state.instance) == AP_BattMonitor::BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT);
|
||||
}
|
||||
|
@ -87,6 +87,9 @@ public:
|
||||
/// Read the battery voltage and current. Should be called at 10hz
|
||||
void read();
|
||||
|
||||
/// returns true if battery monitor provides current info
|
||||
bool has_current() const override;
|
||||
|
||||
protected:
|
||||
|
||||
AP_HAL::AnalogSource *_volt_pin_analog_source;
|
||||
|
@ -34,6 +34,9 @@ public:
|
||||
// read the latest battery voltage
|
||||
virtual void read() = 0;
|
||||
|
||||
/// returns true if battery monitor instance provides current info
|
||||
virtual bool has_current() const = 0;
|
||||
|
||||
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
|
||||
uint8_t capacity_remaining_pct() const;
|
||||
|
||||
|
@ -37,6 +37,9 @@ public:
|
||||
// read the latest battery voltage
|
||||
void read() override;
|
||||
|
||||
// bebop provides current info
|
||||
bool has_current() const override { return true; };
|
||||
|
||||
private:
|
||||
float _prev_vbat_raw;
|
||||
float _prev_vbat;
|
||||
|
@ -23,6 +23,8 @@ public:
|
||||
// virtual destructor to reduce compiler warnings
|
||||
virtual ~AP_BattMonitor_SMBus() {}
|
||||
|
||||
// all smart batteries provide current info
|
||||
bool has_current() const override { return true; }
|
||||
|
||||
protected:
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user