AP_Scripting: update docs

This commit is contained in:
Andrew Tridgell 2022-09-29 15:02:44 +10:00
parent bea668a2bd
commit 4c40279d48
1 changed files with 111 additions and 0 deletions

View File

@ -67,6 +67,117 @@ i2c = {}
---@return AP_HAL__I2CDevice_ud
function i2c:get_device(bus, address, clock, smbus) end
-- EFI state structure
---@class EFI_State_ud
local EFI_State_ud = {}
---@return EFI_State_ud
function EFI_State() end
-- set field
---@param value Cylinder_Status_ud
function EFI_State_ud:cylinder_status(value) end
-- set field
---@param value integer
function EFI_State_ud:ecu_index(value) end
-- set field
---@param value integer
function EFI_State_ud:throttle_position_percent(value) end
-- set field
---@param value number
function EFI_State_ud:estimated_consumed_fuel_volume_cm3(value) end
-- set field
---@param value number
function EFI_State_ud:fuel_consumption_rate_cm3pm(value) end
-- set field
---@param value number
function EFI_State_ud:fuel_pressure(value) end
-- set field
---@param value number
function EFI_State_ud:oil_temperature(value) end
-- set field
---@param value number
function EFI_State_ud:oil_pressure(value) end
-- set field
---@param value number
function EFI_State_ud:coolant_temperature(value) end
-- set field
---@param value number
function EFI_State_ud:intake_manifold_temperature(value) end
-- set field
---@param value number
function EFI_State_ud:intake_manifold_pressure_kpa(value) end
-- set field
---@param value number
function EFI_State_ud:atmospheric_pressure_kpa(value) end
-- set field
---@param value number
function EFI_State_ud:spark_dwell_time_ms(value) end
-- set field
---@param value uint32_t_ud
function EFI_State_ud:engine_speed_rpm(value) end
-- set field
---@param value integer
function EFI_State_ud:engine_load_percent(value) end
-- set field
---@param value boolean
function EFI_State_ud:general_error(value) end
-- set field
---@param value uint32_t_ud
function EFI_State_ud:last_updated_ms(value) end
-- EFI Cylinder_Status structure
---@class Cylinder_Status_ud
local Cylinder_Status_ud = {}
---@return Cylinder_Status_ud
function Cylinder_Status() end
-- set field
---@param value number
function Cylinder_Status_ud:lambda_coefficient(value) end
-- set field
---@param value number
function Cylinder_Status_ud:exhaust_gas_temperature(value) end
-- set field
---@param value number
function Cylinder_Status_ud:cylinder_head_temperature(value) end
-- set field
---@param value number
function Cylinder_Status_ud:injection_time_ms(value) end
-- set field
---@param value number
function Cylinder_Status_ud:ignition_timing_deg(value) end
-- desc
---@class efi
efi = {}
-- EFI handle scripting update
---@param efi_state EFI_State_ud
function efi:handle_scripting(efi_state) end
-- CAN bus interaction
---@class CAN