mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BattMonitor: Get pack_capacity_mah function
This commit is contained in:
parent
a9b01b470c
commit
ec157bd4c2
@ -269,7 +269,17 @@ uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
|
||||
}
|
||||
}
|
||||
|
||||
/// exhausted - returns true if the voltage remains below the low_voltage for 10 seconds or remaining capacity falls below min_capacity_mah
|
||||
/// 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
|
||||
{
|
||||
if (instance < AP_BATT_MONITOR_MAX_INSTANCES) {
|
||||
return _pack_capacity[instance];
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/// exhausted - returns true if the voltage remains below the low_voltage for 10 seconds or remaining capacity falls below min_capacity_mah
|
||||
bool AP_BattMonitor::exhausted(uint8_t instance, float low_voltage, float min_capacity_mah)
|
||||
{
|
||||
// exit immediately if no monitors setup
|
||||
|
@ -94,6 +94,10 @@ public:
|
||||
virtual uint8_t capacity_remaining_pct(uint8_t instance) const;
|
||||
uint8_t capacity_remaining_pct() const { return capacity_remaining_pct(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
/// 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); }
|
||||
|
||||
/// exhausted - returns true if the battery's voltage remains below the low_voltage for 10 seconds or remaining capacity falls below min_capacity
|
||||
bool exhausted(uint8_t instance, float low_voltage, float min_capacity_mah);
|
||||
bool exhausted(float low_voltage, float min_capacity_mah) { return exhausted(AP_BATT_PRIMARY_INSTANCE, low_voltage, min_capacity_mah); }
|
||||
|
Loading…
Reference in New Issue
Block a user