AP_Scripting: Add arming call, improve range check casting

This commit is contained in:
Michael du Breuil 2019-07-19 22:28:49 -07:00 committed by Randy Mackay
parent bb7f80b452
commit f79a3100d0
3 changed files with 50 additions and 6 deletions

View File

@ -36,6 +36,7 @@ include AP_Arming/AP_Arming.h
singleton AP_Arming alias arming singleton AP_Arming alias arming
singleton AP_Arming method disarm boolean singleton AP_Arming method disarm boolean
singleton AP_Arming method is_armed boolean singleton AP_Arming method is_armed boolean
singleton AP_Arming method arm boolean AP_Arming::Method'enum AP_Arming::Method::RUDDER AP_Arming::Method::MOTORTEST
include AP_BattMonitor/AP_BattMonitor.h include AP_BattMonitor/AP_BattMonitor.h

View File

@ -931,11 +931,36 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
arg_number, t.range->high, forced_max, arg_number, t.range->high, forced_max,
arg_number, name); arg_number, name);
} else { } else {
fprintf(source, "%sluaL_argcheck(L, ((raw_data_%d >= %s) && (raw_data_%d <= %s)), %d, \"%s out of range\");\n", char * cast_target = "";
indentation,
arg_number, t.range->low, switch (t.type) {
arg_number, t.range->high, case TYPE_FLOAT:
arg_number, name); cast_target = "float";
break;
case TYPE_INT8_T:
case TYPE_INT16_T:
case TYPE_INT32_T:
case TYPE_UINT8_T:
case TYPE_UINT16_T:
case TYPE_ENUM:
cast_target = "int32_t";
break;
case TYPE_UINT32_T:
cast_target = "uint32_t";
break;
case TYPE_NONE:
case TYPE_STRING:
case TYPE_BOOLEAN:
case TYPE_USERDATA:
assert(t.range == NULL); // we should have caught this during the parse phase
break;
}
fprintf(source, "%sluaL_argcheck(L, ((raw_data_%d >= static_cast<%s>(%s)) && (raw_data_%d <= static_cast<%s>(%s))), %d, \"%s out of range\");\n",
indentation,
arg_number, cast_target, t.range->low,
arg_number, cast_target, t.range->high,
arg_number, name);
} }
} }

View File

@ -478,7 +478,7 @@ static int GCS_send_text(lua_State *L) {
binding_argcheck(L, 3); binding_argcheck(L, 3);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2); const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAV_SEVERITY_EMERGENCY) && (raw_data_2 <= MAV_SEVERITY_DEBUG)), 2, "argument out of range"); luaL_argcheck(L, ((raw_data_2 >= static_cast<int32_t>(MAV_SEVERITY_EMERGENCY)) && (raw_data_2 <= static_cast<int32_t>(MAV_SEVERITY_DEBUG))), 2, "argument out of range");
const MAV_SEVERITY data_2 = static_cast<MAV_SEVERITY>(raw_data_2); const MAV_SEVERITY data_2 = static_cast<MAV_SEVERITY>(raw_data_2);
const char * data_3 = luaL_checkstring(L, 3); const char * data_3 = luaL_checkstring(L, 3);
ud->send_text( ud->send_text(
@ -1290,6 +1290,23 @@ static int AP_BattMonitor_num_instances(lua_State *L) {
return 1; return 1;
} }
static int AP_Arming_arm(lua_State *L) {
AP_Arming * ud = AP_Arming::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "arming not supported on this firmware");
}
binding_argcheck(L, 2);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= static_cast<int32_t>(AP_Arming::Method::RUDDER)) && (raw_data_2 <= static_cast<int32_t>(AP_Arming::Method::MOTORTEST))), 2, "argument out of range");
const AP_Arming::Method data_2 = static_cast<AP_Arming::Method>(raw_data_2);
const bool data = ud->arm(
data_2);
lua_pushboolean(L, data);
return 1;
}
static int AP_Arming_is_armed(lua_State *L) { static int AP_Arming_is_armed(lua_State *L) {
AP_Arming * ud = AP_Arming::get_singleton(); AP_Arming * ud = AP_Arming::get_singleton();
if (ud == nullptr) { if (ud == nullptr) {
@ -1632,6 +1649,7 @@ const luaL_Reg AP_BattMonitor_meta[] = {
}; };
const luaL_Reg AP_Arming_meta[] = { const luaL_Reg AP_Arming_meta[] = {
{"arm", AP_Arming_arm},
{"is_armed", AP_Arming_is_armed}, {"is_armed", AP_Arming_is_armed},
{"disarm", AP_Arming_disarm}, {"disarm", AP_Arming_disarm},
{NULL, NULL} {NULL, NULL}