mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Scripting: add fuel_pressure_status binding
This commit is contained in:
parent
8c335be045
commit
74279d9b32
@ -114,6 +114,10 @@ function EFI_State_ud:fuel_consumption_rate_cm3pm(value) end
|
||||
---@param value number
|
||||
function EFI_State_ud:fuel_pressure(value) end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function EFI_State_ud:fuel_pressure_status(value) end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:oil_temperature(value) end
|
||||
|
@ -221,6 +221,7 @@ local function engine_control(_driver)
|
||||
efi_state:throttle_position_percent(math.floor((throttle_pos*100/255)+0.5))
|
||||
efi_state:ignition_voltage(ecu_voltage)
|
||||
efi_state:fuel_pressure(fuel_press*0.001)
|
||||
efi_state:fuel_pressure_status(1) -- Fuel_Pressure_Status::OK
|
||||
|
||||
local gram_to_cm3 = EFI_HFE_FUEL_DTY:get() * 0.001
|
||||
efi_state:fuel_consumption_rate_cm3pm((fuel_flow_gph/60.0) * gram_to_cm3)
|
||||
|
@ -637,6 +637,7 @@ userdata EFI_State field coolant_temperature float'skip_check write
|
||||
userdata EFI_State field oil_pressure float'skip_check write
|
||||
userdata EFI_State field oil_temperature float'skip_check write
|
||||
userdata EFI_State field fuel_pressure float'skip_check write
|
||||
userdata EFI_State field fuel_pressure_status Fuel_Pressure_Status'enum write Fuel_Pressure_Status::NOT_SUPPORTED Fuel_Pressure_Status::ABOVE_NOMINAL
|
||||
userdata EFI_State field fuel_consumption_rate_cm3pm float'skip_check write
|
||||
userdata EFI_State field estimated_consumed_fuel_volume_cm3 float'skip_check write
|
||||
userdata EFI_State field throttle_position_percent uint8_t'skip_check write
|
||||
|
Loading…
Reference in New Issue
Block a user