From 8a9a856de8ebe12e2ece567c351941f5ea005791 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 3 May 2022 11:49:56 +1000 Subject: [PATCH] ArduSub: move logging of compass ERR flags into AP_Compass --- ArduSub/ArduSub.cpp | 2 -- ArduSub/Log.cpp | 15 --------------- ArduSub/Sub.cpp | 3 --- ArduSub/Sub.h | 1 - 4 files changed, 21 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 08f47afe73..edfc63d4e0 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -68,8 +68,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { // camera mount's fast update FAST_TASK_CLASS(AP_Mount, &sub.camera_mount, update_fast), #endif - // log sensor health - FAST_TASK(Log_Sensor_Health), SCHED_TASK(fifty_hz_loop, 50, 75, 3), SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6), diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 1e103e9e71..c070163e47 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -168,20 +168,6 @@ void Sub::Log_Write_Data(LogDataID id, float value) } } -// logs when compass becomes unhealthy -void Sub::Log_Sensor_Health() -{ - if (!should_log(MASK_LOG_ANY)) { - return; - } - - // check compass - if (sensor_health.compass != compass.healthy()) { - sensor_health.compass = compass.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); - } -} - struct PACKED log_GuidedTarget { LOG_PACKET_HEADER; uint64_t time_us; @@ -320,7 +306,6 @@ void Sub::Log_Write_Data(LogDataID id, uint32_t value) {} void Sub::Log_Write_Data(LogDataID id, int16_t value) {} void Sub::Log_Write_Data(LogDataID id, uint16_t value) {} void Sub::Log_Write_Data(LogDataID id, float value) {} -void Sub::Log_Sensor_Health() {} void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} void Sub::Log_Write_Vehicle_Startup_Messages() {} diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index fbc32e7e1a..b3e055f1eb 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -39,9 +39,6 @@ Sub::Sub() circle_nav(inertial_nav, ahrs_view, pos_control), param_loader(var_info) { - // init sensor error logging flags - sensor_health.compass = true; - #if CONFIG_HAL_BOARD != HAL_BOARD_SITL failsafe.pilot_input = true; #endif diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 91745bfad9..2a061b8474 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -410,7 +410,6 @@ private: void Log_Write_Data(LogDataID id, int16_t value); void Log_Write_Data(LogDataID id, uint16_t value); void Log_Write_Data(LogDataID id, float value); - void Log_Sensor_Health(); void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); void Log_Write_Vehicle_Startup_Messages(); void load_parameters(void) override;