diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index a49fed225b..1e103e9e71 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -168,19 +168,13 @@ void Sub::Log_Write_Data(LogDataID id, float value) } } -// logs when baro or compass becomes unhealthy +// logs when compass becomes unhealthy void Sub::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(); diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index c55a6cd1a3..fbc32e7e1a 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -40,7 +40,6 @@ Sub::Sub() param_loader(var_info) { // init sensor error logging flags - sensor_health.baro = true; sensor_health.compass = true; #if CONFIG_HAL_BOARD != HAL_BOARD_SITL diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 028a97c4f7..91745bfad9 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -233,7 +233,6 @@ private: // sensor health for logging struct { - uint8_t baro : 1; // true if any single baro is healthy uint8_t depth : 1; // true if depth sensor is healthy uint8_t compass : 1; // true if compass is healthy } sensor_health;