Skip to content

Commit

Permalink
EFI : correct hirth EFI log messages
Browse files Browse the repository at this point in the history
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
  • Loading branch information
Pradeep-Carbonix authored and loki077 committed Sep 2, 2024
1 parent abeb3a3 commit 6aa7cc5
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_EFI/AP_EFI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 6aa7cc5

Please sign in to comment.