mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: move error logging of sensor health into AP_Baro
This commit is contained in:
parent
b2d811a444
commit
d9f605ed36
|
@ -851,6 +851,10 @@ void AP_Baro::update(void)
|
|||
_alt_offset_active = _alt_offset;
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
bool old_primary_healthy = sensors[_primary].healthy;
|
||||
#endif
|
||||
|
||||
for (uint8_t i=0; i<_num_drivers; i++) {
|
||||
drivers[i]->backend_update(i);
|
||||
}
|
||||
|
@ -905,6 +909,16 @@ void AP_Baro::update(void)
|
|||
if (should_log()) {
|
||||
Write_Baro();
|
||||
}
|
||||
|
||||
#define MASK_LOG_ANY 0xFFFF
|
||||
|
||||
// log sensor healthy state change:
|
||||
if (sensors[_primary].healthy != old_primary_healthy) {
|
||||
if (AP::logger().should_log(MASK_LOG_ANY)) {
|
||||
const LogErrorCode code = sensors[_primary].healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY;
|
||||
AP::logger().Write_Error(LogErrorSubsystem::BARO, code);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue