mirror of https://github.com/ArduPilot/ardupilot
AP_EFI: Add ECU density parameter for Currawong fuel flow calculations
This commit is contained in:
parent
ad808cb25b
commit
21ac8d801c
|
@ -17,10 +17,12 @@
|
|||
|
||||
#if HAL_EFI_ENABLED
|
||||
|
||||
#define HAL_EFI_CURRAWONG_ECU_ENABLED 1
|
||||
#include "AP_EFI_Serial_MS.h"
|
||||
#include "AP_EFI_Serial_Lutan.h"
|
||||
#include "AP_EFI_NWPMU.h"
|
||||
#include "AP_EFI_DroneCAN.h"
|
||||
#include "AP_EFI_Currawong_ECU.h"
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
|
@ -53,6 +55,14 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("_COEF2", 3, AP_EFI, coef2, 0),
|
||||
|
||||
// @Param: ECU_DN
|
||||
// @DisplayName: ECU Fuel Density
|
||||
// @Description: Used to calculate fuel consumption
|
||||
// @Units: kg/m/m/m
|
||||
// @Range: 0 10000
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_ECU_DN", 4, AP_EFI, ecu_dn, 0.),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -98,6 +98,8 @@ protected:
|
|||
AP_Float coef1;
|
||||
AP_Float coef2;
|
||||
|
||||
AP_Float ecu_dn;
|
||||
|
||||
EFI_State state;
|
||||
|
||||
private:
|
||||
|
|
|
@ -47,4 +47,8 @@ HAL_Semaphore &AP_EFI_Backend::get_sem(void)
|
|||
return frontend.sem;
|
||||
}
|
||||
|
||||
float AP_EFI_Backend::get_ecu_dn(void) const
|
||||
{
|
||||
return frontend.ecu_dn;
|
||||
}
|
||||
#endif // HAL_EFI_ENABLED
|
||||
|
|
|
@ -41,6 +41,7 @@ protected:
|
|||
int8_t get_uavcan_node_id(void) const;
|
||||
float get_coef1(void) const;
|
||||
float get_coef2(void) const;
|
||||
float get_ecu_dn(void) const;
|
||||
|
||||
HAL_Semaphore &get_sem(void);
|
||||
|
||||
|
|
Loading…
Reference in New Issue