From 6830092a7d539982354fbf4a19eec889a96bbe09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 27 Apr 2022 20:57:42 +1000 Subject: [PATCH] ArduCopter: move error logging of sensor health into AP_Baro --- ArduCopter/Copter.cpp | 1 - ArduCopter/Copter.h | 1 - ArduCopter/Log.cpp | 9 +-------- 3 files changed, 1 insertion(+), 10 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 51c855281d..705ccafae7 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -744,7 +744,6 @@ Copter::Copter(void) flightmode(&mode_stabilize) { // init sensor error logging flags - sensor_health.baro = true; sensor_health.compass = true; } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3649582832..574e550a3c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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; diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 6eeeecbc60..215e249e63 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -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();