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

Adding ThM (modified throttle send to engine) to EFIS log #27077

Merged
merged 1 commit into from
Aug 18, 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
57 changes: 22 additions & 35 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,6 +205,7 @@ void AP_EFI_Serial_Hirth::send_request()
bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
{
uint8_t computed_checksum = 0;
throttle_to_hirth = 0;

// clear buffer
memset(raw_data, 0, ARRAY_SIZE(raw_data));
Expand All @@ -214,15 +215,15 @@ bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
thr = linearise_throttle(thr);
#endif

const uint16_t throttle = thr * THROTTLE_POSITION_FACTOR;
throttle_to_hirth = thr * THROTTLE_POSITION_FACTOR;

uint8_t idx = 0;

// set Quantity + Code + "20 bytes of records to set" + Checksum
computed_checksum += raw_data[idx++] = QUANTITY_SET_VALUE;
computed_checksum += raw_data[idx++] = requested_code = CODE_SET_VALUE;
computed_checksum += raw_data[idx++] = throttle & 0xFF;
computed_checksum += raw_data[idx++] = (throttle >> 8) & 0xFF;
computed_checksum += raw_data[idx++] = throttle_to_hirth & 0xFF;
computed_checksum += raw_data[idx++] = (throttle_to_hirth >> 8) & 0xFF;

// checksum calculation
raw_data[QUANTITY_SET_VALUE - 1] = (256 - computed_checksum);
Expand Down Expand Up @@ -309,10 +310,7 @@ void AP_EFI_Serial_Hirth::decode_data()
// EFI3 log
internal_state.ignition_voltage = record1->battery_voltage * VOLTAGE_RESOLUTION;

engine_temperature_sensor_status = (record1->sensor_ok & 0x01) != 0;
air_temperature_sensor_status = (record1->sensor_ok & 0x02) != 0;
air_pressure_sensor_status = (record1->sensor_ok & 0x04) != 0;
throttle_sensor_status = (record1->sensor_ok & 0x08) != 0;
sensor_status = record1->sensor_ok;

// resusing mavlink variables as required for Hirth
// add in ADC voltage of MAP sensor > convert to MAP in kPa
Expand Down Expand Up @@ -344,10 +342,7 @@ void AP_EFI_Serial_Hirth::decode_data()
struct Record3 *record3 = (Record3*)raw_data;

// EFI3 Log
CHT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0007) != 0;
CHT_2_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0038) != 0;
EGT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x01C0) != 0;
EGT_2_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0E00) != 0;
error_excess_temperature = record3->error_excess_temperature_bitfield;

// ECYL log
internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(record3->excess_temperature_1);
Expand All @@ -369,36 +364,28 @@ void AP_EFI_Serial_Hirth::log_status(void)
// @LoggerMessage: EFIS
// @Description: Electronic Fuel Injection data - Hirth specific Status information
// @Field: TimeUS: Time since system startup
// @Field: ETS1: Status of EGT1 excess temperature error
// @Field: ETS2: Status of EGT2 excess temperature error
// @Field: CTS1: Status of CHT1 excess temperature error
// @Field: CTS2: Status of CHT2 excess temperature error
// @Field: ETSS: Status of Engine temperature sensor
// @Field: ATSS: Status of Air temperature sensor
// @Field: APSS: Status of Air pressure sensor
// @Field: TSS: Status of Temperature sensor
// @Field: CRCF: CRC failure count
// @Field: AckF: ACK failure count
// @Field: EET: Error Excess Temperature Bitfield
// @FieldBitmaskEnum: EET: AP_EFI_Serial_Hirth:::Error_Excess_Temp_Bitfield
// @Field: FLAG: Sensor Status Bitfield
// @FieldBitmaskEnum: FLAG: AP_EFI_Serial_Hirth:::Sensor_Status_Bitfield
// @Field: CRF: CRC failure count
// @Field: AKF: ACK failure count
// @Field: Up: Uptime between 2 messages
// @Field: ThrO: Throttle output as received by the engine
// @Field: ThO: Throttle output as received by the engine
// @Field: ThM: Modified throttle_to_hirth output sent to the engine
AP::logger().WriteStreaming("EFIS",
"TimeUS,ETS1,ETS2,CTS1,CTS2,ETSS,ATSS,APSS,TSS,CRCF,AckF,Up,ThrO",
"s------------",
"F------------",
"QBBBBBBBBIIIf",
"TimeUS,EET,FLAG,CRF,AKF,Up,ThO,ThM",
"s-------",
"F-------",
"QHBIIIfH",
AP_HAL::micros64(),
uint8_t(EGT_1_error_excess_temperature_status),
uint8_t(EGT_2_error_excess_temperature_status),
uint8_t(CHT_1_error_excess_temperature_status),
uint8_t(CHT_2_error_excess_temperature_status),
uint8_t(engine_temperature_sensor_status),
uint8_t(air_temperature_sensor_status),
uint8_t(air_pressure_sensor_status),
uint8_t(throttle_sensor_status),
uint16_t(error_excess_temperature),
uint8_t(sensor_status),
uint32_t(crc_fail_cnt),
uint32_t(ack_fail_cnt),
uint32_t(uptime),
float(internal_state.throttle_out));
float(internal_state.throttle_out),
uint16_t(throttle_to_hirth));
}
#endif // HAL_LOGGING_ENABLED

Expand Down
37 changes: 27 additions & 10 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,28 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend {

void update() override;

enum class Error_Excess_Temp_Bitfield : uint16_t {
tridge marked this conversation as resolved.
Show resolved Hide resolved
CHT_1_LOW = 1U<<0, // true if CHT1 is too low
CHT_1_HIGH = 1U<<1, // true if CHT1 is too high
CHT_1_ENRC_ACTIVE = 1U<<2, // true if CHT1 Enrichment is active
CHT_2_LOW = 1U<<3, // true if CHT2 is too low
CHT_2_HIGH = 1U<<4, // true if CHT2 is too high
CHT_2_ENRC_ACTIVE = 1U<<5, // true if CHT2 Enrichment is active
EGT_1_LOW = 1U<<6, // true if EGT1 is too low
EGT_1_HIGH = 1U<<7, // true if EGT1 is too high
EGT_1_ENRC_ACTIVE = 1U<<8, // true if EGT1 Enrichment is active
EGT_2_LOW = 1U<<9, // true if EGT2 is too low
EGT_2_HIGH = 1U<<10, // true if EGT2 is too high
EGT_2_ENRC_ACTIVE = 1U<<11, // true if EGT2 Enrichment is active
};

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
};

private:
// serial port instance
AP_HAL::UARTDriver *port;
Expand Down Expand Up @@ -61,20 +83,15 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend {
uint8_t expected_bytes;

// Throttle values
uint16_t last_throttle;
uint16_t last_throttle;
uint16_t throttle_to_hirth;

uint32_t last_fuel_integration_ms;

// custom status for Hirth
bool engine_temperature_sensor_status;
bool air_temperature_sensor_status;
bool air_pressure_sensor_status;
bool throttle_sensor_status;

bool CHT_1_error_excess_temperature_status;
bool CHT_2_error_excess_temperature_status;
bool EGT_1_error_excess_temperature_status;
bool EGT_2_error_excess_temperature_status;
uint16_t sensor_status;

uint16_t error_excess_temperature;
uint32_t crc_fail_cnt;
uint32_t uptime;
uint32_t ack_fail_cnt;
Expand Down
Loading