AP_Scripting: Make EFI bindings readable
This commit is contained in:
parent
068443718e
commit
7b64d09dc4
@ -78,14 +78,26 @@ local EFI_State_ud = {}
|
||||
---@return EFI_State_ud
|
||||
function EFI_State() end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:pt_compensation() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:pt_compensation(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:throttle_out() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:throttle_out(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:ignition_voltage() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:ignition_voltage(value) end
|
||||
@ -94,22 +106,42 @@ function EFI_State_ud:ignition_voltage(value) end
|
||||
---@param value Cylinder_Status_ud
|
||||
function EFI_State_ud:cylinder_status(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function EFI_State_ud:ecu_index() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function EFI_State_ud:ecu_index(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function EFI_State_ud:throttle_position_percent() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function EFI_State_ud:throttle_position_percent(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:estimated_consumed_fuel_volume_cm3() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:estimated_consumed_fuel_volume_cm3(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:fuel_consumption_rate_cm3pm() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:fuel_consumption_rate_cm3pm(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:fuel_pressure() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:fuel_pressure(value) end
|
||||
@ -122,46 +154,90 @@ function EFI_State_ud:fuel_pressure(value) end
|
||||
---| '3' # Above nominal
|
||||
function EFI_State_ud:fuel_pressure_status(status) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:oil_temperature() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:oil_temperature(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:oil_pressure() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:oil_pressure(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:coolant_temperature() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:coolant_temperature(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:intake_manifold_temperature() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:intake_manifold_temperature(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:intake_manifold_pressure_kpa() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:intake_manifold_pressure_kpa(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:atmospheric_pressure_kpa() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:atmospheric_pressure_kpa(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function EFI_State_ud:spark_dwell_time_ms() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function EFI_State_ud:spark_dwell_time_ms(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function EFI_State_ud:engine_speed_rpm() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud
|
||||
function EFI_State_ud:engine_speed_rpm(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function EFI_State_ud:engine_load_percent() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function EFI_State_ud:engine_load_percent(value) end
|
||||
|
||||
-- get field
|
||||
---@return boolean
|
||||
function EFI_State_ud:general_error() end
|
||||
|
||||
-- set field
|
||||
---@param value boolean
|
||||
function EFI_State_ud:general_error(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function EFI_State_ud:last_updated_ms() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud
|
||||
function EFI_State_ud:last_updated_ms(value) end
|
||||
@ -174,22 +250,42 @@ local Cylinder_Status_ud = {}
|
||||
---@return Cylinder_Status_ud
|
||||
function Cylinder_Status() end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function Cylinder_Status_ud:lambda_coefficient() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function Cylinder_Status_ud:lambda_coefficient(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function Cylinder_Status_ud:exhaust_gas_temperature() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function Cylinder_Status_ud:exhaust_gas_temperature(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function Cylinder_Status_ud:cylinder_head_temperature() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function Cylinder_Status_ud:cylinder_head_temperature(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function Cylinder_Status_ud:injection_time_ms() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function Cylinder_Status_ud:injection_time_ms(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function Cylinder_Status_ud:ignition_timing_deg() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function Cylinder_Status_ud:ignition_timing_deg(value) end
|
||||
|
@ -633,34 +633,34 @@ include AP_EFI/AP_EFI_Scripting.h depends AP_EFI_SCRIPTING_ENABLED
|
||||
include AP_EFI/AP_EFI_config.h
|
||||
|
||||
userdata Cylinder_Status depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
||||
userdata Cylinder_Status field ignition_timing_deg float'skip_check write
|
||||
userdata Cylinder_Status field injection_time_ms float'skip_check write
|
||||
userdata Cylinder_Status field cylinder_head_temperature float'skip_check write
|
||||
userdata Cylinder_Status field exhaust_gas_temperature float'skip_check write
|
||||
userdata Cylinder_Status field lambda_coefficient float'skip_check write
|
||||
userdata Cylinder_Status field ignition_timing_deg float'skip_check read write
|
||||
userdata Cylinder_Status field injection_time_ms float'skip_check read write
|
||||
userdata Cylinder_Status field cylinder_head_temperature float'skip_check read write
|
||||
userdata Cylinder_Status field exhaust_gas_temperature float'skip_check read write
|
||||
userdata Cylinder_Status field lambda_coefficient float'skip_check read write
|
||||
|
||||
userdata EFI_State depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
||||
userdata EFI_State field last_updated_ms uint32_t'skip_check write
|
||||
userdata EFI_State field general_error boolean write
|
||||
userdata EFI_State field engine_load_percent uint8_t'skip_check write
|
||||
userdata EFI_State field engine_speed_rpm uint32_t'skip_check write
|
||||
userdata EFI_State field spark_dwell_time_ms float'skip_check write
|
||||
userdata EFI_State field atmospheric_pressure_kpa float'skip_check write
|
||||
userdata EFI_State field intake_manifold_pressure_kpa float'skip_check write
|
||||
userdata EFI_State field intake_manifold_temperature float'skip_check write
|
||||
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 last_updated_ms uint32_t'skip_check read write
|
||||
userdata EFI_State field general_error boolean read write
|
||||
userdata EFI_State field engine_load_percent uint8_t'skip_check read write
|
||||
userdata EFI_State field engine_speed_rpm uint32_t'skip_check read write
|
||||
userdata EFI_State field spark_dwell_time_ms float'skip_check read write
|
||||
userdata EFI_State field atmospheric_pressure_kpa float'skip_check read write
|
||||
userdata EFI_State field intake_manifold_pressure_kpa float'skip_check read write
|
||||
userdata EFI_State field intake_manifold_temperature float'skip_check read write
|
||||
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_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
|
||||
userdata EFI_State field ecu_index uint8_t'skip_check write
|
||||
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 ignition_voltage float'skip_check write
|
||||
userdata EFI_State field throttle_out float'skip_check write
|
||||
userdata EFI_State field pt_compensation float'skip_check 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
|
||||
|
||||
ap_object AP_EFI_Backend depends (AP_EFI_SCRIPTING_ENABLED == 1)
|
||||
ap_object AP_EFI_Backend method handle_scripting boolean EFI_State
|
||||
|
Loading…
Reference in New Issue
Block a user