Skip to content

Commit

Permalink
AP_EFI: Hirth Driver addition
Browse files Browse the repository at this point in the history
Implementation for Hirth.
 - Base class - AP_EFI
 - polynomial functional throttle linearization 
 - AP_EFI_State parameter addition and changes for hirth logging
 - to fix autotest errors
 - updated comments
 - Hirth CI/CD autotest fail fixes
  • Loading branch information
Pradeep-Carbonix committed Nov 1, 2023
1 parent a15e479 commit f9ea02a
Show file tree
Hide file tree
Showing 8 changed files with 915 additions and 72 deletions.
217 changes: 151 additions & 66 deletions libraries/AP_EFI/AP_EFI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include "AP_EFI_NWPMU.h"
#include "AP_EFI_DroneCAN.h"
#include "AP_EFI_Currawong_ECU.h"
#include "AP_EFI_Serial_Hirth.h"
#include "AP_EFI_Scripting.h"
#include "AP_EFI_MAV.h"

Expand All @@ -39,7 +40,7 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = {
// @Param: _TYPE
// @DisplayName: EFI communication type
// @Description: What method of communication is used for EFI #1
// @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,9:MAV
// @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth,9:MAV
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE),
Expand All @@ -65,6 +66,70 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = {
// @Range: 0 10000
// @User: Advanced
AP_GROUPINFO("_FUEL_DENS", 4, AP_EFI, ecu_fuel_density, 0),

// @Param: _THTL_FOP
// @DisplayName: Throttle value - First Order
// @Description: First Order Polynomial with 0.0001 Resolution. (=1, if throttle is first order polynomial trendline)
// @Range: -1 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_THTL_FOP", 5, AP_EFI, throttle_firstorder, 1),

// @Param: _THTL_SOP
// @DisplayName: Throttle value - Second Order
// @Description: Second Order Polynomial with 0.0001 Resolution. (=0, if throttle is first order polynomial trendline)
// @Range: -1 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_THTL_SOP", 6, AP_EFI, throttle_secondorder, 0),

// @Param: _THTL_TOP
// @DisplayName: Throttle value - First Order
// @Description: Third Order Polynomial with 0.0001 Resolution. (=0, if throttle is first order polynomial trendline)
// @Range: -1 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_THTL_TOP", 7, AP_EFI, throttle_thirdorder, 0),

// @Param: _THTL_OFF
// @DisplayName: EFI throttle linearization offset
// @Description: Offset for throttle linearization
// @Range: 0 100
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_THTL_OFF", 8, AP_EFI, throttle_offset, 10),

// @Param: _EFCR_SLP
// @DisplayName: ECU Fuel Consumption Rate factor
// @Description: ECU FCR gradient/factor. Must be used along with _EFCR_OFT
// @Range: 0 1000
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_EFCR_SLP", 9, AP_EFI, ecu_fcr_slope, 1),

// @Param: _EFCR_OFT
// @DisplayName: ECU Fuel Consumption Rate Offset
// @Description: ECU FCR intercept/offset. Must be used along with _EFCR_SLP
// @Range: 0 1000
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_EFCR_OFT", 10, AP_EFI, ecu_fcr_offset, 0),

// @Param: _EFCR_AVG
// @DisplayName: ECU Fuel Consumption Rate Average count
// @Description: Averages _EFCR_AVG consecutive reading
// @Range: 0 100
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_EFCR_AVG", 11, AP_EFI, ecu_fcr_average_count, 1),

// @Param: _FUEL_VOL
// @DisplayName: Full Fuel Volume / Capacity
// @Description: Full fuel volume in ml
// @Range: 0 65535
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("_FUEL_VOL", 12, AP_EFI, fuel_volume_in_ml, 1),

AP_GROUPEND
};
Expand Down Expand Up @@ -117,6 +182,11 @@ void AP_EFI::init(void)
case Type::SCRIPTING:
backend = new AP_EFI_Scripting(*this);
break;
#endif
#if AP_EFI_SERIAL_HIRTH_ENABLED
case Type::Hirth:
backend = new AP_EFI_Serial_Hirth(*this);
break;
#endif
#if AP_EFI_MAV_ENABLED
case Type::MAV:
Expand Down Expand Up @@ -151,23 +221,23 @@ bool AP_EFI::is_healthy(void) const
*/
void AP_EFI::log_status(void)
{
// @LoggerMessage: EFI
// @Description: Electronic Fuel Injection system data
// @Field: TimeUS: Time since system startup
// @Field: LP: Reported engine load
// @Field: Rpm: Reported engine RPM
// @Field: SDT: Spark Dwell Time
// @Field: ATM: Atmospheric pressure
// @Field: IMP: Intake manifold pressure
// @Field: IMT: Intake manifold temperature
// @Field: ECT: Engine Coolant Temperature
// @Field: OilP: Oil Pressure
// @Field: OilT: Oil temperature
// @Field: FP: Fuel Pressure
// @Field: FCR: Fuel Consumption Rate
// @Field: CFV: Consumed fueld volume
// @Field: TPS: Throttle Position
// @Field: IDX: Index of the publishing ECU
// @LoggerMessage: EFI
// @Description: Electronic Fuel Injection system data
// @Field: TimeUS: Time since system startup
// @Field: LP: Reported engine load
// @Field: Rpm: Reported engine RPM
// @Field: SDT: Spark Dwell Time
// @Field: ATM: Atmospheric pressure
// @Field: IMP: Intake manifold pressure
// @Field: IMT: Intake manifold temperature
// @Field: ECT: Engine Coolant Temperature
// @Field: OilP: Oil Pressure
// @Field: OilT: Oil temperature
// @Field: FP: Fuel Pressure
// @Field: FCR: Fuel Consumption Rate
// @Field: CFV: Consumed fueld volume
// @Field: TPS: Throttle Position
// @Field: IDX: Index of the publishing ECU
AP::logger().WriteStreaming("EFI",
"TimeUS,LP,Rpm,SDT,ATM,IMP,IMT,ECT,OilP,OilT,FP,FCR,CFV,TPS,IDX",
"s%qsPPOOPOP--%-",
Expand All @@ -189,50 +259,50 @@ void AP_EFI::log_status(void)
uint8_t(state.throttle_position_percent),
uint8_t(state.ecu_index));

// @LoggerMessage: EFI2
// @Description: Electronic Fuel Injection system data - redux
// @Field: TimeUS: Time since system startup
// @Field: Healthy: True if EFI is healthy
// @Field: ES: Engine state
// @Field: GE: General error
// @Field: CSE: Crankshaft sensor status
// @Field: TS: Temperature status
// @Field: FPS: Fuel pressure status
// @Field: OPS: Oil pressure status
// @Field: DS: Detonation status
// @Field: MS: Misfire status
// @Field: DebS: Debris status
// @Field: SPU: Spark plug usage
// @Field: IDX: Index of the publishing ECU
// @LoggerMessage: EFI2
// @Description: Electronic Fuel Injection system data - redux
// @Field: TimeUS: Time since system startup
// @Field: Healthy: True if EFI is healthy
// @Field: ES: Engine state
// @Field: GE: General error
// @Field: CSE: Crankshaft sensor status
// @Field: TS: Temperature status
// @Field: FPS: Fuel pressure status
// @Field: OPS: Oil pressure status
// @Field: DS: Detonation status
// @Field: MS: Misfire status
// @Field: DebS: Debris status
// @Field: SPU: Spark plug usage
// @Field: IDX: Index of the publishing ECU
AP::logger().WriteStreaming("EFI2",
"TimeUS,Healthy,ES,GE,CSE,TS,FPS,OPS,DS,MS,DebS,SPU,IDX",
"s------------",
"F------------",
"QBBBBBBBBBBBB",
AP_HAL::micros64(),
uint8_t(is_healthy()),
uint8_t(state.engine_state),
uint8_t(state.general_error),
uint8_t(state.crankshaft_sensor_status),
uint8_t(state.temperature_status),
uint8_t(state.fuel_pressure_status),
uint8_t(state.oil_pressure_status),
uint8_t(state.detonation_status),
uint8_t(state.misfire_status),
uint8_t(state.debris_status),
uint8_t(state.spark_plug_usage),
uint8_t(state.ecu_index));
"TimeUS,Healthy,ES,GE,CSE,TS,FPS,OPS,DS,MS,DebS,SPU,IDX",
"s------------",
"F------------",
"QBBBBBBBBBBBB",
AP_HAL::micros64(),
uint8_t(is_healthy()),
uint8_t(state.engine_state),
uint8_t(state.general_error),
uint8_t(state.crankshaft_sensor_status),
uint8_t(state.temperature_status),
uint8_t(state.fuel_pressure_status),
uint8_t(state.oil_pressure_status),
uint8_t(state.detonation_status),
uint8_t(state.misfire_status),
uint8_t(state.debris_status),
uint8_t(state.spark_plug_usage),
uint8_t(state.ecu_index));

