Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_EFI: Hirth: fix sensor health flags #28075

Merged
merged 2 commits into from
Sep 13, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 0 additions & 2 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down Expand Up @@ -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;
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,10 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend {
};

enum class Sensor_Status_Bitfield : uint8_t {
ENGINE_TEMP_SENSOR_OK = 1U<<0, // true if engine temperature sensor is OK
AIR_TEMP_SENSOR_OK = 1U<<1, // true if air temperature sensor is OK
AIR_PRESSURE_SENSOR_OK = 1U<<2, // true if intake air pressure sensor is OK
THROTTLE_SENSOR_OK = 1U<<3, // true if throttle sensor is OK
ENGINE_TEMP_SENSOR_OK = 1U<<1, // true if engine temperature sensor is OK
AIR_TEMP_SENSOR_OK = 1U<<2, // true if air temperature sensor is OK
AIR_PRESSURE_SENSOR_OK = 1U<<3, // true if intake air pressure sensor is OK
THROTTLE_SENSOR_OK = 1U<<4, // true if throttle sensor is OK
};

private:
Expand Down
Loading