mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: make healthy() check all configured monitors
GCS reporting for SYS_STATUS should check all healthy, not just first backend
This commit is contained in:
parent
93ee9a4ac1
commit
ba10c0ae42
|
@ -740,6 +740,19 @@ uint32_t AP_BattMonitor::get_mavlink_fault_bitmask(const uint8_t instance) const
|
|||
return drivers[instance]->get_mavlink_fault_bitmask();
|
||||
}
|
||||
|
||||
/*
|
||||
check that all configured battery monitors are healthy
|
||||
*/
|
||||
bool AP_BattMonitor::healthy() const
|
||||
{
|
||||
for (uint8_t i=0; i< _num_instances; i++) {
|
||||
if (get_type(i) != Type::NONE && !healthy(i)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
namespace AP {
|
||||
|
||||
AP_BattMonitor &battery()
|
||||
|
|
|
@ -156,7 +156,9 @@ public:
|
|||
|
||||
// healthy - returns true if monitor is functioning
|
||||
bool healthy(uint8_t instance) const;
|
||||
bool healthy() const { return healthy(AP_BATT_PRIMARY_INSTANCE); }
|
||||
|
||||
// return true if all configured battery monitors are healthy
|
||||
bool healthy() const;
|
||||
|
||||
/// voltage - returns battery voltage in volts
|
||||
float voltage(uint8_t instance) const;
|
||||
|
|
Loading…
Reference in New Issue