mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: Add an initial generator
This commit is contained in:
parent
7c017568e4
commit
e7d59514d9
2
libraries/AP_Scripting/generator/.gitignore
vendored
Normal file
2
libraries/AP_Scripting/generator/.gitignore
vendored
Normal file
@ -0,0 +1,2 @@
|
|||||||
|
./build/*
|
||||||
|
gen-bindings
|
35
libraries/AP_Scripting/generator/Makefile
Normal file
35
libraries/AP_Scripting/generator/Makefile
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
CC = gcc
|
||||||
|
CFLAGS = -Wall -Werror -Wextra -g
|
||||||
|
LDFLAGS = -lreadline
|
||||||
|
|
||||||
|
OBJ_DIR = build/obj
|
||||||
|
SRC_DIR = src
|
||||||
|
OUT_DIR = build
|
||||||
|
OUT_NAME = gen-bindings
|
||||||
|
OUT = $(OUT_DIR)/$(OUT_NAME)
|
||||||
|
|
||||||
|
_OBJS = main.c.o
|
||||||
|
OBJS = $(patsubst %,$(OBJ_DIR)/%,$(_OBJS))
|
||||||
|
|
||||||
|
.PHONY: all
|
||||||
|
all: directories $(OBJS)
|
||||||
|
$(CC) $(LDFLAGS) $(OBJS) -o $(OUT)
|
||||||
|
cp $(OUT) .
|
||||||
|
|
||||||
|
run: all
|
||||||
|
./$(OUT) -o ../lua_generated_bindings < description/bindings.desc
|
||||||
|
|
||||||
|
$(OBJ_DIR)/%.c.o: $(SRC_DIR)/%.c
|
||||||
|
$(CC) $(CFLAGS) -c $< -o $@
|
||||||
|
|
||||||
|
.PHONY: directories
|
||||||
|
directories:
|
||||||
|
mkdir -p $(OUT_DIR)
|
||||||
|
mkdir -p $(OBJ_DIR)
|
||||||
|
|
||||||
|
.PHONY: clean
|
||||||
|
clean:
|
||||||
|
rm -rf $(OBJ_DIR)/*c.o
|
||||||
|
rm -rf $(OUT_DIR)
|
||||||
|
rm -rf $(OUT)
|
||||||
|
rm -rf $(OUT_NAME)
|
28
libraries/AP_Scripting/generator/description/bindings.desc
Normal file
28
libraries/AP_Scripting/generator/description/bindings.desc
Normal file
@ -0,0 +1,28 @@
|
|||||||
|
-- Location stuff (this is a commented line)
|
||||||
|
|
||||||
|
include AP_Common/Location.h
|
||||||
|
|
||||||
|
userdata Location field lat int32_t read write -900000000 900000000
|
||||||
|
userdata Location field lng int32_t read write -1800000000 1800000000
|
||||||
|
userdata Location field relative_alt boolean read write
|
||||||
|
userdata Location field terrain_alt boolean read write
|
||||||
|
userdata Location field origin_alt boolean read write
|
||||||
|
userdata Location field loiter_xtrack boolean read write
|
||||||
|
|
||||||
|
userdata Location method get_distance float Location
|
||||||
|
userdata Location method offset void float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX
|
||||||
|
userdata Location method get_vector_from_origin_NEU boolean Vector3f
|
||||||
|
|
||||||
|
include AP_AHRS/AP_AHRS.h
|
||||||
|
|
||||||
|
singleton ahrs method get_position boolean Location
|
||||||
|
singleton ahrs method get_home Location
|
||||||
|
|
||||||
|
include AP_Math/AP_Math.h
|
||||||
|
|
||||||
|
userdata Vector3f field x float read write -FLT_MAX FLT_MAX
|
||||||
|
userdata Vector3f field y float read write -FLT_MAX FLT_MAX
|
||||||
|
userdata Vector3f field z float read write -FLT_MAX FLT_MAX
|
||||||
|
|
||||||
|
include AP_Notify/AP_Notify.h
|
||||||
|
singleton notify method play_tune void string
|
1127
libraries/AP_Scripting/generator/src/main.c
Normal file
1127
libraries/AP_Scripting/generator/src/main.c
Normal file
File diff suppressed because it is too large
Load Diff
@ -5,6 +5,8 @@
|
|||||||
|
|
||||||
#include "lua_bindings.h"
|
#include "lua_bindings.h"
|
||||||
|
|
||||||
|
#include "lua_generated_bindings.h"
|
||||||
|
|
||||||
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name);
|
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name);
|
||||||
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name) {
|
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name) {
|
||||||
#if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1
|
#if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1
|
||||||
@ -63,287 +65,6 @@ static const luaL_Reg servo_functions[] =
|
|||||||
{NULL, NULL}
|
{NULL, NULL}
|
||||||
};
|
};
|
||||||
|
|
||||||
// location stuff
|
|
||||||
static int new_location(lua_State *L) {
|
|
||||||
Location *loc = (Location *)lua_newuserdata(L, sizeof(Location));
|
|
||||||
luaL_getmetatable(L, "location");
|
|
||||||
lua_setmetatable(L, -2);
|
|
||||||
memset((void *)loc, 0, sizeof(Location));
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static Location *check_location(lua_State *L, int arg) {
|
|
||||||
void *data = luaL_checkudata(L, arg, "location");
|
|
||||||
luaL_argcheck(L, data != NULL, arg, "`location` expected");
|
|
||||||
return (Location *)data;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_lat(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushinteger(L, loc->lat);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
{
|
|
||||||
const int32_t lat = luaL_checkinteger(L, 2);
|
|
||||||
luaL_argcheck(L, ((lat >= -900000000) && (lat <= 900000000)), 2, "invalid latitude out of range");
|
|
||||||
loc->lat = lat;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_long(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushinteger(L, loc->lng);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
{
|
|
||||||
const int32_t lng = luaL_checkinteger(L, 2);
|
|
||||||
luaL_argcheck(L, ((lng >= -1800000000) && (lng <= 1800000000)), 2, "invalid longitude out of range");
|
|
||||||
loc->lng = lng;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_alt(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushinteger(L, loc->alt);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
loc->alt = luaL_checknumber(L, 2);
|
|
||||||
return 0;
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_relative_alt(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushboolean(L, loc->relative_alt);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
loc->relative_alt = lua_toboolean(L, 2);
|
|
||||||
return 0;
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_loiter_ccw(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushboolean(L, loc->loiter_ccw);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
loc->loiter_ccw = lua_toboolean(L, 2);
|
|
||||||
return 0;
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_terrain_alt(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushboolean(L, loc->terrain_alt);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
loc->terrain_alt = lua_toboolean(L, 2);
|
|
||||||
return 0;
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_origin_alt(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushboolean(L, loc->origin_alt);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
loc->origin_alt = lua_toboolean(L, 2);
|
|
||||||
return 0;
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_loiter_xtrack(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, 1);
|
|
||||||
switch(lua_gettop(L)) {
|
|
||||||
case 1: // access
|
|
||||||
lua_pushboolean(L, loc->loiter_xtrack);
|
|
||||||
return 1;
|
|
||||||
case 2: // set
|
|
||||||
loc->loiter_xtrack = lua_toboolean(L, 2);
|
|
||||||
return 0;
|
|
||||||
default:
|
|
||||||
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_tostring(lua_State *L) {
|
|
||||||
Location *loc = check_location(L, -1);
|
|
||||||
char buf[64] = {};
|
|
||||||
snprintf(buf, sizeof(buf),
|
|
||||||
"Loc(%ld.%07ld %c, %ld.%07ld %c, %.02f)",
|
|
||||||
labs(loc->lat / 10000000),
|
|
||||||
labs(loc->lat % 10000000),
|
|
||||||
loc->lat > 0 ? 'N' : 'S',
|
|
||||||
labs(loc->lng / 10000000),
|
|
||||||
labs(loc->lng % 10000000),
|
|
||||||
loc->lng > 0 ? 'E' : 'W',
|
|
||||||
loc->alt * 1e-2);
|
|
||||||
lua_pushstring(L, buf);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_distance(lua_State *L) {
|
|
||||||
const int args = lua_gettop(L);
|
|
||||||
if (args != 2) {
|
|
||||||
return luaL_argerror(L, args, "too many arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
lua_pushnumber(L, check_location(L, -2)->get_distance(*check_location(L, -1)));
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_project(lua_State *L) {
|
|
||||||
const int args = lua_gettop(L);
|
|
||||||
if (args != 3) {
|
|
||||||
return luaL_argerror(L, args, "too many arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
(*check_location(L, -3)).offset_bearing(luaL_checknumber(L, -2), luaL_checknumber(L, -1));
|
|
||||||
|
|
||||||
lua_pop(L, 2);
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_passed_point(lua_State *L) {
|
|
||||||
const int args = lua_gettop(L);
|
|
||||||
if (args != 3) {
|
|
||||||
return luaL_argerror(L, args, "too many arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
lua_pushboolean(L, location_passed_point(*check_location(L, -3),
|
|
||||||
*check_location(L, -2),
|
|
||||||
*check_location(L, -1)));
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_path_proportion(lua_State *L) {
|
|
||||||
const int args = lua_gettop(L);
|
|
||||||
if (args != 3) {
|
|
||||||
return luaL_argerror(L, args, "too many arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
lua_pushnumber(L, location_path_proportion(*check_location(L, -3),
|
|
||||||
*check_location(L, -2),
|
|
||||||
*check_location(L, -1)));
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_offset(lua_State *L) {
|
|
||||||
const int args = lua_gettop(L);
|
|
||||||
if (args != 3) {
|
|
||||||
return luaL_argerror(L, args, "too many arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
check_location(L, -3)->offset(luaL_checknumber(L, -2),
|
|
||||||
luaL_checknumber(L, -1));
|
|
||||||
|
|
||||||
lua_pop(L, 2);
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int location_equal(lua_State *L) {
|
|
||||||
const int args = lua_gettop(L);
|
|
||||||
if (args != 2) {
|
|
||||||
return luaL_argerror(L, args, "too many arguments");
|
|
||||||
}
|
|
||||||
|
|
||||||
Location *l2 = check_location(L, -2);
|
|
||||||
Location *l1 = check_location(L, -1);
|
|
||||||
|
|
||||||
lua_pushboolean(L, l1->same_latlon_as(*l2));
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const luaL_Reg locLib[] = {
|
|
||||||
{"new", new_location},
|
|
||||||
{NULL, NULL}
|
|
||||||
};
|
|
||||||
|
|
||||||
static const luaL_Reg locationMeta[] = {
|
|
||||||
{"lat", location_lat},
|
|
||||||
{"long", location_long},
|
|
||||||
{"alt", location_alt},
|
|
||||||
{"relative_alt", location_relative_alt},
|
|
||||||
{"loiter_ccw", location_loiter_ccw},
|
|
||||||
{"terrain_alt", location_terrain_alt},
|
|
||||||
{"origin_alt", location_origin_alt},
|
|
||||||
{"loiter_xtrack", location_loiter_xtrack},
|
|
||||||
{"distance", location_distance},
|
|
||||||
{"project", location_project},
|
|
||||||
{"passed_point", location_passed_point},
|
|
||||||
{"path_proportion", location_path_proportion},
|
|
||||||
{"offset", location_offset},
|
|
||||||
{"__tostring", location_tostring},
|
|
||||||
{"__eq", location_equal},
|
|
||||||
{NULL, NULL}
|
|
||||||
};
|
|
||||||
|
|
||||||
static int ahrs_position(lua_State *L) {
|
|
||||||
check_arguments(L, 1, "ahrs:position");
|
|
||||||
|
|
||||||
new_location(L);
|
|
||||||
Location *loc = check_location(L, -1);
|
|
||||||
AP::ahrs().get_position(*loc);
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int ahrs_get_home(lua_State *L) {
|
|
||||||
check_arguments(L, 1, "ahrs:home");
|
|
||||||
|
|
||||||
new_location(L);
|
|
||||||
Location *loc = check_location(L, -1);
|
|
||||||
*loc = AP::ahrs().get_home();
|
|
||||||
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static const luaL_Reg ahrsMeta[] = {
|
|
||||||
{"position", ahrs_position},
|
|
||||||
{"home", ahrs_get_home},
|
|
||||||
{NULL, NULL}
|
|
||||||
};
|
|
||||||
|
|
||||||
// all bindings
|
|
||||||
|
|
||||||
void load_lua_bindings(lua_State *L) {
|
void load_lua_bindings(lua_State *L) {
|
||||||
luaL_newlib(L, gcs_functions);
|
luaL_newlib(L, gcs_functions);
|
||||||
lua_setglobal(L, "gcs");
|
lua_setglobal(L, "gcs");
|
||||||
@ -351,28 +72,6 @@ void load_lua_bindings(lua_State *L) {
|
|||||||
luaL_newlib(L, servo_functions);
|
luaL_newlib(L, servo_functions);
|
||||||
lua_setglobal(L, "servo");
|
lua_setglobal(L, "servo");
|
||||||
|
|
||||||
// location metatable
|
load_generated_bindings(L);
|
||||||
luaL_newmetatable(L, "location");
|
|
||||||
luaL_setfuncs(L, locationMeta, 0);
|
|
||||||
lua_pushstring(L, "__index");
|
|
||||||
lua_pushvalue(L, -2);
|
|
||||||
lua_settable(L, -3);
|
|
||||||
lua_pop(L, 1);
|
|
||||||
luaL_newlib(L, locLib);
|
|
||||||
lua_setglobal(L, "loc");
|
|
||||||
|
|
||||||
// ahrs metatable
|
|
||||||
luaL_newmetatable(L, "ahrs");
|
|
||||||
luaL_setfuncs(L, ahrsMeta, 0);
|
|
||||||
lua_pushstring(L, "__index");
|
|
||||||
lua_pushvalue(L, -2);
|
|
||||||
lua_settable(L, -3);
|
|
||||||
lua_pop(L, 1);
|
|
||||||
|
|
||||||
// ahrs userdata
|
|
||||||
lua_newuserdata(L, 0); // lose the pointer, we don't really care about it
|
|
||||||
luaL_getmetatable(L, "ahrs");
|
|
||||||
lua_setmetatable(L, -2);
|
|
||||||
lua_setglobal(L, "ahrs");
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
385
libraries/AP_Scripting/lua_generated_bindings.cpp
Normal file
385
libraries/AP_Scripting/lua_generated_bindings.cpp
Normal file
@ -0,0 +1,385 @@
|
|||||||
|
// auto generated bindings, don't manually edit
|
||||||
|
#include "lua_generated_bindings.h"
|
||||||
|
#include <AP_Notify/AP_Notify.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
|
|
||||||
|
|
||||||
|
int new_Vector3f(lua_State *L) {
|
||||||
|
Vector3f *ud = (Vector3f *)lua_newuserdata(L, sizeof(Vector3f));
|
||||||
|
new (ud) Vector3f();
|
||||||
|
luaL_getmetatable(L, "Vector3f");
|
||||||
|
lua_setmetatable(L, -2);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int new_Location(lua_State *L) {
|
||||||
|
Location *ud = (Location *)lua_newuserdata(L, sizeof(Location));
|
||||||
|
new (ud) Location();
|
||||||
|
luaL_getmetatable(L, "Location");
|
||||||
|
lua_setmetatable(L, -2);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
Vector3f * check_Vector3f(lua_State *L, int arg) {
|
||||||
|
void *data = luaL_checkudata(L, arg, "Vector3f");
|
||||||
|
return (Vector3f *)data;
|
||||||
|
}
|
||||||
|
|
||||||
|
Location * check_Location(lua_State *L, int arg) {
|
||||||
|
void *data = luaL_checkudata(L, arg, "Location");
|
||||||
|
return (Location *)data;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Vector3f_z(lua_State *L) {
|
||||||
|
Vector3f *ud = check_Vector3f(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushnumber(L, ud->z);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const float data_2 = luaL_checknumber(L, 2);
|
||||||
|
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "z out of range");
|
||||||
|
ud->z = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Vector3f_y(lua_State *L) {
|
||||||
|
Vector3f *ud = check_Vector3f(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushnumber(L, ud->y);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const float data_2 = luaL_checknumber(L, 2);
|
||||||
|
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "y out of range");
|
||||||
|
ud->y = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Vector3f_x(lua_State *L) {
|
||||||
|
Vector3f *ud = check_Vector3f(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushnumber(L, ud->x);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const float data_2 = luaL_checknumber(L, 2);
|
||||||
|
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "x out of range");
|
||||||
|
ud->x = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_loiter_xtrack(lua_State *L) {
|
||||||
|
Location *ud = check_Location(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushinteger(L, ud->loiter_xtrack);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const bool data_2 = lua_toboolean(L, 2);
|
||||||
|
ud->loiter_xtrack = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_origin_alt(lua_State *L) {
|
||||||
|
Location *ud = check_Location(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushinteger(L, ud->origin_alt);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const bool data_2 = lua_toboolean(L, 2);
|
||||||
|
ud->origin_alt = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_terrain_alt(lua_State *L) {
|
||||||
|
Location *ud = check_Location(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushinteger(L, ud->terrain_alt);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const bool data_2 = lua_toboolean(L, 2);
|
||||||
|
ud->terrain_alt = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_relative_alt(lua_State *L) {
|
||||||
|
Location *ud = check_Location(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushinteger(L, ud->relative_alt);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const bool data_2 = lua_toboolean(L, 2);
|
||||||
|
ud->relative_alt = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_lng(lua_State *L) {
|
||||||
|
Location *ud = check_Location(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushinteger(L, ud->lng);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const int32_t data_2 = luaL_checkinteger(L, 2);
|
||||||
|
luaL_argcheck(L, ((data_2 >= -1800000000) && (data_2 <= 1800000000)), 2, "lng out of range");
|
||||||
|
ud->lng = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_lat(lua_State *L) {
|
||||||
|
Location *ud = check_Location(L, 1);
|
||||||
|
switch(lua_gettop(L)) {
|
||||||
|
case 1:
|
||||||
|
lua_pushinteger(L, ud->lat);
|
||||||
|
return 1;
|
||||||
|
case 2: {
|
||||||
|
const int32_t data_2 = luaL_checkinteger(L, 2);
|
||||||
|
luaL_argcheck(L, ((data_2 >= -900000000) && (data_2 <= 900000000)), 2, "lat out of range");
|
||||||
|
ud->lat = data_2;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
return luaL_argerror(L, lua_gettop(L), "too many arguments");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_get_vector_from_origin_NEU(lua_State *L) {
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 2) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
} else if (args < 2) {
|
||||||
|
return luaL_argerror(L, args, "too few arguments");
|
||||||
|
}
|
||||||
|
|
||||||
|
Location * ud = check_Location(L, 1);
|
||||||
|
Vector3f & data_2 = *check_Vector3f(L, 2);
|
||||||
|
const bool data = ud->get_vector_from_origin_NEU(
|
||||||
|
data_2);
|
||||||
|
|
||||||
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_offset(lua_State *L) {
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 3) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
} else if (args < 3) {
|
||||||
|
return luaL_argerror(L, args, "too few arguments");
|
||||||
|
}
|
||||||
|
|
||||||
|
Location * ud = check_Location(L, 1);
|
||||||
|
const float data_2 = luaL_checknumber(L, 2);
|
||||||
|
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "argument out of range");
|
||||||
|
const float data_3 = luaL_checknumber(L, 3);
|
||||||
|
luaL_argcheck(L, ((data_3 >= -FLT_MAX) && (data_3 <= FLT_MAX)), 3, "argument out of range");
|
||||||
|
ud->offset(
|
||||||
|
data_2,
|
||||||
|
data_3);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int Location_get_distance(lua_State *L) {
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 2) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
} else if (args < 2) {
|
||||||
|
return luaL_argerror(L, args, "too few arguments");
|
||||||
|
}
|
||||||
|
|
||||||
|
Location * ud = check_Location(L, 1);
|
||||||
|
Location & data_2 = *check_Location(L, 2);
|
||||||
|
const float data = ud->get_distance(
|
||||||
|
data_2);
|
||||||
|
|
||||||
|
lua_pushnumber(L, data);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
const luaL_Reg Vector3f_meta[] = {
|
||||||
|
{"z", Vector3f_z},
|
||||||
|
{"y", Vector3f_y},
|
||||||
|
{"x", Vector3f_x},
|
||||||
|
{NULL, NULL}
|
||||||
|
};
|
||||||
|
|
||||||
|
const luaL_Reg Location_meta[] = {
|
||||||
|
{"loiter_xtrack", Location_loiter_xtrack},
|
||||||
|
{"origin_alt", Location_origin_alt},
|
||||||
|
{"terrain_alt", Location_terrain_alt},
|
||||||
|
{"relative_alt", Location_relative_alt},
|
||||||
|
{"lng", Location_lng},
|
||||||
|
{"lat", Location_lat},
|
||||||
|
{"get_vector_from_origin_NEU", Location_get_vector_from_origin_NEU},
|
||||||
|
{"offset", Location_offset},
|
||||||
|
{"get_distance", Location_get_distance},
|
||||||
|
{NULL, NULL}
|
||||||
|
};
|
||||||
|
|
||||||
|
int notify_play_tune(lua_State *L) {
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 2) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
} else if (args < 2) {
|
||||||
|
return luaL_argerror(L, args, "too few arguments");
|
||||||
|
}
|
||||||
|
|
||||||
|
luaL_checkudata(L, 1, "notify");
|
||||||
|
const char * data_2 = luaL_checkstring(L, 2);
|
||||||
|
AP::notify().play_tune(
|
||||||
|
data_2);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int ahrs_get_home(lua_State *L) {
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 1) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
} else if (args < 1) {
|
||||||
|
return luaL_argerror(L, args, "too few arguments");
|
||||||
|
}
|
||||||
|
|
||||||
|
luaL_checkudata(L, 1, "ahrs");
|
||||||
|
const Location &data = AP::ahrs().get_home(
|
||||||
|
);
|
||||||
|
|
||||||
|
new_Location(L);
|
||||||
|
*check_Location(L, -1) = data;
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
int ahrs_get_position(lua_State *L) {
|
||||||
|
const int args = lua_gettop(L);
|
||||||
|
if (args > 2) {
|
||||||
|
return luaL_argerror(L, args, "too many arguments");
|
||||||
|
} else if (args < 2) {
|
||||||
|
return luaL_argerror(L, args, "too few arguments");
|
||||||
|
}
|
||||||
|
|
||||||
|
luaL_checkudata(L, 1, "ahrs");
|
||||||
|
Location & data_2 = *check_Location(L, 2);
|
||||||
|
const bool data = AP::ahrs().get_position(
|
||||||
|
data_2);
|
||||||
|
|
||||||
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
const luaL_Reg notify_meta[] = {
|
||||||
|
{"play_tune", notify_play_tune},
|
||||||
|
{NULL, NULL}
|
||||||
|
};
|
||||||
|
|
||||||
|
const luaL_Reg ahrs_meta[] = {
|
||||||
|
{"get_home", ahrs_get_home},
|
||||||
|
{"get_position", ahrs_get_position},
|
||||||
|
{NULL, NULL}
|
||||||
|
};
|
||||||
|
|
||||||
|
const struct userdata_fun {
|
||||||
|
const char *name;
|
||||||
|
const luaL_Reg *reg;
|
||||||
|
} userdata_fun[] = {
|
||||||
|
{"Vector3f", Vector3f_meta},
|
||||||
|
{"Location", Location_meta},
|
||||||
|
};
|
||||||
|
|
||||||
|
const struct singleton_fun {
|
||||||
|
const char *name;
|
||||||
|
const luaL_Reg *reg;
|
||||||
|
} singleton_fun[] = {
|
||||||
|
{"notify", notify_meta},
|
||||||
|
{"ahrs", ahrs_meta},
|
||||||
|
};
|
||||||
|
|
||||||
|
void load_generated_bindings(lua_State *L) {
|
||||||
|
// userdata metatables
|
||||||
|
for (uint32_t i = 0; i < ARRAY_SIZE(userdata_fun); i++) {
|
||||||
|
luaL_newmetatable(L, userdata_fun[i].name);
|
||||||
|
luaL_setfuncs(L, userdata_fun[i].reg, 0);
|
||||||
|
lua_pushstring(L, "__index");
|
||||||
|
lua_pushvalue(L, -2);
|
||||||
|
lua_settable(L, -3);
|
||||||
|
lua_pop(L, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
// singleton metatables
|
||||||
|
for (uint32_t i = 0; i < ARRAY_SIZE(singleton_fun); i++) {
|
||||||
|
luaL_newmetatable(L, singleton_fun[i].name);
|
||||||
|
luaL_setfuncs(L, singleton_fun[i].reg, 0);
|
||||||
|
lua_pushstring(L, "__index");
|
||||||
|
lua_pushvalue(L, -2);
|
||||||
|
lua_settable(L, -3);
|
||||||
|
lua_pop(L, 1);
|
||||||
|
lua_newuserdata(L, 0);
|
||||||
|
luaL_getmetatable(L, singleton_fun[i].name);
|
||||||
|
lua_setmetatable(L, -2);
|
||||||
|
lua_setglobal(L, singleton_fun[i].name);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *singletons[] = {
|
||||||
|
"notify",
|
||||||
|
"ahrs",
|
||||||
|
};
|
||||||
|
|
||||||
|
const struct userdata {
|
||||||
|
const char *name;
|
||||||
|
const lua_CFunction fun;
|
||||||
|
} new_userdata[] = {
|
||||||
|
{"Vector3f", new_Vector3f},
|
||||||
|
{"Location", new_Location},
|
||||||
|
};
|
||||||
|
|
||||||
|
void load_generated_sandbox(lua_State *L) {
|
||||||
|
for (uint32_t i = 0; i < ARRAY_SIZE(singletons); i++) {
|
||||||
|
lua_pushstring(L, singletons[i]);
|
||||||
|
lua_getglobal(L, singletons[i]);
|
||||||
|
lua_settable(L, -3);
|
||||||
|
}
|
||||||
|
for (uint32_t i = 0; i < ARRAY_SIZE(new_userdata); i++) {
|
||||||
|
lua_pushstring(L, new_userdata[i].name);
|
||||||
|
lua_pushcfunction(L, new_userdata[i].fun);
|
||||||
|
lua_settable(L, -3);
|
||||||
|
}
|
||||||
|
}
|
15
libraries/AP_Scripting/lua_generated_bindings.h
Normal file
15
libraries/AP_Scripting/lua_generated_bindings.h
Normal file
@ -0,0 +1,15 @@
|
|||||||
|
#pragma once
|
||||||
|
// auto generated bindings, don't manually edit
|
||||||
|
#include <AP_Notify/AP_Notify.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
#include <AP_Common/Location.h>
|
||||||
|
#include "lua/src/lua.hpp"
|
||||||
|
#include <new>
|
||||||
|
|
||||||
|
int new_Vector3f(lua_State *L);
|
||||||
|
Vector3f * check_Vector3f(lua_State *L, int arg);
|
||||||
|
int new_Location(lua_State *L);
|
||||||
|
Location * check_Location(lua_State *L, int arg);
|
||||||
|
void load_generated_bindings(lua_State *L);
|
||||||
|
void load_generated_sandbox(lua_State *L);
|
@ -26,6 +26,8 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include "lua_generated_bindings.h"
|
||||||
|
|
||||||
#ifndef SCRIPTING_DIRECTORY
|
#ifndef SCRIPTING_DIRECTORY
|
||||||
#if HAL_OS_FATFS_IO
|
#if HAL_OS_FATFS_IO
|
||||||
#define SCRIPTING_DIRECTORY "/APM/scripts"
|
#define SCRIPTING_DIRECTORY "/APM/scripts"
|
||||||
@ -99,6 +101,7 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
|
|||||||
hal.console->printf("Lua: Scripting: Could not create sandbox: %s", lua_tostring(L, -1));
|
hal.console->printf("Lua: Scripting: Could not create sandbox: %s", lua_tostring(L, -1));
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
load_generated_sandbox(L);
|
||||||
lua_setupvalue(L, -2, 1);
|
lua_setupvalue(L, -2, 1);
|
||||||
|
|
||||||
new_script->lua_ref = luaL_ref(L, LUA_REGISTRYINDEX); // cache the reference
|
new_script->lua_ref = luaL_ref(L, LUA_REGISTRYINDEX); // cache the reference
|
||||||
|
@ -31,7 +31,5 @@ function get_sandbox_env ()
|
|||||||
-- ArduPilot specific
|
-- ArduPilot specific
|
||||||
gcs = { send_text = gcs.send_text},
|
gcs = { send_text = gcs.send_text},
|
||||||
servo = { set_output_pwm = servo.set_output_pwm},
|
servo = { set_output_pwm = servo.set_output_pwm},
|
||||||
location = { new = loc.new},
|
|
||||||
ahrs = ahrs
|
|
||||||
}
|
}
|
||||||
end
|
end
|
||||||
|
Loading…
Reference in New Issue
Block a user