mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Scripting: load uint32_t bindings via generator
This commit is contained in:
parent
5bfb295fdd
commit
7850aea186
@ -524,3 +524,24 @@ singleton i2c manual get_device lua_get_i2c_device
|
|||||||
global manual millis lua_millis
|
global manual millis lua_millis
|
||||||
global manual micros lua_micros
|
global manual micros lua_micros
|
||||||
global manual mission_receive lua_mission_receive
|
global manual mission_receive lua_mission_receive
|
||||||
|
|
||||||
|
userdata uint32_t creation lua_new_uint32_t
|
||||||
|
userdata uint32_t manual_operator __add uint32_t___add
|
||||||
|
userdata uint32_t manual_operator __sub uint32_t___sub
|
||||||
|
userdata uint32_t manual_operator __mul uint32_t___mul
|
||||||
|
userdata uint32_t manual_operator __div uint32_t___div
|
||||||
|
userdata uint32_t manual_operator __mod uint32_t___mod
|
||||||
|
userdata uint32_t manual_operator __idiv uint32_t___idiv
|
||||||
|
userdata uint32_t manual_operator __band uint32_t___band
|
||||||
|
userdata uint32_t manual_operator __bor uint32_t___bor
|
||||||
|
userdata uint32_t manual_operator __bxor uint32_t___bxor
|
||||||
|
userdata uint32_t manual_operator __shl uint32_t___shl
|
||||||
|
userdata uint32_t manual_operator __shr uint32_t___shr
|
||||||
|
userdata uint32_t manual_operator __eq uint32_t___eq
|
||||||
|
userdata uint32_t manual_operator __lt uint32_t___lt
|
||||||
|
userdata uint32_t manual_operator __le uint32_t___le
|
||||||
|
userdata uint32_t manual_operator __bnot uint32_t___bnot
|
||||||
|
userdata uint32_t manual_operator __tostring uint32_t___tostring
|
||||||
|
userdata uint32_t manual toint uint32_t_toint
|
||||||
|
userdata uint32_t manual tofloat uint32_t_tofloat
|
||||||
|
|
||||||
|
@ -2278,8 +2278,6 @@ void emit_loaders(void) {
|
|||||||
fprintf(source, " }\n");
|
fprintf(source, " }\n");
|
||||||
|
|
||||||
fprintf(source, "\n");
|
fprintf(source, "\n");
|
||||||
fprintf(source, " load_boxed_numerics(L);\n");
|
|
||||||
|
|
||||||
fprintf(source, "}\n\n");
|
fprintf(source, "}\n\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -2335,9 +2333,6 @@ void emit_sandbox(void) {
|
|||||||
fprintf(source, " }\n");
|
fprintf(source, " }\n");
|
||||||
|
|
||||||
fprintf(source, "\n");
|
fprintf(source, "\n");
|
||||||
fprintf(source, " load_boxed_numerics_sandbox(L);\n");
|
|
||||||
|
|
||||||
// load the userdata complex functions
|
|
||||||
fprintf(source, "}\n");
|
fprintf(source, "}\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,5 +1,6 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "lua_boxed_numerics.h"
|
#include "lua_boxed_numerics.h"
|
||||||
|
#include <AP_Scripting/lua_generated_bindings.h>
|
||||||
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -34,18 +35,7 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg) {
|
|||||||
return luaL_argerror(L, arg, "Unable to coerce to uint32_t");
|
return luaL_argerror(L, arg, "Unable to coerce to uint32_t");
|
||||||
}
|
}
|
||||||
|
|
||||||
// creates a new userdata for a uint32_t
|
|
||||||
int new_uint32_t(lua_State *L) {
|
|
||||||
luaL_checkstack(L, 2, "Out of stack");
|
|
||||||
|
|
||||||
*static_cast<uint32_t *>(lua_newuserdata(L, sizeof(uint32_t))) = 0;
|
|
||||||
luaL_getmetatable(L, "uint32_t");
|
|
||||||
lua_setmetatable(L, -2);
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// the exposed constructor to lua calls to create a uint32_t
|
// the exposed constructor to lua calls to create a uint32_t
|
||||||
int lua_new_uint32_t(lua_State *L);
|
|
||||||
int lua_new_uint32_t(lua_State *L) {
|
int lua_new_uint32_t(lua_State *L) {
|
||||||
const int args = lua_gettop(L);
|
const int args = lua_gettop(L);
|
||||||
if (args > 1) {
|
if (args > 1) {
|
||||||
@ -58,13 +48,8 @@ int lua_new_uint32_t(lua_State *L) {
|
|||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t * check_uint32_t(lua_State *L, int arg) {
|
|
||||||
void *data = luaL_checkudata(L, arg, "uint32_t");
|
|
||||||
return static_cast<uint32_t *>(data);
|
|
||||||
}
|
|
||||||
|
|
||||||
#define UINT32_T_BOX_OP(name, sym) \
|
#define UINT32_T_BOX_OP(name, sym) \
|
||||||
static int uint32_t___##name(lua_State *L) { \
|
int uint32_t___##name(lua_State *L) { \
|
||||||
const int args = lua_gettop(L); \
|
const int args = lua_gettop(L); \
|
||||||
if (args > 2) { \
|
if (args > 2) { \
|
||||||
return luaL_argerror(L, args, "too many arguments"); \
|
return luaL_argerror(L, args, "too many arguments"); \
|
||||||
@ -93,7 +78,7 @@ UINT32_T_BOX_OP(shl, <<)
|
|||||||
UINT32_T_BOX_OP(shr, >>)
|
UINT32_T_BOX_OP(shr, >>)
|
||||||
|
|
||||||
#define UINT32_T_BOX_OP_BOOL(name, sym) \
|
#define UINT32_T_BOX_OP_BOOL(name, sym) \
|
||||||
static int uint32_t___##name(lua_State *L) { \
|
int uint32_t___##name(lua_State *L) { \
|
||||||
const int args = lua_gettop(L); \
|
const int args = lua_gettop(L); \
|
||||||
luaL_checkstack(L, 1, "Out of stack"); \
|
luaL_checkstack(L, 1, "Out of stack"); \
|
||||||
if (args > 2) { \
|
if (args > 2) { \
|
||||||
@ -114,7 +99,7 @@ UINT32_T_BOX_OP_BOOL(lt, <)
|
|||||||
UINT32_T_BOX_OP_BOOL(le, <=)
|
UINT32_T_BOX_OP_BOOL(le, <=)
|
||||||
|
|
||||||
#define UINT32_T_BOX_OP_UNARY(name, sym) \
|
#define UINT32_T_BOX_OP_UNARY(name, sym) \
|
||||||
static int uint32_t___##name(lua_State *L) { \
|
int uint32_t___##name(lua_State *L) { \
|
||||||
const int args = lua_gettop(L); \
|
const int args = lua_gettop(L); \
|
||||||
luaL_checkstack(L, 1, "Out of stack"); \
|
luaL_checkstack(L, 1, "Out of stack"); \
|
||||||
if (args != 1) { \
|
if (args != 1) { \
|
||||||
@ -131,7 +116,7 @@ UINT32_T_BOX_OP_BOOL(le, <=)
|
|||||||
// DO NOT SUPPORT UNARY NEGATION
|
// DO NOT SUPPORT UNARY NEGATION
|
||||||
UINT32_T_BOX_OP_UNARY(bnot, ~)
|
UINT32_T_BOX_OP_UNARY(bnot, ~)
|
||||||
|
|
||||||
static int uint32_t_toint(lua_State *L) {
|
int uint32_t_toint(lua_State *L) {
|
||||||
const int args = lua_gettop(L);
|
const int args = lua_gettop(L);
|
||||||
if (args != 1) {
|
if (args != 1) {
|
||||||
return luaL_argerror(L, args, "Expected 1 argument");
|
return luaL_argerror(L, args, "Expected 1 argument");
|
||||||
@ -144,7 +129,7 @@ static int uint32_t_toint(lua_State *L) {
|
|||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int uint32_t_tofloat(lua_State *L) {
|
int uint32_t_tofloat(lua_State *L) {
|
||||||
const int args = lua_gettop(L);
|
const int args = lua_gettop(L);
|
||||||
if (args != 1) {
|
if (args != 1) {
|
||||||
return luaL_argerror(L, args, "Expected 1 argument");
|
return luaL_argerror(L, args, "Expected 1 argument");
|
||||||
@ -157,7 +142,7 @@ static int uint32_t_tofloat(lua_State *L) {
|
|||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int uint32_t___tostring(lua_State *L) {
|
int uint32_t___tostring(lua_State *L) {
|
||||||
const int args = lua_gettop(L);
|
const int args = lua_gettop(L);
|
||||||
if (args != 1) {
|
if (args != 1) {
|
||||||
return luaL_argerror(L, args, "Expected 1 argument");
|
return luaL_argerror(L, args, "Expected 1 argument");
|
||||||
@ -172,43 +157,3 @@ static int uint32_t___tostring(lua_State *L) {
|
|||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
const luaL_Reg uint32_t_meta[] = {
|
|
||||||
{"__add", uint32_t___add},
|
|
||||||
{"__sub", uint32_t___sub},
|
|
||||||
{"__mul", uint32_t___mul},
|
|
||||||
{"__div", uint32_t___div},
|
|
||||||
{"__mod", uint32_t___mod},
|
|
||||||
{"__idiv", uint32_t___idiv},
|
|
||||||
{"__band", uint32_t___band},
|
|
||||||
{"__bor", uint32_t___bor},
|
|
||||||
{"__bxor", uint32_t___bxor},
|
|
||||||
{"__shl", uint32_t___shl},
|
|
||||||
{"__shr", uint32_t___shr},
|
|
||||||
{"__shr", uint32_t___shr},
|
|
||||||
{"__eq", uint32_t___eq},
|
|
||||||
{"__lt", uint32_t___lt},
|
|
||||||
{"__le", uint32_t___le},
|
|
||||||
{"__bnot", uint32_t___bnot},
|
|
||||||
{"__tostring", uint32_t___tostring},
|
|
||||||
{"toint", uint32_t_toint},
|
|
||||||
{"tofloat", uint32_t_tofloat},
|
|
||||||
{NULL, NULL}
|
|
||||||
};
|
|
||||||
|
|
||||||
void load_boxed_numerics(lua_State *L) {
|
|
||||||
luaL_checkstack(L, 5, "Out of stack");
|
|
||||||
luaL_newmetatable(L, "uint32_t");
|
|
||||||
luaL_setfuncs(L, uint32_t_meta, 0);
|
|
||||||
lua_pushstring(L, "__index");
|
|
||||||
lua_pushvalue(L, -2);
|
|
||||||
lua_settable(L, -3);
|
|
||||||
lua_pop(L, 1);
|
|
||||||
}
|
|
||||||
|
|
||||||
void load_boxed_numerics_sandbox(lua_State *L) {
|
|
||||||
// if there are ever more drivers then move to a table based solution
|
|
||||||
lua_pushstring(L, "uint32_t");
|
|
||||||
lua_pushcfunction(L, lua_new_uint32_t);
|
|
||||||
lua_settable(L, -3);
|
|
||||||
}
|
|
||||||
|
@ -2,9 +2,24 @@
|
|||||||
|
|
||||||
#include "lua/src/lua.hpp"
|
#include "lua/src/lua.hpp"
|
||||||
|
|
||||||
int new_uint32_t(lua_State *L);
|
|
||||||
uint32_t *check_uint32_t(lua_State *L, int arg);
|
|
||||||
uint32_t coerce_to_uint32_t(lua_State *L, int arg);
|
uint32_t coerce_to_uint32_t(lua_State *L, int arg);
|
||||||
|
int lua_new_uint32_t(lua_State *L);
|
||||||
|
|
||||||
void load_boxed_numerics(lua_State *L);
|
int uint32_t___add(lua_State *L);
|
||||||
void load_boxed_numerics_sandbox(lua_State *L);
|
int uint32_t___sub(lua_State *L);
|
||||||
|
int uint32_t___mul(lua_State *L);
|
||||||
|
int uint32_t___div(lua_State *L);
|
||||||
|
int uint32_t___mod(lua_State *L);
|
||||||
|
int uint32_t___idiv(lua_State *L);
|
||||||
|
int uint32_t___band(lua_State *L);
|
||||||
|
int uint32_t___bor(lua_State *L);
|
||||||
|
int uint32_t___bxor(lua_State *L);
|
||||||
|
int uint32_t___shl(lua_State *L);
|
||||||
|
int uint32_t___shr(lua_State *L);
|
||||||
|
int uint32_t___eq(lua_State *L);
|
||||||
|
int uint32_t___lt(lua_State *L);
|
||||||
|
int uint32_t___le(lua_State *L);
|
||||||
|
int uint32_t___bnot(lua_State *L);
|
||||||
|
int uint32_t___tostring(lua_State *L);
|
||||||
|
int uint32_t_toint(lua_State *L);
|
||||||
|
int uint32_t_tofloat(lua_State *L);
|
||||||
|
Loading…
Reference in New Issue
Block a user