// @LoggerMessage: ECYL
// @Description: EFI per-cylinder information
// @Field: TimeUS: Time since system startup
// @Field: Inst: Cylinder this data belongs to
// @Field: IgnT: Ignition timing
// @Field: InjT: Injection time
// @Field: CHT: Cylinder head temperature
// @Field: EGT: Exhaust gas temperature
// @Field: Lambda: Estimated lambda coefficient (dimensionless ratio)
// @Field: IDX: Index of the publishing ECU
// @LoggerMessage: ECYL
// @Description: EFI per-cylinder information
// @Field: TimeUS: Time since system startup
// @Field: Inst: Cylinder this data belongs to
// @Field: IgnT: Ignition timing
// @Field: InjT: Injection time
// @Field: CHT: Cylinder head temperature
// @Field: EGT: Exhaust gas temperature
// @Field: Lambda: Estimated lambda coefficient (dimensionless ratio)
// @Field: IDX: Index of the publishing ECU
AP::logger().WriteStreaming("ECYL",
"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,IDX",
"s#dsOO--",
Expand All @@ -246,6 +316,22 @@ void AP_EFI::log_status(void)
state.cylinder_status.exhaust_gas_temperature,
state.cylinder_status.lambda_coefficient,
state.ecu_index);

#if AP_EFI_SERIAL_HIRTH_ENABLED
AP::logger().WriteStreaming("ECYL",
"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,IDX",
"s#dsOO--",
"F-0C0000",
"QBfffffB",
AP_HAL::micros64(),
1,
state.cylinder_status.ignition_timing_deg,
state.cylinder_status.injection_time_ms,
state.cylinder_status2.cylinder_head_temperature,
state.cylinder_status2.exhaust_gas_temperature,
state.ecu_index);
#endif // AP_EFI_SERIAL_HIRTH_ENABLED
state.cylinder_status.lambda_coefficient,
}
#endif // LOGGING_ENABLED

