AP_Scripting: bindings: remaining EFI_State to read and write

This commit is contained in:
Iampete1 2023-05-02 21:26:09 +01:00 committed by Andrew Tridgell
parent 8fa2472148
commit 7a129e73cb
2 changed files with 14 additions and 2 deletions

View File

@ -102,6 +102,10 @@ function EFI_State_ud:ignition_voltage() end
---@param value number
function EFI_State_ud:ignition_voltage(value) end
-- get field
---@return Cylinder_Status_ud
function EFI_State_ud:cylinder_status() end
-- set field
---@param value Cylinder_Status_ud
function EFI_State_ud:cylinder_status(value) end
@ -146,6 +150,14 @@ function EFI_State_ud:fuel_pressure() end
---@param value number
function EFI_State_ud:fuel_pressure(value) end
-- get field
---@return integer
---| '0' # Not supported
---| '1' # Ok
---| '2' # Below nominal
---| '3' # Above nominal
function EFI_State_ud:fuel_pressure_status() end
-- set field
---@param status integer
---| '0' # Not supported

View File

@ -653,12 +653,12 @@ userdata EFI_State field coolant_temperature float'skip_check read write
userdata EFI_State field oil_pressure float'skip_check read write
userdata EFI_State field oil_temperature float'skip_check read write
userdata EFI_State field fuel_pressure float'skip_check read 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_pressure_status Fuel_Pressure_Status'enum read write Fuel_Pressure_Status::NOT_SUPPORTED Fuel_Pressure_Status::ABOVE_NOMINAL
userdata EFI_State field fuel_consumption_rate_cm3pm float'skip_check read write
userdata EFI_State field estimated_consumed_fuel_volume_cm3 float'skip_check read write
userdata EFI_State field throttle_position_percent uint8_t'skip_check read write
userdata EFI_State field ecu_index uint8_t'skip_check read write
userdata EFI_State field cylinder_status Cylinder_Status write
userdata EFI_State field cylinder_status Cylinder_Status read write
userdata EFI_State field ignition_voltage float'skip_check read write
userdata EFI_State field throttle_out float'skip_check read write
userdata EFI_State field pt_compensation float'skip_check read write