mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Parameter helper: allow optional param name in constructior
This commit is contained in:
parent
049101580a
commit
41e36e3128
|
@ -1,7 +1,40 @@
|
||||||
#include "AP_Scripting_helpers.h"
|
#include "AP_Scripting_helpers.h"
|
||||||
|
#include <AP_Scripting/lua_generated_bindings.h>
|
||||||
|
|
||||||
/// Fast param access via pointer helper class
|
/// Fast param access via pointer helper class
|
||||||
|
|
||||||
|
// Custom lua constructor with optional param name
|
||||||
|
int lua_new_Parameter(lua_State *L) {
|
||||||
|
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 1) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
}
|
||||||
|
const char * name = nullptr;
|
||||||
|
if (args == 1) {
|
||||||
|
name = luaL_checkstring(L, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// This chunk is the same as the auto generated constructor
|
||||||
|
luaL_checkstack(L, 2, "Out of stack");
|
||||||
|
void *ud = lua_newuserdata(L, sizeof(Parameter));
|
||||||
|
memset(ud, 0, sizeof(Parameter));
|
||||||
|
new (ud) Parameter();
|
||||||
|
luaL_getmetatable(L, "Parameter");
|
||||||
|
lua_setmetatable(L, -2);
|
||||||
|
|
||||||
|
if (args == 0) {
|
||||||
|
// no arguments, nothing to do
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!static_cast<Parameter*>(ud)->init(name)) {
|
||||||
|
return luaL_error(L, "No parameter: %s", name);
|
||||||
|
}
|
||||||
|
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
// init by name
|
// init by name
|
||||||
bool Parameter::init(const char *name)
|
bool Parameter::init(const char *name)
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,6 +1,9 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
#include "lua/src/lua.hpp"
|
||||||
|
|
||||||
|
int lua_new_Parameter(lua_State *L);
|
||||||
|
|
||||||
/// Fast param access via pointer helper
|
/// Fast param access via pointer helper
|
||||||
class Parameter
|
class Parameter
|
||||||
|
|
|
@ -296,7 +296,8 @@ function mavlink_mission_item_int_t_ud:param1(value) end
|
||||||
local Parameter_ud = {}
|
local Parameter_ud = {}
|
||||||
|
|
||||||
---@return Parameter_ud
|
---@return Parameter_ud
|
||||||
function Parameter() end
|
---@param name? string
|
||||||
|
function Parameter(name) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param value number
|
---@param value number
|
||||||
|
|
|
@ -14,6 +14,20 @@ if not fake_param:init('FAKE_PARAM') then
|
||||||
gcs:send_text(6, 'get FAKE_PARAM failed')
|
gcs:send_text(6, 'get FAKE_PARAM failed')
|
||||||
end
|
end
|
||||||
|
|
||||||
|
-- Can also pass param string in constructor to remove the need to init manualy
|
||||||
|
local user_param = Parameter('SCR_USER1')
|
||||||
|
-- this will error out for a bad parameter
|
||||||
|
-- Parameter('FAKE_PARAM')
|
||||||
|
local success, err = pcall(Parameter,'FAKE_PARAM')
|
||||||
|
gcs:send_text(0, "Lua Caught Error: " .. err)
|
||||||
|
-- this allows this example to catch the otherwise fatal error
|
||||||
|
-- not recommend if error is possible/expected, use separate construction and init
|
||||||
|
|
||||||
|
-- local user_param = Parameter('SCR_USER1')
|
||||||
|
-- is equivalent to:
|
||||||
|
-- local user_param = Parameter()
|
||||||
|
-- assert(user_param:init('SCR_USER1'), 'No parameter: SCR_USER1')
|
||||||
|
|
||||||
function update() -- this is the loop which periodically runs
|
function update() -- this is the loop which periodically runs
|
||||||
|
|
||||||
-- get and print all the scripting parameters
|
-- get and print all the scripting parameters
|
||||||
|
@ -64,6 +78,12 @@ function update() -- this is the loop which periodically runs
|
||||||
gcs:send_text(6, 'LUA: read SCR_VM_I_COUNT failed')
|
gcs:send_text(6, 'LUA: read SCR_VM_I_COUNT failed')
|
||||||
end
|
end
|
||||||
|
|
||||||
|
local user = user_param:get()
|
||||||
|
if user then
|
||||||
|
gcs:send_text(6, string.format('LUA: SCR_USER1: %i', user))
|
||||||
|
else
|
||||||
|
gcs:send_text(6, 'LUA: read SCR_USER1 failed')
|
||||||
|
end
|
||||||
|
|
||||||
count = count + 1;
|
count = count + 1;
|
||||||
|
|
||||||
|
|
|
@ -326,6 +326,7 @@ singleton AP_Param method add_table boolean uint8_t 0 200 string uint8_t 1 63
|
||||||
singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string float'skip_check
|
singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string float'skip_check
|
||||||
|
|
||||||
include AP_Scripting/AP_Scripting_helpers.h
|
include AP_Scripting/AP_Scripting_helpers.h
|
||||||
|
userdata Parameter creation lua_new_Parameter
|
||||||
userdata Parameter method init boolean string
|
userdata Parameter method init boolean string
|
||||||
userdata Parameter method init_by_info boolean uint16_t 0 UINT16_MAX uint32_t'skip_check ap_var_type'enum AP_PARAM_INT8 AP_PARAM_FLOAT
|
userdata Parameter method init_by_info boolean uint16_t 0 UINT16_MAX uint32_t'skip_check ap_var_type'enum AP_PARAM_INT8 AP_PARAM_FLOAT
|
||||||
userdata Parameter method get boolean float'Null
|
userdata Parameter method get boolean float'Null
|
||||||
|
|
Loading…
Reference in New Issue