Skip to content

Commit

Permalink
Adding ThM (modified throttle send to engine) to EFIS log
Browse files Browse the repository at this point in the history
 - ThM added to help understand the engine logs better
 - Updated the field names to keep the total length 64-characters long.
  • Loading branch information
Pradeep-Carbonix authored and loki077 committed Mar 5, 2024
1 parent 335860a commit 4c49385
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 16 deletions.
35 changes: 19 additions & 16 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,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 = 0;

// clear buffer
memset(raw_data, 0, ARRAY_SIZE(raw_data));
Expand All @@ -199,7 +200,7 @@ 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 = thr * THROTTLE_POSITION_FACTOR;

uint8_t idx = 0;

Expand Down Expand Up @@ -354,23 +355,24 @@ 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: ES1: Status of EGT1 excess temperature error
// @Field: ES2: Status of EGT2 excess temperature error
// @Field: CS1: Status of CHT1 excess temperature error
// @Field: CS2: Status of CHT2 excess temperature error
// @Field: ETS: Status of Engine temperature sensor
// @Field: ATS: Status of Air temperature sensor
// @Field: APS: Status of Air pressure sensor
// @Field: TSS: Status of Temperature sensor
// @Field: CRCF: CRC failure count
// @Field: AckF: ACK failure count
// @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 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,ES1,ES2,CS1,CS2,ETS,ATS,APS,TSS,CRF,AKF,Up,ThO,ThM",
"s-------------",
"F-------------",
"QBBBBBBBBIIIfH",
AP_HAL::micros64(),
uint8_t(EGT_1_error_excess_temperature_status),
uint8_t(EGT_2_error_excess_temperature_status),
Expand All @@ -383,7 +385,8 @@ void AP_EFI_Serial_Hirth::log_status(void)
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));
}
#endif // HAL_LOGGING_ENABLED

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_EFI/AP_EFI_Serial_Hirth.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ class AP_EFI_Serial_Hirth: public AP_EFI_Backend {

// Throttle values
uint16_t last_throttle;
uint16_t throttle;

uint32_t last_fuel_integration_ms;

Expand Down

0 comments on commit 4c49385

Please sign in to comment.