Expand Down Expand Up @@ -289,16 +375,15 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan)
state.spark_dwell_time_ms,
state.atmospheric_pressure_kpa,
state.intake_manifold_pressure_kpa,
KELVIN_TO_C(state.intake_manifold_temperature),
KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature),
state.intake_manifold_temperature,
state.cylinder_status.cylinder_head_temperature,
state.cylinder_status.ignition_timing_deg,
state.cylinder_status.injection_time_ms,
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),
state.cylinder_status.exhaust_gas_temperature,
state.throttle_out,
state.pt_compensation,
float(state.engine_state), //pt_compensation
ignition_voltage,
fuel_pressure
);
fuel_pressure);
}

// get a copy of state structure
Expand Down
74 changes: 73 additions & 1 deletion libraries/AP_EFI/AP_EFI.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#ifndef HAL_EFI_ENABLED
#define HAL_EFI_ENABLED !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024
#endif

#include "AP_EFI_Backend.h"
#include "AP_EFI_State.h"

Expand Down Expand Up @@ -96,7 +100,9 @@ class AP_EFI {
#if AP_EFI_SCRIPTING_ENABLED
SCRIPTING = 7,
#endif
// Hirth = 8 /* Reserved for future implementation */
#if AP_EFI_SERIAL_HIRTH_ENABLED
Hirth = 8,
#endif
MAV = 9,
};

