AP_Scripting: Add support for UART drivers

Also improves the handling of uint32_t arguments
This commit is contained in:
Michael du Breuil 2020-01-08 13:34:26 -07:00 committed by WickedShell
parent f0a50c51f6
commit 51f79c1b10
7 changed files with 409 additions and 44 deletions

View File

@ -0,0 +1,22 @@
local port = serial:find_serial(0)
port:begin(115200)
port:set_flow_control(0)
local step = 65
function spit ()
if port:available() > 0 then
read = port:read()
gcs:send_text(0, read .. " = " .. step)
end
if step > 122 then
step = 65
else
step = step + 1
end
return spit, 1000
port:write(step)
end
return spit, 1000

View File

@ -159,3 +159,14 @@ singleton SRV_Channels method find_channel boolean SRV_Channel::Aux_servo_functi
include RC_Channel/RC_Channel.h
singleton RC_Channels alias rc
singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null
include AP_SerialManager/AP_SerialManager.h
ap_object AP_HAL::UARTDriver method begin void uint32_t 1U UINT32_MAX
ap_object AP_HAL::UARTDriver method read int16_t
ap_object AP_HAL::UARTDriver method write uint32_t uint8_t 0 UINT8_MAX
ap_object AP_HAL::UARTDriver method available uint32_t
ap_object AP_HAL::UARTDriver method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_AUTO
singleton AP_SerialManager alias serial
singleton AP_SerialManager method find_serial AP_HAL::UARTDriver AP_SerialManager::SerialProtocol_Scripting'literal uint8_t 0 UINT8_MAX

View File

