Browse Source

AP_Scripting: Factor out common range constraints

mission-4.1.18
Michael du Breuil 6 years ago committed by WickedShell
parent
commit
9dd36ba511
  1. 43
      libraries/AP_Scripting/lua_bindings.cpp

43
libraries/AP_Scripting/lua_bindings.cpp

@ -4,8 +4,21 @@ @@ -4,8 +4,21 @@
#include "lua_bindings.h"
int lua_gcs_send_text(lua_State *state) {
const char* str = lua_tostring(state, 1);
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name) {
const int args = lua_gettop(L);
if (args != expected_arguments) {
return luaL_error(L, "%s expected %d arguments got %d", fn_name, expected_arguments, args);
}
return 0;
}
// GCS binding
int lua_gcs_send_text(lua_State *L) {
check_arguments(L, 1, "send_text");
const char* str = lua_tostring(L, 1);
gcs().send_text(MAV_SEVERITY_INFO, str);
return 0;
}
@ -16,21 +29,21 @@ static const luaL_Reg gcs_functions[] = @@ -16,21 +29,21 @@ static const luaL_Reg gcs_functions[] =
{NULL, NULL}
};
int lua_servo_set_output_pwm(lua_State *state) {
int servo_function = luaL_checkinteger(state, -2);
int output_value = luaL_checknumber(state, -1);
// servo binding
// range check the output function
if ((servo_function < SRV_Channel::Aux_servo_function_t::k_scripting1) ||
(servo_function > SRV_Channel::Aux_servo_function_t::k_scripting16)) {
return luaL_error(state, "Servo function (%d) is not a scriptable output", servo_function);
}
int lua_servo_set_output_pwm(lua_State *L) {
check_arguments(L, 2, "set_output_pwm");
if (output_value > (int)UINT16_MAX) {
return luaL_error(state, "Servo range (%d) is out of range", output_value);
}
const SRV_Channel::Aux_servo_function_t servo_function = (SRV_Channel::Aux_servo_function_t)luaL_checkinteger(L, 1);
luaL_argcheck(L, ((servo_function >= SRV_Channel::Aux_servo_function_t::k_scripting1) &&
(servo_function <= SRV_Channel::Aux_servo_function_t::k_scripting16)),
2, "function out of range");
const int output = luaL_checknumber(L, 2);
luaL_argcheck(L, ((output >= 0) && (output <= UINT16_MAX)), 2, "output out of range");
SRV_Channels::set_output_pwm((SRV_Channel::Aux_servo_function_t)servo_function, output);
SRV_Channels::set_output_pwm((SRV_Channel::Aux_servo_function_t)servo_function, output_value);
return 0;
}
@ -40,6 +53,8 @@ static const luaL_Reg servo_functions[] = @@ -40,6 +53,8 @@ static const luaL_Reg servo_functions[] =
{NULL, NULL}
};
// all bindings
void load_lua_bindings(lua_State *state) {
luaL_newlib(state, gcs_functions);
lua_setglobal(state, "gcs");

Loading…
Cancel
Save