mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BattMonitor: Provide the time remaining
This commit is contained in:
parent
5125874681
commit
bf1a17825c
@ -568,6 +568,16 @@ bool AP_BattMonitor::capacity_remaining_pct(uint8_t &percentage, uint8_t instanc
|
||||
return false;
|
||||
}
|
||||
|
||||
/// time_remaining - returns remaining battery time
|
||||
bool AP_BattMonitor::time_remaining(uint32_t &seconds, uint8_t instance) const
|
||||
{
|
||||
if (instance < _num_instances && drivers[instance] != nullptr && state[instance].has_time_remaining) {
|
||||
seconds = state[instance].time_remaining;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
|
||||
int32_t AP_BattMonitor::pack_capacity_mah(uint8_t instance) const
|
||||
{
|
||||
|
@ -136,6 +136,8 @@ public:
|
||||
bool healthy; // battery monitor is communicating correctly
|
||||
bool is_powering_off; // true when power button commands power off
|
||||
bool powerOffNotified; // only send powering off notification once
|
||||
uint32_t time_remaining; // remaining battery time
|
||||
bool has_time_remaining; // time_remaining is only valid if this is true
|
||||
const struct AP_Param::GroupInfo *var_info;
|
||||
};
|
||||
|
||||
@ -177,6 +179,9 @@ public:
|
||||
virtual bool capacity_remaining_pct(uint8_t &percentage, uint8_t instance) const WARN_IF_UNUSED;
|
||||
bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED { return capacity_remaining_pct(percentage, AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// time_remaining - returns remaining battery time
|
||||
bool time_remaining(uint32_t &seconds, const uint8_t instance = AP_BATT_PRIMARY_INSTANCE) const WARN_IF_UNUSED;
|
||||
|
||||
/// pack_capacity_mah - returns the capacity of the battery pack in mAh when the pack is full
|
||||
int32_t pack_capacity_mah(uint8_t instance) const;
|
||||
int32_t pack_capacity_mah() const { return pack_capacity_mah(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
@ -34,6 +34,9 @@ public:
|
||||
// read the latest battery voltage
|
||||
virtual void read() = 0;
|
||||
|
||||
/// returns true if battery monitor instance provides time remaining info
|
||||
virtual bool has_time_remaining() const { return false; }
|
||||
|
||||
/// returns true if battery monitor instance provides consumed energy info
|
||||
virtual bool has_consumed_energy() const { return false; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user