@ -8,6 +8,7 @@
#include <getopt.h>
char keyword_alias[] = "alias";
char keyword_ap_object[] = "ap_object";
char keyword_comment[] = "--";
char keyword_depends[] = "depends";
char keyword_enum[] = "enum";
@ -97,6 +98,7 @@ enum field_type {
TYPE_ENUM,
TYPE_LITERAL,
TYPE_USERDATA,
TYPE_AP_OBJECT
};
const char * type_labels[TYPE_USERDATA + 1] = { "bool",
@ -110,6 +112,7 @@ const char * type_labels[TYPE_USERDATA + 1] = { "bool",
"string",
"enum",
"userdata",
"ap_object",
};
enum operator_type {
@ -143,7 +146,10 @@ struct type {
enum access_type access;
uint32_t flags;
union {
char *userdata_name;
struct ud {
char *name;
char *sanatized_name;
} ud;
char *enum_name;
char *literal;
} data;
@ -264,6 +270,7 @@ void handle_header(void) {
enum userdata_type {
UD_USERDATA,
UD_SINGLETON,
UD_AP_OBJECT,
};
struct argument {
@ -302,6 +309,7 @@ struct userdata_enum {
struct userdata {
struct userdata * next;
char *name; // name of the C++ singleton
char *sanatized_name; // sanatized name of the C++ singleton
char *alias; // (optional) used for scripting access
struct userdata_field *fields;
struct method *methods;
@ -312,6 +320,8 @@ struct userdata {
};
static struct userdata *parsed_userdata = NULL;
static struct userdata *parsed_ap_objects = NULL;
struct dependency {
struct dependency * next;
@ -328,6 +338,17 @@ void string_copy(char **dest, const char * src) {
strcpy(*dest, src);
}
void sanatize_name(char **dest, char *src) {
*dest = (char *)allocate(strlen(src) + 1);
strcpy(*dest, src);
char *position = strchr(*dest, ':');
while (position) {
*position = '_';
position = strchr(position, ':');
}
};
struct range_check *parse_range_check(enum field_type type) {
char * low = next_token();
if (low == NULL) {
@ -375,6 +396,7 @@ unsigned int parse_access_flags(struct type * type) {
case TYPE_ENUM:
type->range = parse_range_check(type->type);
break;
case TYPE_AP_OBJECT:
case TYPE_USERDATA:
case TYPE_BOOLEAN:
case TYPE_STRING:
@ -474,9 +496,19 @@ int parse_type(struct type *type, const uint32_t restrictions, enum range_check_
} else if (type->type == TYPE_LITERAL) {
string_copy(&(type->data.literal), data_type);
} else {
// assume that this is a user data, we can't validate this until later though
type->type = TYPE_USERDATA;
string_copy(&(type->data.userdata_name), data_type);
// this must be a user data or an ap_object, check if it's already been declared as an object
struct userdata *node = parsed_ap_objects;
while (node != NULL && strcmp(node->name, data_type)) {
node = node->next;
}
if (node != NULL) {
type->type = TYPE_AP_OBJECT;
} else {
// assume that this is a user data, we can't validate this until later though
type->type = TYPE_USERDATA;
}
string_copy(&(type->data.ud.name), data_type);
sanatize_name(&(type->data.ud.sanatized_name), type->data.ud.name);
}
// sanity check that only supported types are nullable
@ -495,6 +527,7 @@ int parse_type(struct type *type, const uint32_t restrictions, enum range_check_
case TYPE_ENUM:
case TYPE_USERDATA:
break;
case TYPE_AP_OBJECT:
case TYPE_LITERAL:
case TYPE_NONE:
error(ERROR_USERDATA, "%s types cannot be nullable", data_type);
@ -515,6 +548,7 @@ int parse_type(struct type *type, const uint32_t restrictions, enum range_check_
case TYPE_ENUM:
type->range = parse_range_check(type->type);
break;
case TYPE_AP_OBJECT:
case TYPE_BOOLEAN:
case TYPE_NONE:
case TYPE_STRING:
@ -681,6 +715,7 @@ void handle_userdata(void) {
node->ud_type = UD_USERDATA;
node->name = (char *)allocate(strlen(name) + 1);
strcpy(node->name, name);
sanatize_name(&(node->sanatized_name), node->name);
node->next = parsed_userdata;
parsed_userdata = node;
} else {
@ -729,6 +764,7 @@ void handle_singleton(void) {
node->ud_type = UD_SINGLETON;
node->name = (char *)allocate(strlen(name) + 1);
strcpy(node->name, name);
sanatize_name(&(node->sanatized_name), node->name);
node->next = parsed_singletons;
parsed_singletons = node;
}
@ -766,6 +802,61 @@ void handle_singleton(void) {
}
}
void handle_ap_object(void) {
trace(TRACE_SINGLETON, "Adding a ap_object");
char *name = next_token();
if (name == NULL) {
error(ERROR_USERDATA, "Expected a name for the ap_object");
}
struct userdata *node = parsed_ap_objects;
while (node != NULL && strcmp(node->name, name)) {
node = node->next;
}
if (node == NULL) {
trace(TRACE_USERDATA, "Allocating new ap_object for %s", name);
node = (struct userdata *)allocate(sizeof(struct userdata));
node->ud_type = UD_AP_OBJECT;
node->name = (char *)allocate(strlen(name) + 1);
strcpy(node->name, name);
sanatize_name(&(node->sanatized_name), node->name);
node->next = parsed_ap_objects;
parsed_ap_objects = node;
}
// read type
char *type = next_token();
if (type == NULL) {
error(ERROR_SINGLETON, "Expected a access type for ap_object %s", name);
}
if (strcmp(type, keyword_alias) == 0) {
if (node->alias != NULL) {
error(ERROR_SINGLETON, "Alias of %s was already declared for %s", node->alias, node->name);
}
const char *alias = next_token();
if (alias == NULL) {
error(ERROR_SINGLETON, "Missing the name of the alias for %s", node->name);
}
node->alias = (char *)allocate(strlen(alias) + 1);
strcpy(node->alias, alias);
} else if (strcmp(type, keyword_semaphore) == 0) {
node->flags |= UD_FLAG_SEMAPHORE;
} else if (strcmp(type, keyword_method) == 0) {
handle_method(node->name, &(node->methods));
} else {
error(ERROR_SINGLETON, "AP_Objects only support aliases, methods or semaphore keyowrds (got %s)", type);
}
// ensure no more tokens on the line
if (next_token()) {
error(ERROR_HEADER, "Singleton contained an unexpected extra token: %s", state.token);
}
}
void handle_depends(void) {
trace(TRACE_DEPENDS, "Adding a dependency");
@ -827,7 +918,7 @@ void emit_dependencies(FILE *f) {
void emit_userdata_allocators(void) {
struct userdata * node = parsed_userdata;
while (node) {
fprintf(source, "int new_%s(lua_State *L) {\n", node->name);
fprintf(source, "int new_%s(lua_State *L) {\n", node->sanatized_name);
fprintf(source, " luaL_checkstack(L, 2, \"Out of stack\");\n"); // ensure we have sufficent stack to push the return
fprintf(source, " void *ud = lua_newuserdata(L, sizeof(%s));\n", node->name);
fprintf(source, " memset(ud, 0, sizeof(%s));\n", node->name);
@ -840,10 +931,25 @@ void emit_userdata_allocators(void) {
}
}
void emit_ap_object_allocators(void) {
struct userdata * node = parsed_ap_objects;
while (node) {
fprintf(source, "int new_%s(lua_State *L) {\n", node->sanatized_name);
fprintf(source, " luaL_checkstack(L, 2, \"Out of stack\");\n"); // ensure we have sufficent stack to push the return
fprintf(source, " void *ud = lua_newuserdata(L, sizeof(%s *));\n", node->name);
fprintf(source, " memset(ud, 0, sizeof(%s *));\n", node->name); // FIXME: memset is a ridiculously large hammer here
fprintf(source, " luaL_getmetatable(L, \"%s\");\n", node->name);
fprintf(source, " lua_setmetatable(L, -2);\n");
fprintf(source, " return 1;\n");
fprintf(source, "}\n\n");
node = node->next;
}
}
void emit_userdata_checkers(void) {
struct userdata * node = parsed_userdata;
while (node) {
fprintf(source, "%s * check_%s(lua_State *L, int arg) {\n", node->name, node->name);
fprintf(source, "%s * check_%s(lua_State *L, int arg) {\n", node->name, node->sanatized_name);
fprintf(source, " void *data = luaL_checkudata(L, arg, \"%s\");\n", node->name);
fprintf(source, " return (%s *)data;\n", node->name);
fprintf(source, "}\n\n");
@ -851,11 +957,31 @@ void emit_userdata_checkers(void) {
}
}
void emit_ap_object_checkers(void) {
struct userdata * node = parsed_ap_objects;
while (node) {
fprintf(source, "%s ** check_%s(lua_State *L, int arg) {\n", node->name, node->sanatized_name);
fprintf(source, " void *data = luaL_checkudata(L, arg, \"%s\");\n", node->name);
fprintf(source, " return (%s **)data;\n", node->name);
fprintf(source, "}\n\n");
node = node->next;
}
}
void emit_userdata_declarations(void) {
struct userdata * node = parsed_userdata;
while (node) {
fprintf(header, "int new_%s(lua_State *L);\n", node->name);
fprintf(header, "%s * check_%s(lua_State *L, int arg);\n", node->name, node->name);
fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name);
fprintf(header, "%s * check_%s(lua_State *L, int arg);\n", node->name, node->sanatized_name);
node = node->next;
}
}
void emit_ap_object_declarations(void) {
struct userdata * node = parsed_ap_objects;
while (node) {
fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name);
fprintf(header, "%s ** check_%s(lua_State *L, int arg);\n", node->name, node->sanatized_name);
node = node->next;
}
}
@ -895,6 +1021,7 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
case TYPE_UINT32_T:
fprintf(source, "%suint32_t data_%d = {};\n", indentation, arg_number);
break;
case TYPE_AP_OBJECT:
case TYPE_NONE:
case TYPE_LITERAL:
return; // nothing to do here, this should potentially be checked outside of this, but it makes an easier implementation to accept it
@ -905,7 +1032,7 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
fprintf(source, "%suint32_t data_%d = {};\n", indentation, arg_number);
break;
case TYPE_USERDATA:
fprintf(source, "%s%s data_%d = {};\n", indentation, t.data.userdata_name, arg_number);
fprintf(source, "%s%s data_%d = {};\n", indentation, t.data.ud.name, arg_number);
break;
}
} else {
@ -952,6 +1079,7 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
break;
case TYPE_NONE:
return; // nothing to do here, this should potentially be checked outside of this, but it makes an easier implementation to accept it
case TYPE_AP_OBJECT:
case TYPE_STRING:
case TYPE_BOOLEAN:
case TYPE_USERDATA:
@ -975,8 +1103,9 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
fprintf(source, "%sconst lua_Integer raw_data_%d = luaL_checkinteger(L, %d);\n", indentation, arg_number, arg_number - skipped);
break;
case TYPE_UINT32_T:
fprintf(source, "%sconst uint32_t raw_data_%d = *check_uint32_t(L, %d);\n", indentation, arg_number, arg_number - skipped);
fprintf(source, "%sconst uint32_t raw_data_%d = coerce_to_uint32_t(L, %d);\n", indentation, arg_number, arg_number - skipped);
break;
case TYPE_AP_OBJECT:
case TYPE_NONE:
case TYPE_STRING:
case TYPE_BOOLEAN:
@ -1013,6 +1142,7 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
case TYPE_UINT32_T:
cast_target = "uint32_t";
break;
case TYPE_AP_OBJECT:
case TYPE_NONE:
case TYPE_STRING:
case TYPE_BOOLEAN:
@ -1064,7 +1194,10 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
fprintf(source, "%sconst %s data_%d = static_cast<%s>(raw_data_%d);\n", indentation, t.data.enum_name, arg_number, t.data.enum_name, arg_number);
break;
case TYPE_USERDATA:
fprintf(source, "%s%s & data_%d = *check_%s(L, %d);\n", indentation, t.data.userdata_name, arg_number, t.data.userdata_name, arg_number);
fprintf(source, "%s%s & data_%d = *check_%s(L, %d);\n", indentation, t.data.ud.name, arg_number, t.data.ud.sanatized_name, arg_number);
break;
case TYPE_AP_OBJECT:
fprintf(source, "%s%s * data_%d = *check_%s(L, %d);\n", indentation, t.data.ud.name, arg_number, t.data.ud.sanatized_name, arg_number);
break;
case TYPE_LITERAL:
// literals are expected to be done directly later
@ -1077,8 +1210,8 @@ void emit_checker(const struct type t, int arg_number, int skipped, const char *
}
void emit_userdata_field(const struct userdata *data, const struct userdata_field *field) {
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, field->name);
fprintf(source, " %s *ud = check_%s(L, 1);\n", data->name, data->name);
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, field->name);
fprintf(source, " %s *ud = check_%s(L, 1);\n", data->name, data->sanatized_name);
fprintf(source, " switch(lua_gettop(L)) {\n");
if (field->access_flags & ACCESS_FLAG_READ) {
@ -1114,6 +1247,9 @@ void emit_userdata_field(const struct userdata *data, const struct userdata_fiel
case TYPE_USERDATA:
error(ERROR_USERDATA, "Userdata does not currently support accss to userdata field's");
break;
case TYPE_AP_OBJECT: // FIXME: collapse the identical cases here, and use the type string function
error(ERROR_USERDATA, "AP_Object does not currently support accss to userdata field's");
break;
}
fprintf(source, " return 1;\n");
}
@ -1149,7 +1285,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
const char *access_name = data->alias ? data->alias : data->name;
// bind ud early if it's a singleton, so that we can use it in the range checks
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, method->name);
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, method->name);
// emit comments on expected arg/type
struct argument *arg = method->arguments;
@ -1174,11 +1310,18 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
switch (data->ud_type) {
case UD_USERDATA:
// extract the userdata
fprintf(source, " %s * ud = check_%s(L, 1);\n", data->name, data->name);
fprintf(source, " %s * ud = check_%s(L, 1);\n", data->name, data->sanatized_name);
break;
case UD_SINGLETON:
// this was bound early
break;
case UD_AP_OBJECT:
// extract the userdata, it was a pointer, so we need to grab it
fprintf(source, " %s * ud = *check_%s(L, 1);\n", data->name, data->sanatized_name);
fprintf(source, " if (ud == NULL) {\n");
fprintf(source, " luaL_error(L, \"Internal error, null pointer\");\n");
fprintf(source, " }\n");
break;
}
// extract the arguments
@ -1191,7 +1334,8 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
emit_checker(arg->type, arg_count, skipped, " ", "argument");
arg_count++;
}
if (arg->type.type == TYPE_LITERAL || arg->type.flags & TYPE_FLAGS_NULLABLE) {
if (//arg->type.type == TYPE_LITERAL ||
arg->type.flags & TYPE_FLAGS_NULLABLE) {
skipped++;
}
arg = arg->next;
@ -1212,7 +1356,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
fprintf(source, " const int8_t data = ud->%s(", method->name);
break;
case TYPE_INT16_T:
fprintf(source, " const int6_t data = ud->%s(", method->name);
fprintf(source, " const int16_t data = ud->%s(", method->name);
break;
case TYPE_INT32_T:
fprintf(source, " const int32_t data = ud->%s(", method->name);
@ -1233,7 +1377,10 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
fprintf(source, " const %s &data = ud->%s(", method->return_type.data.enum_name, method->name);
break;
case TYPE_USERDATA:
fprintf(source, " const %s &data = ud->%s(", method->return_type.data.userdata_name, method->name);
fprintf(source, " const %s &data = ud->%s(", method->return_type.data.ud.name, method->name);
break;
case TYPE_AP_OBJECT:
fprintf(source, " %s *data = ud->%s(", method->return_type.data.ud.name, method->name);
break;
case TYPE_NONE:
fprintf(source, " ud->%s(", method->name);
@ -1262,6 +1409,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
case TYPE_UINT32_T:
case TYPE_ENUM:
case TYPE_USERDATA:
case TYPE_AP_OBJECT:
fprintf(source, " data_%d", arg_count + ((arg->type.flags & TYPE_FLAGS_NULLABLE) ? NULLABLE_ARG_COUNT_BASE : 0));
break;
case TYPE_LITERAL:
@ -1321,8 +1469,8 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
break;
case TYPE_USERDATA:
// userdatas must allocate a new container to return
fprintf(source, " new_%s(L);\n", arg->type.data.userdata_name);
fprintf(source, " *check_%s(L, -1) = data_%d;\n", arg->type.data.userdata_name, arg_index);
fprintf(source, " new_%s(L);\n", arg->type.data.ud.sanatized_name);
fprintf(source, " *check_%s(L, -1) = data_%d;\n", arg->type.data.ud.sanatized_name, arg_index);
break;
case TYPE_NONE:
error(ERROR_INTERNAL, "Attempted to emit a nullable argument of type none");
@ -1330,6 +1478,9 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
case TYPE_LITERAL:
error(ERROR_INTERNAL, "Attempted to make a nullable literal");
break;
case TYPE_AP_OBJECT: // FIXME: collapse these to a single failure case
error(ERROR_INTERNAL, "Attempted to make a nullable ap_object");
break;
}
}
@ -1363,8 +1514,16 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
break;
case TYPE_USERDATA:
// userdatas must allocate a new container to return
fprintf(source, " new_%s(L);\n", method->return_type.data.userdata_name);
fprintf(source, " *check_%s(L, -1) = data;\n", method->return_type.data.userdata_name);
fprintf(source, " new_%s(L);\n", method->return_type.data.ud.sanatized_name);
fprintf(source, " *check_%s(L, -1) = data;\n", method->return_type.data.ud.sanatized_name);
break;
case TYPE_AP_OBJECT:
fprintf(source, " if (data == NULL) {\n");
fprintf(source, " lua_pushnil(L);\n");
fprintf(source, " } else {\n");
fprintf(source, " new_%s(L);\n", method->return_type.data.ud.sanatized_name);
fprintf(source, " *check_%s(L, -1) = data;\n", method->return_type.data.ud.sanatized_name);
fprintf(source, " }\n");
break;
case TYPE_NONE:
case TYPE_LITERAL:
@ -1425,15 +1584,15 @@ void emit_operators(struct userdata *data) {
return;
}
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, op_name);
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, op_name);
// check number of arguments
fprintf(source, " binding_argcheck(L, 2);\n");
// check the pointers
fprintf(source, " %s *ud = check_%s(L, 1);\n", data->name, data->name);
fprintf(source, " %s *ud2 = check_%s(L, 2);\n", data->name, data->name);
fprintf(source, " %s *ud = check_%s(L, 1);\n", data->name, data->sanatized_name);
fprintf(source, " %s *ud2 = check_%s(L, 2);\n", data->name, data->sanatized_name);
// create a container for the result
fprintf(source, " new_%s(L);\n", data->name);
fprintf(source, " *check_%s(L, -1) = *ud %c *ud2;;\n", data->name, op_sym);
fprintf(source, " new_%s(L);\n", data->sanatized_name);
fprintf(source, " *check_%s(L, -1) = *ud %c *ud2;;\n", data->sanatized_name, op_sym);
// return the first pointer
fprintf(source, " return 1;\n");
fprintf(source, "}\n\n");
@ -1461,17 +1620,17 @@ void emit_userdata_methods(struct userdata *node) {
void emit_userdata_metatables(void) {
struct userdata * node = parsed_userdata;
while(node) {
fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->name);
fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->sanatized_name);
struct userdata_field *field = node->fields;
while(field) {
fprintf(source, " {\"%s\", %s_%s},\n", field->name, node->name, field->name);
fprintf(source, " {\"%s\", %s_%s},\n", field->name, node->sanatized_name, field->name);
field = field->next;
}
struct method *method = node->methods;
while(method) {
fprintf(source, " {\"%s\", %s_%s},\n", method->name, node->name, method->name);
fprintf(source, " {\"%s\", %s_%s},\n", method->name, node->sanatized_name, method->name);
method = method->next;
}
@ -1480,7 +1639,7 @@ void emit_userdata_metatables(void) {
if (op_name == NULL) {
continue;
}
fprintf(source, " {\"%s\", %s_%s},\n", op_name, node->name, op_name);
fprintf(source, " {\"%s\", %s_%s},\n", op_name, node->sanatized_name, op_name);
}
fprintf(source, " {NULL, NULL}\n");
@ -1490,14 +1649,14 @@ void emit_userdata_metatables(void) {
}
}
void emit_singleton_metatables(void) {
struct userdata * node = parsed_singletons;
void emit_singleton_metatables(struct userdata *head) {
struct userdata * node = head;
while(node) {
fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->name);
fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->sanatized_name);
struct method *method = node->methods;
while (method) {
fprintf(source, " {\"%s\", %s_%s},\n", method->name, node->name, method->name);
fprintf(source, " {\"%s\", %s_%s},\n", method->name, node->sanatized_name, method->name);
method = method->next;
}
@ -1511,7 +1670,7 @@ void emit_singleton_metatables(void) {
void emit_enums(struct userdata * data) {
while (data) {
if (data->enums != NULL) {
fprintf(source, "struct userdata_enum %s_enums[] = {\n", data->name);
fprintf(source, "struct userdata_enum %s_enums[] = {\n", data->sanatized_name);
struct userdata_enum *ud_enum = data->enums;
while (ud_enum != NULL) {
fprintf(source, " {\"%s\", %s::%s},\n", ud_enum->name, data->name, ud_enum->name);
@ -1527,9 +1686,9 @@ void emit_metas(struct userdata * data, char * meta_name) {
fprintf(source, "const struct userdata_meta %s_fun[] = {\n", meta_name);
while (data) {
if (data->enums) {
fprintf(source, " {\"%s\", %s_meta, %s_enums},\n", data->alias ? data->alias : data->name, data->name, data->name);
fprintf(source, " {\"%s\", %s_meta, %s_enums},\n", data->alias ? data->alias : data->name, data->name, data->sanatized_name);
} else {
fprintf(source, " {\"%s\", %s_meta, NULL},\n", data->alias ? data->alias : data->name, data->name);
fprintf(source, " {\"%s\", %s_meta, NULL},\n", data->alias ? data->alias : data->name, data->sanatized_name);
}
data = data->next;
}
@ -1553,6 +1712,7 @@ void emit_loaders(void) {
fprintf(source, "};\n\n");
emit_metas(parsed_userdata, "userdata");
emit_metas(parsed_singletons, "singleton");
emit_metas(parsed_ap_objects, "ap_object");
fprintf(source, "void load_generated_bindings(lua_State *L) {\n");
fprintf(source, " luaL_checkstack(L, 5, \"Out of stack\");\n"); // this is more stack space then we need, but should never fail
@ -1567,6 +1727,17 @@ void emit_loaders(void) {
fprintf(source, " }\n");
fprintf(source, "\n");
fprintf(source, " // ap object metatables\n");
fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(ap_object_fun); i++) {\n");
fprintf(source, " luaL_newmetatable(L, ap_object_fun[i].name);\n");
fprintf(source, " luaL_setfuncs(L, ap_object_fun[i].reg, 0);\n");
fprintf(source, " lua_pushstring(L, \"__index\");\n");
fprintf(source, " lua_pushvalue(L, -2);\n");
fprintf(source, " lua_settable(L, -3);\n");
fprintf(source, " lua_pop(L, 1);\n");
fprintf(source, " }\n");
fprintf(source, "\n");
fprintf(source, " // singleton metatables\n");
fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(singleton_fun); i++) {\n");
fprintf(source, " luaL_newmetatable(L, singleton_fun[i].name);\n");
@ -1602,7 +1773,7 @@ void emit_sandbox(void) {
struct userdata *single = parsed_singletons;
fprintf(source, "const char *singletons[] = {\n");
while (single) {
fprintf(source, " \"%s\",\n", single->alias ? single->alias : single->name);
fprintf(source, " \"%s\",\n", single->alias ? single->alias : single->sanatized_name);
single = single->next;
}
fprintf(source, "};\n\n");
@ -1613,7 +1784,12 @@ void emit_sandbox(void) {
fprintf(source, " const lua_CFunction fun;\n");
fprintf(source, "} new_userdata[] = {\n");
while (data) {
fprintf(source, " {\"%s\", new_%s},\n", data->name, data->name);
fprintf(source, " {\"%s\", new_%s},\n", data->name, data->sanatized_name);
data = data->next;
}
data = parsed_ap_objects;
while (data) {
fprintf(source, " {\"%s\", new_%s},\n", data->name, data->sanatized_name);
data = data->next;
}
fprintf(source, "};\n\n");
@ -1703,6 +1879,8 @@ int main(int argc, char **argv) {
handle_userdata();
} else if (strcmp (state.token, keyword_singleton) == 0){
handle_singleton();
} else if (strcmp (state.token, keyword_ap_object) == 0){
handle_ap_object();
} else if (strcmp (state.token, keyword_depends) == 0){
handle_depends();
} else {
@ -1749,6 +1927,10 @@ int main(int argc, char **argv) {
emit_userdata_checkers();
emit_ap_object_allocators();
emit_ap_object_checkers();
emit_userdata_fields();
emit_userdata_methods(parsed_userdata);
@ -1757,7 +1939,11 @@ int main(int argc, char **argv) {
emit_userdata_methods(parsed_singletons);
emit_singleton_metatables();
emit_singleton_metatables(parsed_singletons);
emit_userdata_methods(parsed_ap_objects);
emit_singleton_metatables(parsed_ap_objects);
emit_loaders();
@ -1781,6 +1967,7 @@ int main(int argc, char **argv) {
fprintf(header, "\n\n");
emit_userdata_declarations();
emit_ap_object_declarations();
fprintf(header, "void load_generated_bindings(lua_State *L);\n");
fprintf(header, "void load_generated_sandbox(lua_State *L);\n");

View File

@ -4,7 +4,7 @@
extern const AP_HAL::HAL& hal;
static uint32_t coerce_to_uint32_t(lua_State *L, int arg) {
uint32_t coerce_to_uint32_t(lua_State *L, int arg) {
{ // userdata
const uint32_t * ud = static_cast<uint32_t *>(luaL_testudata(L, arg, "uint32_t"));
if (ud != nullptr) {

View File

@ -4,6 +4,7 @@
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);
void load_boxed_numerics(lua_State *L);
void load_boxed_numerics_sandbox(lua_State *L);

View File

@ -1,6 +1,7 @@
// auto generated bindings, don't manually edit. See README.md for details.
#include "lua_generated_bindings.h"
#include "lua_boxed_numerics.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_SerialLED/AP_SerialLED.h>
@ -79,6 +80,20 @@ Location * check_Location(lua_State *L, int arg) {
return (Location *)data;
}
int new_AP_HAL__UARTDriver(lua_State *L) {
luaL_checkstack(L, 2, "Out of stack");
void *ud = lua_newuserdata(L, sizeof(AP_HAL::UARTDriver *));
memset(ud, 0, sizeof(AP_HAL::UARTDriver *));
luaL_getmetatable(L, "AP_HAL::UARTDriver");
lua_setmetatable(L, -2);
return 1;
}
AP_HAL::UARTDriver ** check_AP_HAL__UARTDriver(lua_State *L, int arg) {
void *data = luaL_checkudata(L, arg, "AP_HAL::UARTDriver");
return (AP_HAL::UARTDriver **)data;
}
static int Vector2f_y(lua_State *L) {
Vector2f *ud = check_Vector2f(L, 1);
switch(lua_gettop(L)) {
@ -514,6 +529,29 @@ const luaL_Reg Location_meta[] = {
{NULL, NULL}
};
static int AP_SerialManager_find_serial(lua_State *L) {
AP_SerialManager * ud = AP_SerialManager::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "serial not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(UINT8_MAX, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
AP_HAL::UARTDriver *data = ud->find_serial(
AP_SerialManager::SerialProtocol_Scripting,
data_2);
if (data == NULL) {
lua_pushnil(L);
} else {
new_AP_HAL__UARTDriver(L);
*check_AP_HAL__UARTDriver(L, -1) = data;
}
return 1;
}
static int RC_Channels_get_pwm(lua_State *L) {
RC_Channels * ud = RC_Channels::get_singleton();
if (ud == nullptr) {
@ -582,7 +620,7 @@ static int AP_SerialLED_set_RGB(lua_State *L) {
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t raw_data_3 = *check_uint32_t(L, 3);
const uint32_t raw_data_3 = coerce_to_uint32_t(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0U, 0U)) && (raw_data_3 <= MIN(UINT32_MAX, UINT32_MAX))), 3, "argument out of range");
const uint32_t data_3 = static_cast<uint32_t>(raw_data_3);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 4);
@ -666,7 +704,7 @@ static int GCS_set_message_interval(lua_State *L) {
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(MAVLINK_COMM_NUM_BUFFERS, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t raw_data_3 = *check_uint32_t(L, 3);
const uint32_t raw_data_3 = coerce_to_uint32_t(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0U, 0U)) && (raw_data_3 <= MIN(UINT32_MAX, UINT32_MAX))), 3, "argument out of range");
const uint32_t data_3 = static_cast<uint32_t>(raw_data_3);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 4);
@ -1777,6 +1815,11 @@ static int AP_AHRS_get_roll(lua_State *L) {
return 1;
}
const luaL_Reg AP_SerialManager_meta[] = {
{"find_serial", AP_SerialManager_find_serial},
{NULL, NULL}
};
const luaL_Reg RC_Channels_meta[] = {
{"get_pwm", RC_Channels_get_pwm},
{NULL, NULL}
@ -1899,6 +1942,87 @@ const luaL_Reg AP_AHRS_meta[] = {
{NULL, NULL}
};
static int AP_HAL__UARTDriver_set_flow_control(lua_State *L) {
binding_argcheck(L, 2);
AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1);
if (ud == NULL) {
luaL_error(L, "Internal error, null pointer");
}
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= static_cast<int32_t>(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE)) && (raw_data_2 <= static_cast<int32_t>(AP_HAL::UARTDriver::FLOW_CONTROL_AUTO))), 2, "argument out of range");
const AP_HAL::UARTDriver::flow_control data_2 = static_cast<AP_HAL::UARTDriver::flow_control>(raw_data_2);
ud->set_flow_control(
data_2);
return 0;
}
static int AP_HAL__UARTDriver_available(lua_State *L) {
binding_argcheck(L, 1);
AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1);
if (ud == NULL) {
luaL_error(L, "Internal error, null pointer");
}
const uint32_t data = ud->available();
new_uint32_t(L);
*static_cast<uint32_t *>(luaL_checkudata(L, -1, "uint32_t")) = data;
return 1;
}
static int AP_HAL__UARTDriver_write(lua_State *L) {
binding_argcheck(L, 2);
AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1);
if (ud == NULL) {
luaL_error(L, "Internal error, null pointer");
}
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(UINT8_MAX, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t data = ud->write(
data_2);
new_uint32_t(L);
*static_cast<uint32_t *>(luaL_checkudata(L, -1, "uint32_t")) = data;
return 1;
}
static int AP_HAL__UARTDriver_read(lua_State *L) {
binding_argcheck(L, 1);
AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1);
if (ud == NULL) {
luaL_error(L, "Internal error, null pointer");
}
const int16_t data = ud->read();
lua_pushinteger(L, data);
return 1;
}
static int AP_HAL__UARTDriver_begin(lua_State *L) {
binding_argcheck(L, 2);
AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1);
if (ud == NULL) {
luaL_error(L, "Internal error, null pointer");
}
const uint32_t raw_data_2 = coerce_to_uint32_t(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(1U, 0U)) && (raw_data_2 <= MIN(UINT32_MAX, UINT32_MAX))), 2, "argument out of range");
const uint32_t data_2 = static_cast<uint32_t>(raw_data_2);
ud->begin(
data_2);
return 0;
}
const luaL_Reg AP_HAL__UARTDriver_meta[] = {
{"set_flow_control", AP_HAL__UARTDriver_set_flow_control},
{"available", AP_HAL__UARTDriver_available},
{"write", AP_HAL__UARTDriver_write},
{"read", AP_HAL__UARTDriver_read},
{"begin", AP_HAL__UARTDriver_begin},
{NULL, NULL}
};
struct userdata_enum {
const char *name;
int value;
@ -1933,6 +2057,7 @@ const struct userdata_meta userdata_fun[] = {
};
const struct userdata_meta singleton_fun[] = {
{"serial", AP_SerialManager_meta, NULL},
{"rc", RC_Channels_meta, NULL},
{"SRV_Channels", SRV_Channels_meta, NULL},
{"serialLED", AP_SerialLED_meta, NULL},
@ -1948,6 +2073,10 @@ const struct userdata_meta singleton_fun[] = {
{"ahrs", AP_AHRS_meta, NULL},
};
const struct userdata_meta ap_object_fun[] = {
{"AP_HAL::UARTDriver", AP_HAL__UARTDriver_meta, NULL},
};
void load_generated_bindings(lua_State *L) {
luaL_checkstack(L, 5, "Out of stack");
// userdata metatables
@ -1960,6 +2089,16 @@ void load_generated_bindings(lua_State *L) {
lua_pop(L, 1);
}
// ap object metatables
for (uint32_t i = 0; i < ARRAY_SIZE(ap_object_fun); i++) {
luaL_newmetatable(L, ap_object_fun[i].name);
luaL_setfuncs(L, ap_object_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);
@ -1987,6 +2126,7 @@ void load_generated_bindings(lua_State *L) {
}
const char *singletons[] = {
"serial",
"rc",
"SRV_Channels",
"serialLED",
@ -2009,6 +2149,7 @@ const struct userdata {
{"Vector2f", new_Vector2f},
{"Vector3f", new_Vector3f},
{"Location", new_Location},
{"AP_HAL::UARTDriver", new_AP_HAL__UARTDriver},
};
void load_generated_sandbox(lua_State *L) {

View File

@ -1,5 +1,6 @@
#pragma once
// auto generated bindings, don't manually edit. See README.md for details.
#include <AP_SerialManager/AP_SerialManager.h>
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_SerialLED/AP_SerialLED.h>
@ -30,5 +31,7 @@ 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);
int new_AP_HAL__UARTDriver(lua_State *L);
AP_HAL::UARTDriver ** check_AP_HAL__UARTDriver(lua_State *L, int arg);
void load_generated_bindings(lua_State *L);
void load_generated_sandbox(lua_State *L);