Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Scripting: add param set and get #12889

Open
wants to merge 6 commits into
base: master
from
Open
Changes from all commits
Commits
File filter...
Filter file types
Jump to…
Jump to file or symbol
Failed to load files and symbols.

Always

Just for now

@@ -38,6 +38,9 @@ extern const AP_HAL::HAL &hal;

uint16_t AP_Param::sentinal_offset;

// singleton instance
AP_Param *AP_Param::_singleton;

#define ENABLE_DEBUG 1

#if ENABLE_DEBUG
@@ -379,6 +382,14 @@ bool AP_Param::get_base(const struct Info &info, ptrdiff_t &base)
return true;
}

namespace AP {

AP_Param *param()
{
return AP_Param::get_singleton();
}

}

// find the info structure given a header and a group_info table
// return the Info structure and a pointer to the variables storage
@@ -2329,6 +2340,39 @@ bool AP_Param::set_by_name(const char *name, float value)
return false;
}

/*
get a value by name
*/
bool AP_Param::get_by_name(const char *name, float &value)
{
enum ap_var_type vtype;
AP_Param *vp = find(name, &vtype);
if (vp == nullptr) {
return false;
}
switch (vtype) {
case AP_PARAM_INT8:
value = ((AP_Int8 *)vp)->get();
break;
case AP_PARAM_INT16:
value = ((AP_Int16 *)vp)->get();
break;

case AP_PARAM_INT32:
value = ((AP_Int32 *)vp)->get();
break;

case AP_PARAM_FLOAT:
value = ((AP_Float *)vp)->get();
break;

default:
// not a supported type
return false;
}
return true;
}

/*
set and save a value by name
*/
@@ -193,6 +193,11 @@ class AP_Param
uint16_t i;
for (i=0; info[i].type != AP_PARAM_NONE; i++) ;
_num_vars = i;

if (_singleton != nullptr) {
AP_HAL::panic("AP_Param must be singleton");
}
_singleton = this;
}

// empty constructor
@@ -278,6 +283,13 @@ class AP_Param
/// @return true if the variable is found
static bool set_by_name(const char *name, float value);

/// gat a value by name
///
/// @param name The full name of the variable to be found.
/// @param value A refrence to the variable
/// @return true if the variable is found
static bool get_by_name(const char *name, float &value);

/// set and save a value by name
///
/// @param name The full name of the variable to be found.
@@ -467,7 +479,11 @@ class AP_Param
AP_HAL::BetterStream *port);
#endif // AP_PARAM_KEY_DUMP

static AP_Param *get_singleton() { return _singleton; }

private:
static AP_Param *_singleton;

/// EEPROM header
///
/// This structure is placed at the head of the EEPROM to indicate
@@ -661,6 +677,10 @@ class AP_Param
void save_io_handler(void);
};

namespace AP {
AP_Param *param();
};

