AP_Scripting: Fix nullable arguments numbering, add location bearing

This commit is contained in:
Michael du Breuil 2019-10-16 23:29:14 -07:00 committed by Randy Mackay
parent a99f67fd5b
commit 610dff61d8
4 changed files with 32 additions and 14 deletions

View File

@ -12,6 +12,7 @@ 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'Null
userdata Location method get_bearing float Location
include AP_AHRS/AP_AHRS.h

View File

@ -861,7 +861,7 @@ void emit_userdata_declarations(void) {
}
#define NULLABLE_ARG_COUNT_BASE 5000
void emit_checker(const struct type t, int arg_number, const char *indentation, const char *name) {
void emit_checker(const struct type t, int arg_number, int skipped, const char *indentation, const char *name) {
assert(indentation != NULL);
if (arg_number > NULLABLE_ARG_COUNT_BASE) {
@ -964,7 +964,7 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
// non down cast
switch (t.type) {
case TYPE_FLOAT:
fprintf(source, "%sconst float raw_data_%d = luaL_checknumber(L, %d);\n", indentation, arg_number, arg_number);
fprintf(source, "%sconst float raw_data_%d = luaL_checknumber(L, %d);\n", indentation, arg_number, arg_number - skipped);
break;
case TYPE_INT8_T:
case TYPE_INT16_T:
@ -972,10 +972,10 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
case TYPE_UINT8_T:
case TYPE_UINT16_T:
case TYPE_ENUM:
fprintf(source, "%sconst lua_Integer raw_data_%d = luaL_checkinteger(L, %d);\n", indentation, arg_number, arg_number);
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);
fprintf(source, "%sconst uint32_t raw_data_%d = *check_uint32_t(L, %d);\n", indentation, arg_number, arg_number - skipped);
break;
case TYPE_NONE:
case TYPE_STRING:
@ -1026,7 +1026,7 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
indentation,
arg_number, cast_target, t.range->low,
arg_number, cast_target, t.range->high,
arg_number, name);
arg_number - skipped, name);
}
}
@ -1120,7 +1120,7 @@ void emit_userdata_field(const struct userdata *data, const struct userdata_fiel
if (field->access_flags & ACCESS_FLAG_WRITE) {
fprintf(source, " case 2: {\n");
emit_checker(field->type, 2, " ", field->name);
emit_checker(field->type, 2, 0, " ", field->name);
fprintf(source, " ud->%s = data_2;\n", field->name);
fprintf(source, " return 0;\n");
fprintf(source, " }\n");
@ -1184,12 +1184,16 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
// extract the arguments
arg = method->arguments;
arg_count = 2;
int skipped = 0;
while (arg != NULL) {
if (arg->type.type != TYPE_LITERAL) {
// emit_checker will emit a nullable argument for us
emit_checker(arg->type, arg_count, " ", "argument");
emit_checker(arg->type, arg_count, skipped, " ", "argument");
arg_count++;
}
if (arg->type.type != TYPE_LITERAL || arg->type.flags & TYPE_FLAGS_NULLABLE) {
skipped++;
}
arg = arg->next;
}

View File

@ -390,6 +390,17 @@ static int Vector3f___sub(lua_State *L) {
return 1;
}
static int Location_get_bearing(lua_State *L) {
binding_argcheck(L, 2);
Location * ud = check_Location(L, 1);
Location & data_2 = *check_Location(L, 2);
const float data = ud->get_bearing(
data_2);
lua_pushnumber(L, data);
return 1;
}
static int Location_get_vector_from_origin_NEU(lua_State *L) {
binding_argcheck(L, 1);
Location * ud = check_Location(L, 1);
@ -412,7 +423,7 @@ static int Location_offset(lua_State *L) {
const float raw_data_2 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "argument out of range");
const float data_2 = raw_data_2;
const float raw_data_3 = luaL_checknumber(L, 3);
const float raw_data_3 = luaL_checknumber(L, 2);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3;
ud->offset(
@ -467,6 +478,7 @@ const luaL_Reg Location_meta[] = {
{"relative_alt", Location_relative_alt},
{"lng", Location_lng},
{"lat", Location_lat},
{"get_bearing", Location_get_bearing},
{"get_vector_from_origin_NEU", Location_get_vector_from_origin_NEU},
{"offset", Location_offset},
{"get_distance", Location_get_distance},
@ -501,10 +513,10 @@ 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 = *check_uint32_t(L, 2);
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);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_4 >= MAX(-1, INT32_MIN)) && (raw_data_4 <= MIN(INT32_MAX, INT32_MAX))), 4, "argument out of range");
const int32_t data_4 = raw_data_4;
const MAV_RESULT &data = ud->set_message_interval(
@ -1084,7 +1096,7 @@ static int AP_BattMonitor_get_temperature(lua_State *L) {
binding_argcheck(L, 2);
float data_5002 = {};
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
const lua_Integer raw_data_3 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(ud->num_instances(), UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->get_temperature(
@ -1171,7 +1183,7 @@ static int AP_BattMonitor_consumed_wh(lua_State *L) {
binding_argcheck(L, 2);
float data_5002 = {};
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
const lua_Integer raw_data_3 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(ud->num_instances(), UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->consumed_wh(
@ -1194,7 +1206,7 @@ static int AP_BattMonitor_consumed_mah(lua_State *L) {
binding_argcheck(L, 2);
float data_5002 = {};
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
const lua_Integer raw_data_3 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(ud->num_instances(), UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->consumed_mah(
@ -1217,7 +1229,7 @@ static int AP_BattMonitor_current_amps(lua_State *L) {
binding_argcheck(L, 2);
float data_5002 = {};
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
const lua_Integer raw_data_3 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(ud->num_instances(), UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->current_amps(

View File

@ -8,6 +8,7 @@ function get_sandbox_env ()
tonumber = tonumber,
tostring = tostring,
type = type,
error = error,
unpack = unpack,
io = { close = io.close, flush = io.flush, input = io.input, open = io.open, output = io.output,
popen = io.popen, read = io.read, type = io.type, write = io.write},