ArduSub: move error logging of sensor health into AP_Baro

This commit is contained in:
Peter Barker 2022-04-27 21:10:45 +10:00 committed by Peter Barker
parent 6830092a7d
commit 5a4963e4f8
3 changed files with 1 additions and 9 deletions

View File

@ -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();

View File

@ -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

View File

@ -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;