Expand All @@ -113,6 +119,58 @@ class AP_EFI {

void handle_EFI_message(const mavlink_message_t &msg);

#if !AP_EFI_SERIAL_HIRTH_ENABLED
//get engine sensor status hirth values for lua
bool get_sensor_status(uint8_t &engine_temperature_sensor_status, uint8_t &air_temperature_sensor_status,uint8_t &air_pressure_sensor_status,uint8_t &throttle_sensor_status,uint8_t &CHT_1_error_excess_temperature_status,uint8_t &CHT_2_error_excess_temperature_status,uint8_t &EGT_1_error_excess_temperature_status,uint8_t &EGT_2_error_excess_temperature_status) const {
engine_temperature_sensor_status = state.engine_temperature_sensor_status;
air_temperature_sensor_status = state.air_temperature_sensor_status;
air_pressure_sensor_status = state.air_pressure_sensor_status;
throttle_sensor_status = state.throttle_sensor_status;
CHT_1_error_excess_temperature_status = state.CHT_1_error_excess_temperature_status;
CHT_2_error_excess_temperature_status = state.CHT_2_error_excess_temperature_status;
EGT_1_error_excess_temperature_status = state.EGT_1_error_excess_temperature_status;
EGT_2_error_excess_temperature_status = state.EGT_2_error_excess_temperature_status;
return true;
}

//get engine temperature value hirth values for lua
bool get_temp(float &cht1_temp, float &cht2_temp, float &egt1_temp, float &egt2_temp, float &air_temp, float &eng_temp) const {
cht1_temp = state.cht1_temp;
cht2_temp = state.cht2_temp;
egt1_temp = state.egt1_temp;
egt2_temp = state.egt2_temp;
air_temp = state.air_temp;
eng_temp = state.eng_temp;
return true;
}
//get engine load perct values for lua
uint8_t get_eng_load_prct() const {
return uint8_t(state.engine_load_percent);
}
//get engine state specific to Hirth
uint8_t get_state() const {
return uint8_t(state.engine_state);
}
//get crc fail packet number
uint32_t get_crc_fail_ct() const {
return uint8_t(state.crc_fail_cnt);
}

// get pressure from hirth
bool get_pressure(float &atmospheric_pressure_kpa, float &intake_manifold_pressure_kpa) const {
atmospheric_pressure_kpa = state.atmospheric_pressure_kpa;
intake_manifold_pressure_kpa = state.intake_manifold_pressure_kpa;
return true;
}

//get Thr
bool get_thr_pos(float &k_throttle, float &thr_pos) const {
k_throttle = state.k_throttle;
thr_pos = state.thr_pos;
return true;
}
#endif // AP_EFI_SERIAL_HIRTH_ENABLED

protected:

// Back end Parameters
Expand All @@ -121,6 +179,20 @@ class AP_EFI {

AP_Float ecu_fuel_density;

#if AP_EFI_SERIAL_HIRTH_ENABLED
// polynomial config variables for throttle linearization
AP_Float throttle_firstorder;
AP_Float throttle_secondorder;
AP_Float throttle_thirdorder;
AP_Float throttle_offset;

// ECU fuel consumption calculation
AP_Float ecu_fcr_slope;
AP_Float ecu_fcr_offset;
AP_Int16 ecu_fcr_average_count;
AP_Int16 fuel_volume_in_ml;
#endif //AP_EFI_SERIAL_HIRTH_ENABLED

EFI_State state;

private:
Expand Down
Loading

0 comments on commit f9ea02a

Please sign in to comment.