mirror of https://github.com/ArduPilot/ardupilot
AP_EFI: Adding EFIS log for Hirth
- Added EFIS log for Hirth engine - Added ThM to help understand the engine logs better - Updated the field names to keep the total length 64-characters long. - Added Bitfield for the EFIS log to log all errors.
This commit is contained in:
parent
1fe21b6120
commit
54ec26a80a
|
@ -205,6 +205,7 @@ void AP_EFI_Serial_Hirth::send_request()
|
||||||
bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
|
bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
|
||||||
{
|
{
|
||||||
uint8_t computed_checksum = 0;
|
uint8_t computed_checksum = 0;
|
||||||
|
throttle_to_hirth = 0;
|
||||||
|
|
||||||
// clear buffer
|
// clear buffer
|
||||||
memset(raw_data, 0, ARRAY_SIZE(raw_data));
|
memset(raw_data, 0, ARRAY_SIZE(raw_data));
|
||||||
|
@ -214,15 +215,15 @@ bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr)
|
||||||
thr = linearise_throttle(thr);
|
thr = linearise_throttle(thr);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const uint16_t throttle = thr * THROTTLE_POSITION_FACTOR;
|
throttle_to_hirth = thr * THROTTLE_POSITION_FACTOR;
|
||||||
|
|
||||||
uint8_t idx = 0;
|
uint8_t idx = 0;
|
||||||
|
|
||||||
// set Quantity + Code + "20 bytes of records to set" + Checksum
|
// set Quantity + Code + "20 bytes of records to set" + Checksum
|
||||||
computed_checksum += raw_data[idx++] = QUANTITY_SET_VALUE;
|
computed_checksum += raw_data[idx++] = QUANTITY_SET_VALUE;
|
||||||
computed_checksum += raw_data[idx++] = requested_code = CODE_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_to_hirth & 0xFF;
|
||||||
computed_checksum += raw_data[idx++] = (throttle >> 8) & 0xFF;
|
computed_checksum += raw_data[idx++] = (throttle_to_hirth >> 8) & 0xFF;
|
||||||
|
|
||||||
// checksum calculation
|
// checksum calculation
|
||||||
raw_data[QUANTITY_SET_VALUE - 1] = (256 - computed_checksum);
|
raw_data[QUANTITY_SET_VALUE - 1] = (256 - computed_checksum);
|
||||||
|
@ -309,10 +310,7 @@ void AP_EFI_Serial_Hirth::decode_data()
|
||||||
// EFI3 log
|
// EFI3 log
|
||||||
internal_state.ignition_voltage = record1->battery_voltage * VOLTAGE_RESOLUTION;
|
internal_state.ignition_voltage = record1->battery_voltage * VOLTAGE_RESOLUTION;
|
||||||
|
|
||||||
engine_temperature_sensor_status = (record1->sensor_ok & 0x01) != 0;
|
sensor_status = record1->sensor_ok;
|
||||||
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;
|
|
||||||
|
|
||||||
// resusing mavlink variables as required for Hirth
|
// resusing mavlink variables as required for Hirth
|
||||||
// add in ADC voltage of MAP sensor > convert to MAP in kPa
|
// add in ADC voltage of MAP sensor > convert to MAP in kPa
|
||||||
|
@ -344,10 +342,7 @@ void AP_EFI_Serial_Hirth::decode_data()
|
||||||
struct Record3 *record3 = (Record3*)raw_data;
|
struct Record3 *record3 = (Record3*)raw_data;
|
||||||
|
|
||||||
// EFI3 Log
|
// EFI3 Log
|
||||||
CHT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0007) != 0;
|
error_excess_temperature = record3->error_excess_temperature_bitfield;
|
||||||
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;
|
|
||||||
|
|
||||||
// ECYL log
|
// ECYL log
|
||||||
internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(record3->excess_temperature_1);
|
internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(record3->excess_temperature_1);
|
||||||
|
@ -369,36 +364,28 @@ void AP_EFI_Serial_Hirth::log_status(void)
|
||||||
// @LoggerMessage: EFIS
|
// @LoggerMessage: EFIS
|
||||||
// @Description: Electronic Fuel Injection data - Hirth specific Status information
|
// @Description: Electronic Fuel Injection data - Hirth specific Status information
|
||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
// @Field: ETS1: Status of EGT1 excess temperature error
|
// @Field: EET: Error Excess Temperature Bitfield
|
||||||
// @Field: ETS2: Status of EGT2 excess temperature error
|
// @FieldBitmaskEnum: EET: AP_EFI_Serial_Hirth:::Error_Excess_Temp_Bitfield
|
||||||
// @Field: CTS1: Status of CHT1 excess temperature error
|
// @Field: FLAG: Sensor Status Bitfield
|
||||||
// @Field: CTS2: Status of CHT2 excess temperature error
|
// @FieldBitmaskEnum: FLAG: AP_EFI_Serial_Hirth:::Sensor_Status_Bitfield
|
||||||
// @Field: ETSS: Status of Engine temperature sensor
|
// @Field: CRF: CRC failure count
|
||||||
// @Field: ATSS: Status of Air temperature sensor
|
// @Field: AKF: ACK failure count
|
||||||
// @Field: APSS: Status of Air pressure sensor
|
|
||||||
// @Field: TSS: Status of Temperature sensor
|
|
||||||
// @Field: CRCF: CRC failure count
|
|
||||||
// @Field: AckF: ACK failure count
|
|
||||||
// @Field: Up: Uptime between 2 messages
|
// @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",
|
AP::logger().WriteStreaming("EFIS",
|
||||||
"TimeUS,ETS1,ETS2,CTS1,CTS2,ETSS,ATSS,APSS,TSS,CRCF,AckF,Up,ThrO",
|
"TimeUS,EET,FLAG,CRF,AKF,Up,ThO,ThM",
|
||||||
"s------------",
|
"s-------",
|
||||||
"F------------",
|
"F-------",
|
||||||
"QBBBBBBBBIIIf",
|
"QHBIIIfH",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
uint8_t(EGT_1_error_excess_temperature_status),
|
uint16_t(error_excess_temperature),
|
||||||
uint8_t(EGT_2_error_excess_temperature_status),
|
uint8_t(sensor_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),
|
|
||||||
uint32_t(crc_fail_cnt),
|
uint32_t(crc_fail_cnt),
|
||||||
uint32_t(ack_fail_cnt),
|
uint32_t(ack_fail_cnt),
|
||||||
uint32_t(uptime),
|
uint32_t(uptime),
|
||||||
float(internal_state.throttle_out));
|
float(internal_state.throttle_out),
|
||||||
|
uint16_t(throttle_to_hirth));
|
||||||
}
|
}
|
||||||
#endif // HAL_LOGGING_ENABLED
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
|
||||||
|
|
|
@ -31,6 +31,28 @@ public:
|
||||||
|
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
|
enum class Error_Excess_Temp_Bitfield : uint16_t {
|
||||||
|
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:
|
private:
|
||||||
// serial port instance
|
// serial port instance
|
||||||
AP_HAL::UARTDriver *port;
|
AP_HAL::UARTDriver *port;
|
||||||
|
@ -61,20 +83,15 @@ private:
|
||||||
uint8_t expected_bytes;
|
uint8_t expected_bytes;
|
||||||
|
|
||||||
// Throttle values
|
// Throttle values
|
||||||
uint16_t last_throttle;
|
uint16_t last_throttle;
|
||||||
|
uint16_t throttle_to_hirth;
|
||||||
|
|
||||||
uint32_t last_fuel_integration_ms;
|
uint32_t last_fuel_integration_ms;
|
||||||
|
|
||||||
// custom status for Hirth
|
// custom status for Hirth
|
||||||
bool engine_temperature_sensor_status;
|
uint16_t sensor_status;
|
||||||
bool air_temperature_sensor_status;
|
|
||||||
bool air_pressure_sensor_status;
|
|
||||||
bool throttle_sensor_status;
|
|
||||||
|
|
||||||
bool CHT_1_error_excess_temperature_status;
|
uint16_t error_excess_temperature;
|
||||||
bool CHT_2_error_excess_temperature_status;
|
|
||||||
bool EGT_1_error_excess_temperature_status;
|
|
||||||
bool EGT_2_error_excess_temperature_status;
|
|
||||||
uint32_t crc_fail_cnt;
|
uint32_t crc_fail_cnt;
|
||||||
uint32_t uptime;
|
uint32_t uptime;
|
||||||
uint32_t ack_fail_cnt;
|
uint32_t ack_fail_cnt;
|
||||||
|
|
Loading…
Reference in New Issue