mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: print unhealthy message if battery backend not as expected
a backend which fails to allocate, or where the user has changed the backend type without rebooting will cause an "unhealthy" message to be emitted
This commit is contained in:
parent
4b5f490e9f
commit
721a9b846e
|
@ -1019,8 +1019,19 @@ bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const
|
|||
{
|
||||
char temp_buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
|
||||
|
||||
for (uint8_t i = 0; i < _num_instances; i++) {
|
||||
if (drivers[i] != nullptr && !(drivers[i]->arming_checks(temp_buffer, sizeof(temp_buffer)))) {
|
||||
for (uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) {
|
||||
const auto expected_type = configured_type(i);
|
||||
|
||||
if (drivers[i] == nullptr && expected_type == Type::NONE) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (drivers[i] == nullptr || allocated_type(i) != expected_type) {
|
||||
hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, "unhealthy");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!drivers[i]->arming_checks(temp_buffer, sizeof(temp_buffer))) {
|
||||
hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, temp_buffer);
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue