mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add binding and helper to get old params
This commit is contained in:
parent
4a2af10f96
commit
918b8a1a9c
|
@ -12,6 +12,38 @@ bool Parameter::init(const char *name)
|
|||
return true;
|
||||
}
|
||||
|
||||
// init by info, to get the value of old params
|
||||
bool Parameter::init_by_info(uint16_t key, uint32_t group_element, enum ap_var_type type)
|
||||
{
|
||||
switch (type) {
|
||||
case AP_PARAM_INT8:
|
||||
vp = new AP_Int8;
|
||||
break;
|
||||
case AP_PARAM_INT16:
|
||||
vp = new AP_Int16;
|
||||
break;
|
||||
case AP_PARAM_INT32:
|
||||
vp = new AP_Int32;
|
||||
break;
|
||||
case AP_PARAM_FLOAT:
|
||||
vp = new AP_Float;
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
if (vp == nullptr) {
|
||||
return false;
|
||||
}
|
||||
vtype = type;
|
||||
AP_Param::ConversionInfo info = {
|
||||
key,
|
||||
group_element,
|
||||
type,
|
||||
nullptr
|
||||
};
|
||||
return AP_Param::find_old_parameter(&info, vp);
|
||||
}
|
||||
|
||||
// set a value
|
||||
bool Parameter::set(float value)
|
||||
{
|
||||
|
|
|
@ -10,6 +10,9 @@ public:
|
|||
// init to param by name
|
||||
bool init(const char *name);
|
||||
|
||||
// init by token, to get the value of old params
|
||||
bool init_by_info(uint16_t key, uint32_t group_element, enum ap_var_type type);
|
||||
|
||||
// setters and getters
|
||||
bool set(float value);
|
||||
bool set_and_save(float value);
|
||||
|
|
|
@ -321,6 +321,17 @@ function Parameter_ud:set(value) end
|
|||
---@return number|nil
|
||||
function Parameter_ud:get() end
|
||||
|
||||
-- desc
|
||||
---@param key integer
|
||||
---@param group_element uint32_t_ud
|
||||
---@param type integer
|
||||
---| '1' # AP_PARAM_INT8
|
||||
---| '2' # AP_PARAM_INT16
|
||||
---| '3' # AP_PARAM_INT32
|
||||
---| '4' # AP_PARAM_FLOAT
|
||||
---@return boolean
|
||||
function Parameter_ud:init_by_info(key, group_element, type) end
|
||||
|
||||
-- desc
|
||||
---@param name string
|
||||
---@return boolean
|
||||
|
|
|
@ -314,6 +314,7 @@ singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string fl
|
|||
|
||||
include AP_Scripting/AP_Scripting_helpers.h
|
||||
userdata Parameter method init boolean string
|
||||
userdata Parameter method init_by_info boolean uint16_t 0 UINT16_MAX uint32_t 0U UINT32_MAX ap_var_type'enum AP_PARAM_INT8 AP_PARAM_FLOAT
|
||||
userdata Parameter method get boolean float'Null
|
||||
userdata Parameter method set boolean float'skip_check
|
||||
userdata Parameter method set_and_save boolean float'skip_check
|
||||
|
|
Loading…
Reference in New Issue