From 6aa7cc5d497d599fb10bfbed2a03e71f7078b0d8 Mon Sep 17 00:00:00 2001 From: Pradeep CK Date: Thu, 1 Aug 2024 12:37:21 +1000 Subject: [PATCH] EFI : correct hirth EFI log messages 1. ECYL - state.cylinder_status.exhaust_gas_temperature2, format changed from B(uint8_t) to f(float) 2. Sensor_ok - showing OK, when engine_temperature_sensor_status = 0 --- libraries/AP_EFI/AP_EFI.cpp | 2 +- libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI.cpp b/libraries/AP_EFI/AP_EFI.cpp index 9338a50596..42f5b5a880 100644 --- a/libraries/AP_EFI/AP_EFI.cpp +++ b/libraries/AP_EFI/AP_EFI.cpp @@ -240,7 +240,7 @@ void AP_EFI::log_status(void) "TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX", "s#dsOO-OO-", "F-0C000000", - "QBfffffBff", + "QBffffffff", AP_HAL::micros64(), 0, state.cylinder_status.ignition_timing_deg, diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp index 6a2e4c94c0..a90b95aa77 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp @@ -300,7 +300,7 @@ 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; + 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;