AP_Scripting: Add support for enums to be passed through

This commit is contained in:
Michael du Breuil 2019-07-16 21:27:25 -07:00 committed by Randy Mackay
parent 6e7367b86f
commit 0054544bd3
5 changed files with 121 additions and 33 deletions

View File

@ -25,7 +25,7 @@
#define SCRIPTING_STACK_MIN_SIZE (8 * 1024) #define SCRIPTING_STACK_MIN_SIZE (8 * 1024)
#if !defined(SCRIPTING_STACK_SIZE) #if !defined(SCRIPTING_STACK_SIZE)
#define SCRIPTING_STACK_SIZE (16 * 1024) #define SCRIPTING_STACK_SIZE (17 * 1024) // Linux experiences stack corruption at ~16.25KB when handed bad scripts
#endif // !defined(SCRIPTING_STACK_SIZE) #endif // !defined(SCRIPTING_STACK_SIZE)
#if !defined(SCRIPTING_STACK_MAX_SIZE) #if !defined(SCRIPTING_STACK_MAX_SIZE)

View File

@ -50,6 +50,7 @@ singleton AP_BattMonitor method get_temperature boolean float'Null uint8_t 0 ud-
include AP_GPS/AP_GPS.h include AP_GPS/AP_GPS.h
singleton AP_GPS alias gps singleton AP_GPS alias gps
singleton AP_GPS enum NO_GPS NO_FIX GPS_OK_FIX_2D GPS_OK_FIX_3D GPS_OK_FIX_3D_DGPS GPS_OK_FIX_3D_RTK_FLOAT GPS_OK_FIX_3D_RTK_FIXED
singleton AP_GPS method num_sensors uint8_t singleton AP_GPS method num_sensors uint8_t
singleton AP_GPS method primary_sensor uint8_t singleton AP_GPS method primary_sensor uint8_t
singleton AP_GPS method status uint8_t uint8_t 0 ud->num_sensors() singleton AP_GPS method status uint8_t uint8_t 0 ud->num_sensors()

View File

