Skip to content

Commit

Permalink
AP_EFI: Hirth Driver Addition
Browse files Browse the repository at this point in the history
backport from 4.4
  • Loading branch information
tridge committed Nov 15, 2023
1 parent e1ea9e4 commit 9c2c08f
Show file tree
Hide file tree
Showing 12 changed files with 769 additions and 14 deletions.
26 changes: 21 additions & 5 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_Logger/AP_Logger.h>
Expand All @@ -37,7 +38,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
// @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE),
Expand All @@ -64,6 +65,12 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = {
// @User: Advanced
AP_GROUPINFO("_FUEL_DENS", 4, AP_EFI, ecu_fuel_density, 0),

#if AP_EFI_THROTTLE_LINEARISATION_ENABLED
// @Group: _THRLIN
// @Path: AP_EFI_ThrottleLinearisation.cpp
AP_SUBGROUPINFO(throttle_linearisation, "_THRLIN", 5, AP_EFI, AP_EFI_ThrLin),
#endif

AP_GROUPEND
};

Expand Down Expand Up @@ -112,6 +119,11 @@ void AP_EFI::init(void)
backend = new AP_EFI_Scripting(*this);
#endif
break;
#if AP_EFI_SERIAL_HIRTH_ENABLED
case Type::Hirth:
backend = new AP_EFI_Serial_Hirth(*this);
break;
#endif
default:
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown EFI type");
break;
Expand Down Expand Up @@ -221,19 +233,23 @@ void AP_EFI::log_status(void)
// @Field: CHT: Cylinder head temperature
// @Field: EGT: Exhaust gas temperature
// @Field: Lambda: Estimated lambda coefficient (dimensionless ratio)
// @Field: CHT2: Cylinder2 head temperature
// @Field: EGT2: Cylinder2 Exhaust gas temperature
// @Field: IDX: Index of the publishing ECU
AP::logger().WriteStreaming("ECYL",
"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,IDX",
"s#dsOO--",
"F-0C0000",
"QBfffffB",
"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX",
"s#dsOO-OO-",
"F-0C000000",
"QBfffffBff",
AP_HAL::micros64(),
0,
state.cylinder_status.ignition_timing_deg,
state.cylinder_status.injection_time_ms,
state.cylinder_status.cylinder_head_temperature,
state.cylinder_status.exhaust_gas_temperature,
state.cylinder_status.lambda_coefficient,
state.cylinder_status.cylinder_head_temperature2,
state.cylinder_status.exhaust_gas_temperature2,
state.ecu_index);
}
#endif // LOGGING_ENABLED
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_EFI/AP_EFI.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "AP_EFI_ThrottleLinearisation.h"

#include "AP_EFI_Backend.h"
#include "AP_EFI_State.h"
Expand Down Expand Up @@ -84,6 +85,9 @@ class AP_EFI {
DroneCAN = 5,
CurrawongECU = 6,
SCRIPTING = 7,
#if AP_EFI_SERIAL_HIRTH_ENABLED
Hirth = 8,
#endif
};

static AP_EFI *get_singleton(void) {
Expand All @@ -107,6 +111,10 @@ class AP_EFI {

EFI_State state;

#if AP_EFI_THROTTLE_LINEARISATION_ENABLED
AP_EFI_ThrLin throttle_linearisation;
#endif

private:
// Front End Parameters
AP_Enum<Type> type;
Expand Down
16 changes: 16 additions & 0 deletions libraries/AP_EFI/AP_EFI_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@ float AP_EFI_Backend::get_coef2(void) const
return frontend.coef2;
}

void AP_EFI_Backend::set_default_coef1(float coef1)
{
frontend.coef1.set_default(coef1);
}

HAL_Semaphore &AP_EFI_Backend::get_sem(void)
{
return frontend.sem;
Expand All @@ -51,4 +56,15 @@ float AP_EFI_Backend::get_ecu_fuel_density(void) const
{
return frontend.ecu_fuel_density;
}

#if AP_EFI_THROTTLE_LINEARISATION_ENABLED
/*
linearise throttle if enabled
*/
float AP_EFI_Backend::linearise_throttle(float throttle_percent)
{
return frontend.throttle_linearisation.linearise_throttle(throttle_percent);
}
#endif // AP_EFI_THROTTLE_LINEARISATION_ENABLED

#endif // HAL_EFI_ENABLED
8 changes: 8 additions & 0 deletions libraries/AP_EFI/AP_EFI_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,16 @@ class AP_EFI_Backend {
int8_t get_uavcan_node_id(void) const;
float get_coef1(void) const;
float get_coef2(void) const;

void set_default_coef1(float coef1);

float get_ecu_fuel_density(void) const;

/*
linearise throttle if enabled
*/
float linearise_throttle(float throttle_percent);

HAL_Semaphore &get_sem(void);

private:
Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_EFI/AP_EFI_Scripting.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
#include "AP_EFI_Scripting.h"
#include "AP_EFI_config.h"

#if AP_EFI_SCRIPTING_ENABLED

#include "AP_EFI_Scripting.h"


// Called from frontend to update with the readings received by handler
void AP_EFI_Scripting::update()
{
Expand Down
Loading

0 comments on commit 9c2c08f

Please sign in to comment.