ArduCopter: move error logging of sensor health into AP_Baro

This commit is contained in:
Peter Barker 2022-04-27 20:57:42 +10:00 committed by Peter Barker
parent d9f605ed36
commit 6830092a7d
3 changed files with 1 additions and 10 deletions

View File

@ -744,7 +744,6 @@ Copter::Copter(void)
flightmode(&mode_stabilize)
{
// init sensor error logging flags
sensor_health.baro = true;
sensor_health.compass = true;
}

View File

@ -399,7 +399,6 @@ private:
// sensor health for logging
struct {
uint8_t baro : 1; // true if baro is healthy
uint8_t compass : 1; // true if compass is healthy
} sensor_health;

View File

@ -220,20 +220,13 @@ void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float t
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
}
// logs when baro or compass becomes unhealthy
// logs when compass becomes unhealthy
void Copter::Log_Sensor_Health()
{
if (!should_log(MASK_LOG_ANY)) {
return;
}
// check baro
if (sensor_health.baro != barometer.healthy()) {
sensor_health.baro = barometer.healthy();
AP::logger().Write_Error(LogErrorSubsystem::BARO,
(sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
}
// check compass
if (sensor_health.compass != compass.healthy()) {
sensor_health.compass = compass.healthy();