/// Template class for scalar variables.
///
/// Objects of this type have a value, and can be treated in many ways as though they
@@ -61,7 +61,7 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = {
// @Increment: 1024
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("HEAP_SIZE", 3, AP_Scripting, _script_heap_size, 42*1024),
AP_GROUPINFO("HEAP_SIZE", 3, AP_Scripting, _script_heap_size, 43*1024),

AP_GROUPINFO("DEBUG_LVL", 4, AP_Scripting, _debug_level, 1),

@@ -0,0 +1,54 @@
-- This script is a test of param set and get
local count = 0

function update() -- this is the loop which periodically runs

-- get and print all the scripting paramerters
local value = param:get_by_name('SCR_ENABLE')
if value then
gcs:send_text(0, string.format('LUA: SCR_ENABLE: %i',value))
else
gcs:send_text(0, 'LUA: get SCR_ENABLE failed')
end
value = param:get_by_name('SCR_VM_I_COUNT')
if value then
gcs:send_text(0, string.format('LUA: SCR_VM_I_COUNT: %i',value))
else
gcs:send_text(0, 'LUA: get SCR_VM_I_COUNT failed')
end
value = param:get_by_name('SCR_HEAP_SIZE')
if value then
gcs:send_text(0, string.format('LUA: SCR_HEAP_SIZE: %i',value))
else
gcs:send_text(0, 'LUA: get SCR_HEAP_SIZE failed')
end
value = param:get_by_name('SCR_DEBUG_LVL')
if value then
gcs:send_text(0, string.format('LUA: SCR_DEBUG_LVL: %i',value))
else
gcs:send_text(0, 'LUA: get SCR_DEBUG_LVL failed')
end

-- increment the script heap size by one
local heap_size = param:get_by_name('SCR_HEAP_SIZE')
if heap_size then
if not(param:set_by_name('SCR_HEAP_SIZE',heap_size + 1)) then
gcs:send_text(0, 'LUA: param set failed')
end
else
gcs:send_text(0, 'LUA: get SCR_HEAP_SIZE failed')
end


count = count + 1;

-- self terminate after 30 loops
if count > 30 then
gcs:send_text(0, 'LUA: goodby, world')
param:set_by_name('SCR_ENABLE',0)
end

return update, 1000 -- reschedules the loop
end

return update() -- run immediately before starting to reschedule
@@ -152,3 +152,9 @@ singleton AP_SerialLED method send void
include SRV_Channel/SRV_Channel.h
singleton SRV_Channels alias SRV_Channels
singleton SRV_Channels method find_channel boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint8_t'Null

include AP_Param/AP_Param.h
singleton AP_Param alias param
singleton AP_Param method get_by_name boolean string float'Null
singleton AP_Param method set_by_name boolean string float -FLT_MAX FLT_MAX
singleton AP_Param method set_and_save_by_name boolean string float -FLT_MAX FLT_MAX
@@ -1,6 +1,7 @@
// auto generated bindings, don't manually edit
#include "lua_generated_bindings.h"
#include "lua_boxed_numerics.h"
#include <AP_Param/AP_Param.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_SerialLED/AP_SerialLED.h>
#include <AP_Vehicle/AP_Vehicle.h>
@@ -513,6 +514,65 @@ const luaL_Reg Location_meta[] = {
{NULL, NULL}
};

static int AP_Param_set_and_save_by_name(lua_State *L) {
AP_Param * ud = AP_Param::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "param not supported on this firmware");
}

binding_argcheck(L, 3);
const char * data_2 = luaL_checkstring(L, 2);
const float raw_data_3 = luaL_checknumber(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3;
const bool data = ud->set_and_save_by_name(
data_2,
data_3);

lua_pushboolean(L, data);
return 1;
}

static int AP_Param_set_by_name(lua_State *L) {
AP_Param * ud = AP_Param::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "param not supported on this firmware");
}

binding_argcheck(L, 3);
const char * data_2 = luaL_checkstring(L, 2);
const float raw_data_3 = luaL_checknumber(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3;
const bool data = ud->set_by_name(
data_2,
data_3);

lua_pushboolean(L, data);
return 1;
}

static int AP_Param_get_by_name(lua_State *L) {
AP_Param * ud = AP_Param::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "param not supported on this firmware");
}

binding_argcheck(L, 2);
const char * data_2 = luaL_checkstring(L, 2);
float data_5003 = {};
const bool data = ud->get_by_name(
data_2,
data_5003);

if (data) {
lua_pushnumber(L, data_5003);
} else {
lua_pushnil(L);
}
return 1;
}

static int SRV_Channels_find_channel(lua_State *L) {
SRV_Channels * ud = SRV_Channels::get_singleton();
if (ud == nullptr) {
@@ -1689,6 +1749,13 @@ static int AP_AHRS_get_roll(lua_State *L) {
return 1;
}

const luaL_Reg AP_Param_meta[] = {
{"set_and_save_by_name", AP_Param_set_and_save_by_name},
{"set_by_name", AP_Param_set_by_name},
{"get_by_name", AP_Param_get_by_name},
{NULL, NULL}
};

const luaL_Reg SRV_Channels_meta[] = {
{"find_channel", SRV_Channels_find_channel},
{NULL, NULL}
@@ -1837,6 +1904,7 @@ const struct userdata_meta userdata_fun[] = {
};

const struct userdata_meta singleton_fun[] = {
{"param", AP_Param_meta, NULL},
{"SRV_Channels", SRV_Channels_meta, NULL},
{"serialLED", AP_SerialLED_meta, NULL},
{"vehicle", AP_Vehicle_meta, NULL},
@@ -1890,6 +1958,7 @@ void load_generated_bindings(lua_State *L) {
}

const char *singletons[] = {
"param",
"SRV_Channels",
"serialLED",
"vehicle",
@@ -1,5 +1,6 @@
#pragma once
// auto generated bindings, don't manually edit
#include <AP_Param/AP_Param.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_SerialLED/AP_SerialLED.h>
#include <AP_Vehicle/AP_Vehicle.h>
ProTip! Use n and p to navigate between commits in a pull request.
You can’t perform that action at this time.