From bd256afee42fa2a723d84430dc943665333c9f8d Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 29 Apr 2019 08:14:26 +0000 Subject: [PATCH] AP_Scripting: extract a common argument check helper Allows an easy additional flag for saving flash space --- libraries/AP_Scripting/generator/src/main.c | 33 +- .../AP_Scripting/lua_generated_bindings.cpp | 726 ++++-------------- 2 files changed, 163 insertions(+), 596 deletions(-) diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index 4373618d06..bbf3c5b244 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -1029,7 +1029,6 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth arg = arg->next; } // sanity check number of args called with - fprintf(source, " const int args = lua_gettop(L);\n"); arg = method->arguments; arg_count = 1; while (arg != NULL) { @@ -1038,11 +1037,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth } arg = arg->next; } - fprintf(source, " if (args > %d) {\n", arg_count); - fprintf(source, " return luaL_argerror(L, args, \"too many arguments\");\n"); - fprintf(source, " } else if (args < %d) {\n", arg_count); - fprintf(source, " return luaL_argerror(L, args, \"too few arguments\");\n"); - fprintf(source, " }\n\n"); + fprintf(source, " binding_argcheck(L, %d);\n", arg_count); switch (data->ud_type) { case UD_USERDATA: @@ -1053,7 +1048,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth // 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 luaL_argerror(L, args, \"%s not supported on this firmware\");\n", access_name); + fprintf(source, " return luaL_argerror(L, %d, \"%s not supported on this firmware\");\n", arg_count, access_name); fprintf(source, " }\n\n"); break; } @@ -1265,12 +1260,7 @@ void emit_operators(struct userdata *data) { fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, op_name); // check number of arguments - fprintf(source, " const int args = lua_gettop(L);\n"); - fprintf(source, " if (args > 2) {\n"); - fprintf(source, " return luaL_argerror(L, args, \"too many arguments\");\n"); - fprintf(source, " } else if (args < 2) {\n"); - fprintf(source, " return luaL_argerror(L, args, \"too few arguments\");\n"); - fprintf(source, " }\n\n"); + 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); @@ -1449,6 +1439,21 @@ void emit_sandbox(void) { fprintf(source, "}\n"); } +void emit_argcheck_helper(void) { + // tagging this with NOINLINE can save a large amount of flash + // but until we need it we will allow the compilier to choose to inline this for us + fprintf(source, "static int binding_argcheck(lua_State *L, int expected_arg_count) {\n"); + fprintf(source, " const int args = lua_gettop(L);\n"); + fprintf(source, " if (args > expected_arg_count) {\n"); + fprintf(source, " return luaL_argerror(L, args, \"too many arguments\");\n"); + fprintf(source, " } else if (args < expected_arg_count) {\n"); + fprintf(source, " return luaL_argerror(L, args, \"too few arguments\");\n"); + fprintf(source, " }\n"); + fprintf(source, " return 0;\n"); + fprintf(source, "}\n\n"); +} + + char * output_path = NULL; int main(int argc, char **argv) { @@ -1521,6 +1526,8 @@ int main(int argc, char **argv) { fprintf(source, "\n\n"); + emit_argcheck_helper(); + emit_userdata_allocators(); emit_userdata_checkers(); diff --git a/libraries/AP_Scripting/lua_generated_bindings.cpp b/libraries/AP_Scripting/lua_generated_bindings.cpp index 78a7a835b2..d52d7f004a 100644 --- a/libraries/AP_Scripting/lua_generated_bindings.cpp +++ b/libraries/AP_Scripting/lua_generated_bindings.cpp @@ -13,6 +13,16 @@ #include +static int binding_argcheck(lua_State *L, int expected_arg_count) { + const int args = lua_gettop(L); + if (args > expected_arg_count) { + return luaL_argerror(L, args, "too many arguments"); + } else if (args < expected_arg_count) { + return luaL_argerror(L, args, "too few arguments"); + } + return 0; +} + int new_Vector2f(lua_State *L) { luaL_checkstack(L, 2, "Out of stack"); void *ud = lua_newuserdata(L, sizeof(Vector2f)); @@ -249,13 +259,7 @@ static int Location_lat(lua_State *L) { } static int Vector2f_is_zero(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector2f * ud = check_Vector2f(L, 1); ud->is_zero( ); @@ -264,13 +268,7 @@ static int Vector2f_is_zero(lua_State *L) { } static int Vector2f_is_inf(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector2f * ud = check_Vector2f(L, 1); ud->is_inf( ); @@ -279,13 +277,7 @@ static int Vector2f_is_inf(lua_State *L) { } static int Vector2f_is_nan(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector2f * ud = check_Vector2f(L, 1); ud->is_nan( ); @@ -294,13 +286,7 @@ static int Vector2f_is_nan(lua_State *L) { } static int Vector2f_normalize(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector2f * ud = check_Vector2f(L, 1); ud->normalize( ); @@ -309,13 +295,7 @@ static int Vector2f_normalize(lua_State *L) { } static int Vector2f_length(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector2f * ud = check_Vector2f(L, 1); const float data = ud->length( ); @@ -325,13 +305,7 @@ static int Vector2f_length(lua_State *L) { } static int Vector2f___add(lua_State *L) { - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); Vector2f *ud = check_Vector2f(L, 1); Vector2f *ud2 = check_Vector2f(L, 2); new_Vector2f(L); @@ -340,13 +314,7 @@ static int Vector2f___add(lua_State *L) { } static int Vector2f___sub(lua_State *L) { - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); Vector2f *ud = check_Vector2f(L, 1); Vector2f *ud2 = check_Vector2f(L, 2); new_Vector2f(L); @@ -355,13 +323,7 @@ static int Vector2f___sub(lua_State *L) { } static int Vector3f_is_zero(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector3f * ud = check_Vector3f(L, 1); ud->is_zero( ); @@ -370,13 +332,7 @@ static int Vector3f_is_zero(lua_State *L) { } static int Vector3f_is_inf(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector3f * ud = check_Vector3f(L, 1); ud->is_inf( ); @@ -385,13 +341,7 @@ static int Vector3f_is_inf(lua_State *L) { } static int Vector3f_is_nan(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector3f * ud = check_Vector3f(L, 1); ud->is_nan( ); @@ -400,13 +350,7 @@ static int Vector3f_is_nan(lua_State *L) { } static int Vector3f_normalize(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector3f * ud = check_Vector3f(L, 1); ud->normalize( ); @@ -415,13 +359,7 @@ static int Vector3f_normalize(lua_State *L) { } static int Vector3f_length(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); Vector3f * ud = check_Vector3f(L, 1); const float data = ud->length( ); @@ -431,13 +369,7 @@ static int Vector3f_length(lua_State *L) { } static int Vector3f___add(lua_State *L) { - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); Vector3f *ud = check_Vector3f(L, 1); Vector3f *ud2 = check_Vector3f(L, 2); new_Vector3f(L); @@ -446,13 +378,7 @@ static int Vector3f___add(lua_State *L) { } static int Vector3f___sub(lua_State *L) { - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); Vector3f *ud = check_Vector3f(L, 1); Vector3f *ud2 = check_Vector3f(L, 2); new_Vector3f(L); @@ -462,13 +388,7 @@ static int Vector3f___sub(lua_State *L) { static int Location_get_vector_from_origin_NEU(lua_State *L) { // 1 Vector3f 14 : 6 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); Location * ud = check_Location(L, 1); Vector3f & data_2 = *check_Vector3f(L, 2); const bool data = ud->get_vector_from_origin_NEU( @@ -481,13 +401,7 @@ static int Location_get_vector_from_origin_NEU(lua_State *L) { static int Location_offset(lua_State *L) { // 1 float 13 : 8 // 2 float 13 : 11 - const int args = lua_gettop(L); - if (args > 3) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 3) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 3); Location * ud = check_Location(L, 1); 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"); @@ -504,13 +418,7 @@ static int Location_offset(lua_State *L) { static int Location_get_distance(lua_State *L) { // 1 Location 12 : 6 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); Location * ud = check_Location(L, 1); Location & data_2 = *check_Location(L, 2); const float data = ud->get_distance( @@ -563,16 +471,10 @@ const luaL_Reg Location_meta[] = { static int GCS_send_text(lua_State *L) { // 1 MAV_SEVERITY 126 : 8 // 2 enum 126 : 9 - const int args = lua_gettop(L); - if (args > 3) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 3) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 3); GCS * ud = GCS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gcs not supported on this firmware"); + return luaL_argerror(L, 3, "gcs not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -588,16 +490,10 @@ static int GCS_send_text(lua_State *L) { static int AP_Relay_toggle(lua_State *L) { // 1 uint8_t 122 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Relay * ud = AP_Relay::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "relay not supported on this firmware"); + return luaL_argerror(L, 2, "relay not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -611,16 +507,10 @@ static int AP_Relay_toggle(lua_State *L) { static int AP_Relay_enabled(lua_State *L) { // 1 uint8_t 121 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Relay * ud = AP_Relay::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "relay not supported on this firmware"); + return luaL_argerror(L, 2, "relay not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -635,16 +525,10 @@ static int AP_Relay_enabled(lua_State *L) { static int AP_Relay_off(lua_State *L) { // 1 uint8_t 120 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Relay * ud = AP_Relay::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "relay not supported on this firmware"); + return luaL_argerror(L, 2, "relay not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -658,16 +542,10 @@ static int AP_Relay_off(lua_State *L) { static int AP_Relay_on(lua_State *L) { // 1 uint8_t 119 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Relay * ud = AP_Relay::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "relay not supported on this firmware"); + return luaL_argerror(L, 2, "relay not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -682,16 +560,10 @@ static int AP_Relay_on(lua_State *L) { static int AP_Terrain_height_above_terrain(lua_State *L) { // 1 float 114 : 6 // 2 bool 114 : 7 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Terrain * ud = AP_Terrain::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "terrain not supported on this firmware"); + return luaL_argerror(L, 2, "terrain not supported on this firmware"); } float data_5002 = {}; @@ -712,16 +584,10 @@ static int AP_Terrain_height_relative_home_equivalent(lua_State *L) { // 1 float 113 : 8 // 2 float 113 : 9 // 3 bool 113 : 10 - const int args = lua_gettop(L); - if (args > 3) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 3) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 3); AP_Terrain * ud = AP_Terrain::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "terrain not supported on this firmware"); + return luaL_argerror(L, 3, "terrain not supported on this firmware"); } const float raw_data_2 = luaL_checknumber(L, 2); @@ -745,16 +611,10 @@ static int AP_Terrain_height_relative_home_equivalent(lua_State *L) { static int AP_Terrain_height_terrain_difference_home(lua_State *L) { // 1 float 112 : 6 // 2 bool 112 : 7 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Terrain * ud = AP_Terrain::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "terrain not supported on this firmware"); + return luaL_argerror(L, 2, "terrain not supported on this firmware"); } float data_5002 = {}; @@ -775,16 +635,10 @@ static int AP_Terrain_height_amsl(lua_State *L) { // 1 Location 111 : 6 // 2 float 111 : 7 // 3 bool 111 : 8 - const int args = lua_gettop(L); - if (args > 3) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 3) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 3); AP_Terrain * ud = AP_Terrain::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "terrain not supported on this firmware"); + return luaL_argerror(L, 3, "terrain not supported on this firmware"); } Location & data_2 = *check_Location(L, 2); @@ -804,16 +658,10 @@ static int AP_Terrain_height_amsl(lua_State *L) { } static int AP_Terrain_status(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_Terrain * ud = AP_Terrain::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "terrain not supported on this firmware"); + return luaL_argerror(L, 1, "terrain not supported on this firmware"); } const uint8_t data = ud->status( @@ -824,16 +672,10 @@ static int AP_Terrain_status(lua_State *L) { } static int AP_Terrain_enabled(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_Terrain * ud = AP_Terrain::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "terrain not supported on this firmware"); + return luaL_argerror(L, 1, "terrain not supported on this firmware"); } const bool data = ud->enabled( @@ -844,16 +686,10 @@ static int AP_Terrain_enabled(lua_State *L) { } static int RangeFinder_num_sensors(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); RangeFinder * ud = RangeFinder::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "rangefinder not supported on this firmware"); + return luaL_argerror(L, 1, "rangefinder not supported on this firmware"); } const uint8_t data = ud->num_sensors( @@ -865,16 +701,10 @@ static int RangeFinder_num_sensors(lua_State *L) { static int AP_Notify_play_tune(lua_State *L) { // 1 enum 99 : 6 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_Notify * ud = AP_Notify::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "AP_Notify not supported on this firmware"); + return luaL_argerror(L, 2, "AP_Notify not supported on this firmware"); } const char * data_2 = luaL_checkstring(L, 2); @@ -885,16 +715,10 @@ static int AP_Notify_play_tune(lua_State *L) { } static int AP_GPS_first_unconfigured_gps(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 1, "gps not supported on this firmware"); } const uint8_t data = ud->first_unconfigured_gps( @@ -905,16 +729,10 @@ static int AP_GPS_first_unconfigured_gps(lua_State *L) { } static int AP_GPS_all_configured(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 1, "gps not supported on this firmware"); } const bool data = ud->all_configured( @@ -926,16 +744,10 @@ static int AP_GPS_all_configured(lua_State *L) { static int AP_GPS_get_antenna_offset(lua_State *L) { // 1 uint8_t 70 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -951,16 +763,10 @@ static int AP_GPS_get_antenna_offset(lua_State *L) { static int AP_GPS_have_vertical_velocity(lua_State *L) { // 1 uint8_t 69 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -975,16 +781,10 @@ static int AP_GPS_have_vertical_velocity(lua_State *L) { static int AP_GPS_last_message_time_ms(lua_State *L) { // 1 uint8_t 68 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1000,16 +800,10 @@ static int AP_GPS_last_message_time_ms(lua_State *L) { static int AP_GPS_last_fix_time_ms(lua_State *L) { // 1 uint8_t 67 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1025,16 +819,10 @@ static int AP_GPS_last_fix_time_ms(lua_State *L) { static int AP_GPS_get_vdop(lua_State *L) { // 1 uint8_t 66 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1049,16 +837,10 @@ static int AP_GPS_get_vdop(lua_State *L) { static int AP_GPS_get_hdop(lua_State *L) { // 1 uint8_t 65 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1073,16 +855,10 @@ static int AP_GPS_get_hdop(lua_State *L) { static int AP_GPS_time_week_ms(lua_State *L) { // 1 uint8_t 64 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1098,16 +874,10 @@ static int AP_GPS_time_week_ms(lua_State *L) { static int AP_GPS_time_week(lua_State *L) { // 1 uint8_t 63 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1122,16 +892,10 @@ static int AP_GPS_time_week(lua_State *L) { static int AP_GPS_num_sats(lua_State *L) { // 1 uint8_t 62 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1146,16 +910,10 @@ static int AP_GPS_num_sats(lua_State *L) { static int AP_GPS_ground_course(lua_State *L) { // 1 uint8_t 61 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1170,16 +928,10 @@ static int AP_GPS_ground_course(lua_State *L) { static int AP_GPS_ground_speed(lua_State *L) { // 1 uint8_t 60 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1194,16 +946,10 @@ static int AP_GPS_ground_speed(lua_State *L) { static int AP_GPS_velocity(lua_State *L) { // 1 uint8_t 59 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1220,16 +966,10 @@ static int AP_GPS_velocity(lua_State *L) { static int AP_GPS_vertical_accuracy(lua_State *L) { // 1 uint8_t 58 : 8 // 2 float 58 : 9 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1251,16 +991,10 @@ static int AP_GPS_vertical_accuracy(lua_State *L) { static int AP_GPS_horizontal_accuracy(lua_State *L) { // 1 uint8_t 57 : 8 // 2 float 57 : 9 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1282,16 +1016,10 @@ static int AP_GPS_horizontal_accuracy(lua_State *L) { static int AP_GPS_speed_accuracy(lua_State *L) { // 1 uint8_t 56 : 8 // 2 float 56 : 9 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1312,16 +1040,10 @@ static int AP_GPS_speed_accuracy(lua_State *L) { static int AP_GPS_location(lua_State *L) { // 1 uint8_t 55 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1337,16 +1059,10 @@ static int AP_GPS_location(lua_State *L) { static int AP_GPS_status(lua_State *L) { // 1 uint8_t 54 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 2, "gps not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1360,16 +1076,10 @@ static int AP_GPS_status(lua_State *L) { } static int AP_GPS_primary_sensor(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 1, "gps not supported on this firmware"); } const uint8_t data = ud->primary_sensor( @@ -1380,16 +1090,10 @@ static int AP_GPS_primary_sensor(lua_State *L) { } static int AP_GPS_num_sensors(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_GPS * ud = AP_GPS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "gps not supported on this firmware"); + return luaL_argerror(L, 1, "gps not supported on this firmware"); } const uint8_t data = ud->num_sensors( @@ -1402,16 +1106,10 @@ static int AP_GPS_num_sensors(lua_State *L) { static int AP_BattMonitor_get_temperature(lua_State *L) { // 1 float 47 : 6 // 2 uint8_t 47 : 9 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } float data_5002 = {}; @@ -1432,16 +1130,10 @@ static int AP_BattMonitor_get_temperature(lua_State *L) { static int AP_BattMonitor_overpower_detected(lua_State *L) { // 1 uint8_t 46 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1455,16 +1147,10 @@ static int AP_BattMonitor_overpower_detected(lua_State *L) { } static int AP_BattMonitor_has_failsafed(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 1, "battery not supported on this firmware"); } const bool data = ud->has_failsafed( @@ -1476,16 +1162,10 @@ static int AP_BattMonitor_has_failsafed(lua_State *L) { static int AP_BattMonitor_pack_capacity_mah(lua_State *L) { // 1 uint8_t 44 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1500,16 +1180,10 @@ static int AP_BattMonitor_pack_capacity_mah(lua_State *L) { static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) { // 1 uint8_t 43 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1524,16 +1198,10 @@ static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) { static int AP_BattMonitor_consumed_wh(lua_State *L) { // 1 uint8_t 42 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1548,16 +1216,10 @@ static int AP_BattMonitor_consumed_wh(lua_State *L) { static int AP_BattMonitor_consumed_mah(lua_State *L) { // 1 uint8_t 41 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1572,16 +1234,10 @@ static int AP_BattMonitor_consumed_mah(lua_State *L) { static int AP_BattMonitor_current_amps(lua_State *L) { // 1 uint8_t 40 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1596,16 +1252,10 @@ static int AP_BattMonitor_current_amps(lua_State *L) { static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) { // 1 uint8_t 39 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1620,16 +1270,10 @@ static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) { static int AP_BattMonitor_voltage(lua_State *L) { // 1 uint8_t 38 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1644,16 +1288,10 @@ static int AP_BattMonitor_voltage(lua_State *L) { static int AP_BattMonitor_has_current(lua_State *L) { // 1 uint8_t 37 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1668,16 +1306,10 @@ static int AP_BattMonitor_has_current(lua_State *L) { static int AP_BattMonitor_has_consumed_energy(lua_State *L) { // 1 uint8_t 36 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1692,16 +1324,10 @@ static int AP_BattMonitor_has_consumed_energy(lua_State *L) { static int AP_BattMonitor_healthy(lua_State *L) { // 1 uint8_t 35 : 8 - const int args = lua_gettop(L); - if (args > 2) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 2) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 2); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 2, "battery not supported on this firmware"); } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); @@ -1715,16 +1341,10 @@ static int AP_BattMonitor_healthy(lua_State *L) { } static int AP_BattMonitor_num_instances(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_BattMonitor * ud = AP_BattMonitor::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "battery not supported on this firmware"); + return luaL_argerror(L, 1, "battery not supported on this firmware"); } const uint8_t data = ud->num_instances( @@ -1735,16 +1355,10 @@ static int AP_BattMonitor_num_instances(lua_State *L) { } static int AP_AHRS_prearm_healthy(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } ud->get_semaphore().take_blocking(); @@ -1757,16 +1371,10 @@ static int AP_AHRS_prearm_healthy(lua_State *L) { } static int AP_AHRS_home_is_set(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } ud->get_semaphore().take_blocking(); @@ -1780,16 +1388,10 @@ static int AP_AHRS_home_is_set(lua_State *L) { static int AP_AHRS_get_relative_position_NED_home(lua_State *L) { // 1 Vector3f 27 : 6 - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } Vector3f data_5002 = {}; @@ -1809,16 +1411,10 @@ static int AP_AHRS_get_relative_position_NED_home(lua_State *L) { static int AP_AHRS_get_velocity_NED(lua_State *L) { // 1 Vector3f 26 : 6 - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } Vector3f data_5002 = {}; @@ -1837,16 +1433,10 @@ static int AP_AHRS_get_velocity_NED(lua_State *L) { } static int AP_AHRS_groundspeed_vector(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } ud->get_semaphore().take_blocking(); @@ -1860,16 +1450,10 @@ static int AP_AHRS_groundspeed_vector(lua_State *L) { } static int AP_AHRS_wind_estimate(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } ud->get_semaphore().take_blocking(); @@ -1884,16 +1468,10 @@ static int AP_AHRS_wind_estimate(lua_State *L) { static int AP_AHRS_get_hagl(lua_State *L) { // 1 float 23 : 6 - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } float data_5002 = {}; @@ -1911,16 +1489,10 @@ static int AP_AHRS_get_hagl(lua_State *L) { } static int AP_AHRS_get_gyro(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } ud->get_semaphore().take_blocking(); @@ -1934,16 +1506,10 @@ static int AP_AHRS_get_gyro(lua_State *L) { } static int AP_AHRS_get_home(lua_State *L) { - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } ud->get_semaphore().take_blocking(); @@ -1958,16 +1524,10 @@ static int AP_AHRS_get_home(lua_State *L) { static int AP_AHRS_get_position(lua_State *L) { // 1 Location 20 : 6 - const int args = lua_gettop(L); - if (args > 1) { - return luaL_argerror(L, args, "too many arguments"); - } else if (args < 1) { - return luaL_argerror(L, args, "too few arguments"); - } - + binding_argcheck(L, 1); AP_AHRS * ud = AP_AHRS::get_singleton(); if (ud == nullptr) { - return luaL_argerror(L, args, "ahrs not supported on this firmware"); + return luaL_argerror(L, 1, "ahrs not supported on this firmware"); } Location data_5002 = {};