AP_BattMonitor: added reset_remaining() API

used to allow battery swap before takeoff
This commit is contained in:
Andrew Tridgell 2019-06-18 19:30:18 +10:00
parent 0c7fb21c12
commit 11518857b6
6 changed files with 46 additions and 0 deletions

View File

@ -494,6 +494,21 @@ void AP_BattMonitor::checkPoweringOff(void)
}
}
/*
reset battery remaining percentage for batteries that integrate to
calculate percentage remaining
*/
bool AP_BattMonitor::reset_remaining(uint16_t battery_mask, float percentage)
{
bool ret = true;
for (uint8_t i = 0; i < _num_instances; i++) {
if ((1U<<i) & battery_mask) {
ret &= drivers[i]->reset_remaining(percentage);
}
}
return ret;
}
namespace AP {
AP_BattMonitor &battery()

View File

@ -167,6 +167,9 @@ public:
// sends powering off mavlink broadcasts and sets notify flag
void checkPoweringOff(void);
// reset battery remaining percentage
bool reset_remaining(uint16_t battery_mask, float percentage);
static const struct AP_Param::GroupInfo var_info[];
protected:

View File

@ -215,3 +215,22 @@ void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_c
low_capacity = false;
}
}
/*
default implementation for reset_remaining(). This sets consumed_wh
and consumed_mah based on the given percentage. Use percentage=100
for a full battery
*/
bool AP_BattMonitor_Backend::reset_remaining(float percentage)
{
percentage = constrain_float(percentage, 0, 100);
const float used_proportion = (100 - percentage) * 0.01;
_state.consumed_mah = used_proportion * _params._pack_capacity;
// without knowing the history we can't do consumed_wh
// accurately. Best estimate is based on current voltage. This
// will be good when resetting the battery to a value close to
// full charge
_state.consumed_wh = _state.consumed_mah * 1000 * _state.voltage;
return true;
}

View File

@ -59,6 +59,9 @@ public:
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
bool arming_checks(char * buffer, size_t buflen) const;
// reset remaining percentage to given value
virtual bool reset_remaining(float percentage);
protected:
AP_BattMonitor &_mon; // reference to front-end
AP_BattMonitor::BattMonitor_State &_state; // reference to this instances state (held in the front-end)

View File

@ -40,6 +40,9 @@ public:
// bebop provides current info
bool has_current() const override { return true; };
// don't allow reset of remaining capacity for bebop battery
bool reset_remaining(float percentage) override { return false; }
private:
float _prev_vbat_raw;
float _prev_vbat;

View File

@ -42,6 +42,9 @@ public:
// all smart batteries are expected to provide current
bool has_current() const override { return true; }
// don't allow reset of remaining capacity for SMBus
bool reset_remaining(float percentage) override { return false; }
void init(void) override;
protected: