mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add virtual class in docs to avoid need nil check warning
This commit is contained in:
parent
dfc04cd53a
commit
cb22a6389d
|
@ -669,38 +669,39 @@ function mavlink_mission_item_int_t_ud:param1() end
|
|||
function mavlink_mission_item_int_t_ud:param1(value) end
|
||||
|
||||
|
||||
-- desc
|
||||
-- Parameter access helper.
|
||||
---@class (exact) Parameter_ud
|
||||
local Parameter_ud = {}
|
||||
|
||||
-- Create a new parameter helper, init must be called with a parameter name.
|
||||
---@return Parameter_ud
|
||||
---@param name? string
|
||||
function Parameter(name) end
|
||||
function Parameter() end
|
||||
|
||||
-- desc
|
||||
-- Set the defualt value of this parameter, if the parameter has not been configured by the user its value will be updated to the new defualt.
|
||||
---@param value number
|
||||
---@return boolean
|
||||
function Parameter_ud:set_default(value) end
|
||||
|
||||
-- desc
|
||||
-- Return true if the parameter has been configured by the user.
|
||||
---@return boolean
|
||||
function Parameter_ud:configured() end
|
||||
|
||||
-- desc
|
||||
-- Set the parameter to the given value and save. The value will be persistant after a reboot.
|
||||
---@param value number
|
||||
---@return boolean
|
||||
function Parameter_ud:set_and_save(value) end
|
||||
|
||||
-- desc
|
||||
-- Set the parameter to the given value. The value will not persist a reboot.
|
||||
---@param value number
|
||||
---@return boolean
|
||||
function Parameter_ud:set(value) end
|
||||
|
||||
-- desc
|
||||
-- Get the current value of a parameter.
|
||||
-- Returns nil if the init has not been called and a valid parameter found.
|
||||
---@return number|nil
|
||||
function Parameter_ud:get() end
|
||||
|
||||
-- desc
|
||||
-- Init the paramter from a key. This allows the script to load old parameter that have been removed from the main code.
|
||||
---@param key integer
|
||||
---@param group_element uint32_t_ud|integer|number
|
||||
---@param type integer
|
||||
|
@ -711,11 +712,43 @@ function Parameter_ud:get() end
|
|||
---@return boolean
|
||||
function Parameter_ud:init_by_info(key, group_element, type) end
|
||||
|
||||
-- desc
|
||||
-- Init this parameter from a name.
|
||||
---@param name string
|
||||
---@return boolean
|
||||
function Parameter_ud:init(name) end
|
||||
|
||||
-- Parameter access helper
|
||||
---@class (exact) Parameter_ud_const
|
||||
local Parameter_ud_const = {}
|
||||
|
||||
-- Create a new parameter helper with a parameter name.
|
||||
-- This will error if no parameter with the given name is found.
|
||||
---@return Parameter_ud_const
|
||||
---@param name string
|
||||
function Parameter(name) end
|
||||
|
||||
-- Set the defualt value of this parameter, if the parameter has not been configured by the user its value will be updated to the new defualt.
|
||||
---@param value number
|
||||
---@return boolean
|
||||
function Parameter_ud_const:set_default(value) end
|
||||
|
||||
-- Retrun true if the parameter has been configured by the user.
|
||||
---@return boolean
|
||||
function Parameter_ud_const:configured() end
|
||||
|
||||
-- Set the parameter to the given value and save. The value will be persistant after a reboot.
|
||||
---@param value number
|
||||
---@return boolean
|
||||
function Parameter_ud_const:set_and_save(value) end
|
||||
|
||||
-- Set the parameter to the given value. The value will not persist a reboot.
|
||||
---@param value number
|
||||
---@return boolean
|
||||
function Parameter_ud_const:set(value) end
|
||||
|
||||
-- Get the current value of a parameter.
|
||||
---@return number
|
||||
function Parameter_ud_const:get() end
|
||||
|
||||
-- Vector2f is a userdata object that holds a 2D vector with x and y components. The components are stored as floating point numbers.
|
||||
-- To create a new Vector2f you can call Vector2f() to allocate a new one, or call a method that returns one to you.
|
||||
|
|
|
@ -458,7 +458,7 @@ singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string fl
|
|||
singleton AP_Param method add_param depends AP_PARAM_DYNAMIC_ENABLED
|
||||
|
||||
include AP_Scripting/AP_Scripting_helpers.h
|
||||
userdata Parameter creation lua_new_Parameter 1
|
||||
userdata Parameter creation lua_new_Parameter 0
|
||||
userdata Parameter method init boolean string
|
||||
userdata Parameter method init_by_info boolean uint16_t'skip_check uint32_t'skip_check ap_var_type'enum AP_PARAM_INT8 AP_PARAM_FLOAT
|
||||
userdata Parameter method get boolean float'Null
|
||||
|
|
|
@ -85,13 +85,16 @@ class method(object):
|
|||
return (self.global_name == other.global_name) and (self.local_name == other.local_name) and (self.num_args == other.num_args)
|
||||
|
||||
def is_overload(self, other):
|
||||
# Allow manual bindings to have fewer arguments
|
||||
# this allows multiple function definitions with different params
|
||||
return other.manual and (self.global_name == other.global_name) and (self.local_name == other.local_name) and (self.num_args < other.num_args)
|
||||
white_list = [
|
||||
"Parameter"
|
||||
]
|
||||
allow_override = other.manual or (self.global_name in white_list)
|
||||
return allow_override and (self.global_name == other.global_name) and (self.local_name == other.local_name) and (self.num_args != other.num_args)
|
||||
|
||||
def get_return_type(line):
|
||||
try:
|
||||
match = re.findall("^---@return (\w+(\|(\w+))*)", line)
|
||||
match = re.findall(r"^---@return (\w+(\|(\w+))*)", line)
|
||||
all_types = match[0][0]
|
||||
return all_types.split("|")
|
||||
|
||||
|
@ -100,7 +103,7 @@ def get_return_type(line):
|
|||
|
||||
def get_param_type(line):
|
||||
try:
|
||||
match = re.findall("^---@param (?:\w+\??|...) (\w+(\|(\w+))*)", line)
|
||||
match = re.findall(r"^---@param (?:\w+\??|...) (\w+(\|(\w+))*)", line)
|
||||
all_types = match[0][0]
|
||||
return all_types.split("|")
|
||||
|
||||
|
@ -202,8 +205,18 @@ def compare(expected_file_name, got_file_name):
|
|||
pass_check = False
|
||||
|
||||
|
||||
# White list of classes that are allowed unexpected definitions
|
||||
white_list = [
|
||||
# "virtual" class to bypass need for nil check when getting a parameter value, Parameter_ud is used internally, Parameter_ud_const exists only in the docs.
|
||||
"Parameter_ud_const"
|
||||
]
|
||||
|
||||
# make sure no unexpected methods are included
|
||||
for got in got_methods:
|
||||
if got.global_name in white_list:
|
||||
# Dont check if in the white list
|
||||
continue
|
||||
|
||||
found = False
|
||||
for meth in expected_methods:
|
||||
if (got == meth) or got.is_overload(meth):
|
||||
|
|
Loading…
Reference in New Issue