From 8db8dcd2d2296f9d5b66d1d5475289fbe08828ad Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 29 Apr 2019 08:21:20 +0000 Subject: [PATCH] AP_Scripting: Fix up some warnings -Remove some non forward declared issues -Remove forced min/max values from the enum range check --- libraries/AP_Scripting/generator/src/main.c | 22 ++++++++++++++----- libraries/AP_Scripting/lua_bindings.cpp | 5 ++--- libraries/AP_Scripting/lua_boxed_numerics.cpp | 3 ++- .../AP_Scripting/lua_generated_bindings.cpp | 2 +- 4 files changed, 21 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index bbf3c5b244..e4cc5db418 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -845,7 +845,6 @@ void emit_checker(const struct type t, int arg_number, const char *indentation, forced_min = "INT16_MIN"; forced_max = "INT16_MAX"; break; - case TYPE_ENUM: // enums are assumed to only ever be within the int32_t space case TYPE_INT32_T: forced_min = "INT32_MIN"; forced_max = "INT32_MAX"; @@ -862,6 +861,9 @@ void emit_checker(const struct type t, int arg_number, const char *indentation, forced_min = "0"; forced_max = "UINT16_MAX"; break; + case TYPE_ENUM: + forced_min = forced_max = NULL; + 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_STRING: @@ -899,11 +901,19 @@ void emit_checker(const struct type t, int arg_number, const char *indentation, // range check if (t.range != NULL) { - fprintf(source, "%sluaL_argcheck(L, ((raw_data_%d >= MAX(%s, %s)) && (raw_data_%d <= MIN(%s, %s))), %d, \"%s out of range\");\n", - indentation, - arg_number, t.range->low, forced_min, - arg_number, t.range->high, forced_max, - arg_number, name); + if ((forced_min != NULL) && (forced_max != NULL)) { + fprintf(source, "%sluaL_argcheck(L, ((raw_data_%d >= MAX(%s, %s)) && (raw_data_%d <= MIN(%s, %s))), %d, \"%s out of range\");\n", + indentation, + arg_number, t.range->low, forced_min, + arg_number, t.range->high, forced_max, + arg_number, name); + } else { + fprintf(source, "%sluaL_argcheck(L, ((raw_data_%d >= %s) && (raw_data_%d <= %s)), %d, \"%s out of range\");\n", + indentation, + arg_number, t.range->low, + arg_number, t.range->high, + arg_number, name); + } } // down cast diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index f6b85ea0e8..a8ff247771 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -26,8 +26,7 @@ int check_arguments(lua_State *L, int expected_arguments, const char *fn_name) { // servo binding -int lua_servo_set_output_pwm(lua_State *L); -int lua_servo_set_output_pwm(lua_State *L) { +static int lua_servo_set_output_pwm(lua_State *L) { check_arguments(L, 2, "set_output_pwm"); const SRV_Channel::Aux_servo_function_t servo_function = (SRV_Channel::Aux_servo_function_t)luaL_checkinteger(L, -2); @@ -44,7 +43,7 @@ int lua_servo_set_output_pwm(lua_State *L) { } // millis -int lua_millis(lua_State *L) { +static int lua_millis(lua_State *L) { check_arguments(L, 0, "millis"); new_uint32_t(L); diff --git a/libraries/AP_Scripting/lua_boxed_numerics.cpp b/libraries/AP_Scripting/lua_boxed_numerics.cpp index c40248111b..4dda7feffd 100644 --- a/libraries/AP_Scripting/lua_boxed_numerics.cpp +++ b/libraries/AP_Scripting/lua_boxed_numerics.cpp @@ -1,6 +1,7 @@ #include #include "lua_boxed_numerics.h" + extern const AP_HAL::HAL& hal; int new_uint32_t(lua_State *L) { @@ -16,7 +17,7 @@ uint32_t * check_uint32_t(lua_State *L, int arg) { return static_cast(data); } -uint32_t coerce_to_uint32_t(lua_State *L, int arg) { +static uint32_t coerce_to_uint32_t(lua_State *L, int arg) { { // userdata const uint32_t * ud = static_cast(luaL_testudata(L, arg, "uint32_t")); if (ud != nullptr) { diff --git a/libraries/AP_Scripting/lua_generated_bindings.cpp b/libraries/AP_Scripting/lua_generated_bindings.cpp index d52d7f004a..55190caf9a 100644 --- a/libraries/AP_Scripting/lua_generated_bindings.cpp +++ b/libraries/AP_Scripting/lua_generated_bindings.cpp @@ -478,7 +478,7 @@ static int GCS_send_text(lua_State *L) { } const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); - luaL_argcheck(L, ((raw_data_2 >= MAX(MAV_SEVERITY_EMERGENCY, INT32_MIN)) && (raw_data_2 <= MIN(MAV_SEVERITY_DEBUG, INT32_MAX))), 2, "argument out of range"); + luaL_argcheck(L, ((raw_data_2 >= MAV_SEVERITY_EMERGENCY) && (raw_data_2 <= MAV_SEVERITY_DEBUG)), 2, "argument out of range"); const MAV_SEVERITY data_2 = static_cast(raw_data_2); const char * data_3 = luaL_checkstring(L, 3); ud->send_text(