@ -9,6 +9,7 @@
char keyword_alias[] = "alias"; char keyword_alias[] = "alias";
char keyword_comment[] = "--"; char keyword_comment[] = "--";
char keyword_enum[] = "enum";
char keyword_field[] = "field"; char keyword_field[] = "field";
char keyword_include[] = "include"; char keyword_include[] = "include";
char keyword_method[] = "method"; char keyword_method[] = "method";
@ -287,12 +288,18 @@ enum userdata_flags {
UD_FLAG_SEMAPHORE = (1U << 0), UD_FLAG_SEMAPHORE = (1U << 0),
}; };
struct userdata_enum {
struct userdata_enum * next;
char * name; // enum name
};
struct userdata { struct userdata {
struct userdata * next; struct userdata * next;
char *name; // name of the C++ singleton char *name; // name of the C++ singleton
char *alias; // (optional) used for scripting access char *alias; // (optional) used for scripting access
struct userdata_field *fields; struct userdata_field *fields;
struct method *methods; struct method *methods;
struct userdata_enum *enums;
enum userdata_type ud_type; enum userdata_type ud_type;
uint32_t operations; // bitset of enum operation_types uint32_t operations; // bitset of enum operation_types
int flags; // flags from the userdata_flags enum int flags; // flags from the userdata_flags enum
@ -498,6 +505,19 @@ int parse_type(struct type *type, const uint32_t restrictions, enum range_check_
return TRUE; return TRUE;
} }
void handle_userdata_enum(struct userdata *data) {
trace(TRACE_USERDATA, "Adding a userdata enum");
char * enum_name;
while ((enum_name = next_token()) != NULL) {
trace(TRACE_USERDATA, "Adding enum %s", enum_name);
struct userdata_enum *ud_enum = (struct userdata_enum *) allocate(sizeof(struct userdata_enum));
ud_enum->next = data->enums;
string_copy(&(ud_enum->name), enum_name);
data->enums = ud_enum;
}
}
void handle_userdata_field(struct userdata *data) { void handle_userdata_field(struct userdata *data) {
trace(TRACE_USERDATA, "Adding a userdata field"); trace(TRACE_USERDATA, "Adding a userdata field");
@ -658,6 +678,8 @@ void handle_userdata(void) {
handle_operator(node); handle_operator(node);
} else if (strcmp(type, keyword_method) == 0) { } else if (strcmp(type, keyword_method) == 0) {
handle_method(node->name, &(node->methods)); handle_method(node->name, &(node->methods));
} else if (strcmp(type, keyword_enum) == 0) {
handle_userdata_enum(node);
} else { } else {
error(ERROR_USERDATA, "Unknown or unsupported type for userdata: %s", type); error(ERROR_USERDATA, "Unknown or unsupported type for userdata: %s", type);
} }
@ -710,6 +732,8 @@ void handle_singleton(void) {
node->flags |= UD_FLAG_SEMAPHORE; node->flags |= UD_FLAG_SEMAPHORE;
} else if (strcmp(type, keyword_method) == 0) { } else if (strcmp(type, keyword_method) == 0) {
handle_method(node->name, &(node->methods)); handle_method(node->name, &(node->methods));
} else if (strcmp(type, keyword_enum) == 0) {
handle_userdata_enum(node);
} else { } else {
error(ERROR_SINGLETON, "Singletons only support aliases, methods or semaphore keyowrds (got %s)", type); error(ERROR_SINGLETON, "Singletons only support aliases, methods or semaphore keyowrds (got %s)", type);
} }
@ -1336,7 +1360,7 @@ void emit_singleton_metatables(void) {
fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->name); fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->name);
struct method *method = node->methods; struct method *method = node->methods;
while(method) { while (method) {
fprintf(source, " {\"%s\", %s_%s},\n", method->name, node->name, method->name); fprintf(source, " {\"%s\", %s_%s},\n", method->name, node->name, method->name);
method = method->next; method = method->next;
} }
@ -1348,28 +1372,51 @@ void emit_singleton_metatables(void) {
} }
} }
void emit_loaders(void) { void emit_enums(struct userdata * data) {
fprintf(source, "const struct userdata_fun {\n");
fprintf(source, " const char *name;\n");
fprintf(source, " const luaL_Reg *reg;\n");
fprintf(source, "} userdata_fun[] = {\n");
struct userdata * data = parsed_userdata;
while (data) { while (data) {
fprintf(source, " {\"%s\", %s_meta},\n", data->name, data->name); if (data->enums != NULL) {
fprintf(source, "struct userdata_enum %s_enums[] = {\n", data->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);
ud_enum = ud_enum->next;
}
fprintf(source, " {NULL, 0}};\n\n");
}
data = data->next;
}
}
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);
} else {
fprintf(source, " {\"%s\", %s_meta, NULL},\n", data->alias ? data->alias : data->name, data->name);
}
data = data->next; data = data->next;
} }
fprintf(source, "};\n\n"); fprintf(source, "};\n\n");
}
fprintf(source, "const struct singleton_fun {\n"); void emit_loaders(void) {
// emit the enum header
fprintf(source, "struct userdata_enum {\n");
fprintf(source, " const char *name;\n");
fprintf(source, " int value;\n");
fprintf(source, "};\n\n");
emit_enums(parsed_userdata);
emit_enums(parsed_singletons);
// emit the meta table header
fprintf(source, "struct userdata_meta {\n");
fprintf(source, " const char *name;\n"); fprintf(source, " const char *name;\n");
fprintf(source, " const luaL_Reg *reg;\n"); fprintf(source, " const luaL_Reg *reg;\n");
fprintf(source, "} singleton_fun[] = {\n"); fprintf(source, " const struct userdata_enum *enums;\n");
struct userdata * single = parsed_singletons;
while (single) {
fprintf(source, " {\"%s\", %s_meta},\n", single->alias ? single->alias : single->name, single->name);
single = single->next;
}
fprintf(source, "};\n\n"); fprintf(source, "};\n\n");
emit_metas(parsed_userdata, "userdata");
emit_metas(parsed_singletons, "singleton");
fprintf(source, "void load_generated_bindings(lua_State *L) {\n"); 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 fprintf(source, " luaL_checkstack(L, 5, \"Out of stack\");\n"); // this is more stack space then we need, but should never fail
@ -1391,6 +1438,17 @@ void emit_loaders(void) {
fprintf(source, " lua_pushstring(L, \"__index\");\n"); fprintf(source, " lua_pushstring(L, \"__index\");\n");
fprintf(source, " lua_pushvalue(L, -2);\n"); fprintf(source, " lua_pushvalue(L, -2);\n");
fprintf(source, " lua_settable(L, -3);\n"); fprintf(source, " lua_settable(L, -3);\n");
fprintf(source, " if (singleton_fun[i].enums != nullptr) {\n");
fprintf(source, " int j = 0;\n");
fprintf(source, " while (singleton_fun[i].enums[j].name != NULL) {\n");
fprintf(source, " lua_pushstring(L, singleton_fun[i].enums[j].name);\n");
fprintf(source, " lua_pushinteger(L, singleton_fun[i].enums[j].value);\n");
fprintf(source, " lua_settable(L, -3);\n");
fprintf(source, " j++;\n");
fprintf(source, " }\n");
fprintf(source, " }\n");
fprintf(source, " lua_pop(L, 1);\n"); fprintf(source, " lua_pop(L, 1);\n");
fprintf(source, " lua_newuserdata(L, 0);\n"); fprintf(source, " lua_newuserdata(L, 0);\n");
fprintf(source, " luaL_getmetatable(L, singleton_fun[i].name);\n"); fprintf(source, " luaL_getmetatable(L, singleton_fun[i].name);\n");

View File

@ -1619,28 +1619,43 @@ const luaL_Reg AP_AHRS_meta[] = {
{NULL, NULL} {NULL, NULL}
}; };
const struct userdata_fun { struct userdata_enum {
const char *name; const char *name;
const luaL_Reg *reg; int value;
} userdata_fun[] = {
{"Vector2f", Vector2f_meta},
{"Vector3f", Vector3f_meta},
{"Location", Location_meta},
}; };
const struct singleton_fun { struct userdata_enum AP_GPS_enums[] = {
{"GPS_OK_FIX_3D_RTK_FIXED", AP_GPS::GPS_OK_FIX_3D_RTK_FIXED},
{"GPS_OK_FIX_3D_RTK_FLOAT", AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT},
{"GPS_OK_FIX_3D_DGPS", AP_GPS::GPS_OK_FIX_3D_DGPS},
{"GPS_OK_FIX_3D", AP_GPS::GPS_OK_FIX_3D},
{"GPS_OK_FIX_2D", AP_GPS::GPS_OK_FIX_2D},
{"NO_FIX", AP_GPS::NO_FIX},
{"NO_GPS", AP_GPS::NO_GPS},
{NULL, 0}};
struct userdata_meta {
const char *name; const char *name;
const luaL_Reg *reg; const luaL_Reg *reg;
} singleton_fun[] = { const struct userdata_enum *enums;
{"gcs", GCS_meta}, };
{"relay", AP_Relay_meta},
{"terrain", AP_Terrain_meta}, const struct userdata_meta userdata_fun[] = {
{"rangefinder", RangeFinder_meta}, {"Vector2f", Vector2f_meta, NULL},
{"AP_Notify", AP_Notify_meta}, {"Vector3f", Vector3f_meta, NULL},
{"notify", notify_meta}, {"Location", Location_meta, NULL},
{"gps", AP_GPS_meta}, };
{"battery", AP_BattMonitor_meta},
{"ahrs", AP_AHRS_meta}, const struct userdata_meta singleton_fun[] = {
{"gcs", GCS_meta, NULL},
{"relay", AP_Relay_meta, NULL},
{"terrain", AP_Terrain_meta, NULL},
{"rangefinder", RangeFinder_meta, NULL},
{"AP_Notify", AP_Notify_meta, NULL},
{"notify", notify_meta, NULL},
{"gps", AP_GPS_meta, AP_GPS_enums},
{"battery", AP_BattMonitor_meta, NULL},
{"ahrs", AP_AHRS_meta, NULL},
}; };
void load_generated_bindings(lua_State *L) { void load_generated_bindings(lua_State *L) {
@ -1662,6 +1677,15 @@ void load_generated_bindings(lua_State *L) {
lua_pushstring(L, "__index"); lua_pushstring(L, "__index");
lua_pushvalue(L, -2); lua_pushvalue(L, -2);
lua_settable(L, -3); lua_settable(L, -3);
if (singleton_fun[i].enums != nullptr) {
int j = 0;
while (singleton_fun[i].enums[j].name != NULL) {
lua_pushstring(L, singleton_fun[i].enums[j].name);
lua_pushinteger(L, singleton_fun[i].enums[j].value);
lua_settable(L, -3);
j++;
}
}
lua_pop(L, 1); lua_pop(L, 1);
lua_newuserdata(L, 0); lua_newuserdata(L, 0);
luaL_getmetatable(L, singleton_fun[i].name); luaL_getmetatable(L, singleton_fun[i].name);

View File

@ -69,16 +69,21 @@ lua_scripts::script_info *lua_scripts::load_script(lua_State *L, char *filename)
switch (error) { switch (error) {
case LUA_ERRSYNTAX: case LUA_ERRSYNTAX:
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Syntax error in %s", filename); gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Syntax error in %s", filename);
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Error: %s", lua_tostring(L, -1));
lua_pop(L, lua_gettop(L));
return nullptr; return nullptr;
case LUA_ERRMEM: case LUA_ERRMEM:
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Insufficent memory loading %s", filename); gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Insufficent memory loading %s", filename);
lua_pop(L, lua_gettop(L));
return nullptr; return nullptr;
case LUA_ERRFILE: case LUA_ERRFILE:
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Unable to load the file: %s", lua_tostring(L, -1)); gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Unable to load the file: %s", lua_tostring(L, -1));
hal.console->printf("Lua: File error: %s\n", lua_tostring(L, -1)); hal.console->printf("Lua: File error: %s\n", lua_tostring(L, -1));
lua_pop(L, lua_gettop(L));
return nullptr; return nullptr;
default: default:
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Unknown error (%d) loading %s", error, filename); gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Unknown error (%d) loading %s", error, filename);
lua_pop(L, lua_gettop(L));
return nullptr; return nullptr;
} }
} }