mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Scripting: support singleton feild types
This commit is contained in:
parent
9ccf17488d
commit
18d0687847
@ -929,6 +929,8 @@ void handle_singleton(void) {
|
||||
string_copy(&(node->dependency), depends);
|
||||
} else if (strcmp(type, keyword_literal) == 0) {
|
||||
node->flags |= UD_FLAG_LITERAL;
|
||||
} else if (strcmp(type, keyword_field) == 0) {
|
||||
handle_userdata_field(node);
|
||||
} else if (strcmp(type, keyword_reference) == 0) {
|
||||
node->flags |= UD_FLAG_REFERENCE;
|
||||
} else {
|
||||
@ -1448,6 +1450,104 @@ void emit_userdata_fields() {
|
||||
}
|
||||
}
|
||||
|
||||
void emit_singleton_field(const struct userdata *data, const struct userdata_field *field) {
|
||||
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, field->name);
|
||||
|
||||
// emit comments on expected arg/type
|
||||
if (!(data->flags & UD_FLAG_LITERAL)) {
|
||||
// fetch and check the singleton pointer
|
||||
fprintf(source, " %s * ud = %s::get_singleton();\n", data->name, data->name);
|
||||
fprintf(source, " if (ud == nullptr) {\n");
|
||||
fprintf(source, " return not_supported_error(L, %d, \"%s\");\n", 1, data->alias ? data->alias : data->name);
|
||||
fprintf(source, " }\n\n");
|
||||
}
|
||||
const char *ud_name = (data->flags & UD_FLAG_LITERAL)?data->name:"ud";
|
||||
const char *ud_access = (data->flags & UD_FLAG_REFERENCE)?".":"->";
|
||||
|
||||
char *index_string = "";
|
||||
int write_arg_number = 2;
|
||||
if (field->array_len != NULL) {
|
||||
index_string = "[index]";
|
||||
write_arg_number = 3;
|
||||
|
||||
fprintf(source, "\n const lua_Integer raw_index = luaL_checkinteger(L, 2);\n");
|
||||
fprintf(source, " luaL_argcheck(L, ((raw_index >= 0) && (raw_index < MIN(%s, UINT8_MAX))), 2, \"index out of range\");\n",field->array_len);
|
||||
fprintf(source, " const uint8_t index = static_cast<uint8_t>(raw_index);\n\n");
|
||||
|
||||
fprintf(source, " switch(lua_gettop(L)-1) {\n");
|
||||
|
||||
} else {
|
||||
fprintf(source, " switch(lua_gettop(L)) {\n");
|
||||
}
|
||||
|
||||
if (field->access_flags & ACCESS_FLAG_READ) {
|
||||
fprintf(source, " case 1:\n");
|
||||
switch (field->type.type) {
|
||||
case TYPE_BOOLEAN:
|
||||
fprintf(source, " lua_pushinteger(L, %s%s%s%s);\n", ud_name, ud_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, " lua_pushnumber(L, %s%s%s%s);\n", ud_name, ud_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
case TYPE_INT16_T:
|
||||
case TYPE_INT32_T:
|
||||
case TYPE_UINT8_T:
|
||||
case TYPE_UINT16_T:
|
||||
case TYPE_ENUM:
|
||||
fprintf(source, " lua_pushinteger(L, %s%s%s%s);\n", ud_name, ud_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_UINT32_T:
|
||||
fprintf(source, " new_uint32_t(L);\n");
|
||||
fprintf(source, " *static_cast<uint32_t *>(luaL_checkudata(L, -1, \"uint32_t\")) = %s%s%s%s;\n", ud_name, ud_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
error(ERROR_INTERNAL, "Can't access a NONE field");
|
||||
break;
|
||||
case TYPE_LITERAL:
|
||||
error(ERROR_INTERNAL, "Can't access a literal field");
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
fprintf(source, " lua_pushstring(L, %s%s%s%s);\n", ud_name, ud_access, field->name, index_string);
|
||||
break;
|
||||
case TYPE_USERDATA:
|
||||
error(ERROR_USERDATA, "Userdata does not currently support access 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 access to userdata field's");
|
||||
break;
|
||||
}
|
||||
fprintf(source, " return 1;\n");
|
||||
}
|
||||
|
||||
if (field->access_flags & ACCESS_FLAG_WRITE) {
|
||||
fprintf(source, " case 2: {\n");
|
||||
emit_checker(field->type, write_arg_number, 0, " ", field->name);
|
||||
fprintf(source, " %s%s%s%s = data_%i;\n", ud_name, ud_access, field->name, index_string, write_arg_number);
|
||||
fprintf(source, " return 0;\n");
|
||||
fprintf(source, " }\n");
|
||||
}
|
||||
|
||||
fprintf(source, " default:\n");
|
||||
fprintf(source, " return luaL_argerror(L, lua_gettop(L), \"too many arguments\");\n");
|
||||
fprintf(source, " }\n");
|
||||
fprintf(source, "}\n\n");
|
||||
}
|
||||
|
||||
void emit_singleton_fields() {
|
||||
struct userdata * node = parsed_singletons;
|
||||
while(node) {
|
||||
struct userdata_field *field = node->fields;
|
||||
start_dependency(source, node->dependency);
|
||||
while(field) {
|
||||
emit_singleton_field(node, field);
|
||||
field = field->next;
|
||||
}
|
||||
end_dependency(source, node->dependency);
|
||||
node = node->next;
|
||||
}
|
||||
}
|
||||
|
||||
// emit refences functions for a call, return the number of arduments added
|
||||
int emit_references(const struct argument *arg, const char * tab) {
|
||||
int arg_index = NULLABLE_ARG_COUNT_BASE + 2;
|
||||
@ -1895,6 +1995,12 @@ void emit_singleton_metatables(struct userdata *head) {
|
||||
method = method->next;
|
||||
}
|
||||
|
||||
struct userdata_field *field = node->fields;
|
||||
while(field) {
|
||||
fprintf(source, " {\"%s\", %s_%s},\n", field->name, node->sanatized_name, field->name);
|
||||
field = field->next;
|
||||
}
|
||||
|
||||
fprintf(source, " {NULL, NULL}\n");
|
||||
fprintf(source, "};\n");
|
||||
end_dependency(source, node->dependency);
|
||||
@ -2372,6 +2478,8 @@ int main(int argc, char **argv) {
|
||||
|
||||
emit_userdata_metatables();
|
||||
|
||||
emit_singleton_fields();
|
||||
|
||||
emit_userdata_methods(parsed_singletons);
|
||||
|
||||
emit_singleton_metatables(parsed_singletons);
|
||||
|
Loading…
Reference in New Issue
Block a user