From de65762b85af639980d914d4bb3d8dc8296dc404 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Wed, 11 Sep 2024 12:02:32 +1000 Subject: [PATCH] AP_EFI: Hirth: remove crankshaft sensor status There is no crankshaft sensor status reported by this EFI. This line is misleading and should be removed. The sensor health bitmask is already logged elsewhere. --- libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp index 59abce994f..37ca36f333 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp @@ -33,7 +33,6 @@ #define ENGINE_RUNNING 4 #define THROTTLE_POSITION_FACTOR 10 -#define CRANK_SHAFT_SENSOR_OK 0x0F #define INJECTION_TIME_RESOLUTION 0.8 #define THROTTLE_POSITION_RESOLUTION 0.1 #define VOLTAGE_RESOLUTION 0.0049 /* 5/1024 */ @@ -301,7 +300,6 @@ void AP_EFI_Serial_Hirth::decode_data() // EFI2 log internal_state.engine_state = (Engine_State)record1->engine_status; - internal_state.crankshaft_sensor_status = (record1->sensor_ok & CRANK_SHAFT_SENSOR_OK) ? Crankshaft_Sensor_Status::OK : Crankshaft_Sensor_Status::ERROR; // ECYL log internal_state.cylinder_status.injection_time_ms = record1->injection_time * INJECTION_TIME_RESOLUTION;