AP_Scripting: Fix generation of uint32_t arguments

This also fixes the message interval description not generating
correctly, it must have been manually edited before
This commit is contained in:
Michael du Breuil 2019-10-08 21:06:24 -07:00 committed by Andrew Tridgell
parent 5ac44c3aaf
commit 7b9d3594fb
3 changed files with 30 additions and 31 deletions

View File

@ -134,4 +134,4 @@ singleton AP_Relay method toggle void uint8_t 0 AP_RELAY_NUM_RELAYS
include GCS_MAVLink/GCS.h
singleton GCS alias gcs
singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string
singleton GCS method set_message_interval MAV_RESULT uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t 0 UINT32_MAX int32_t -1 INT32_MAX
singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t 0U UINT32_MAX int32_t -1 INT32_MAX

View File

@ -944,8 +944,8 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
forced_max = "UINT16_MAX";
break;
case TYPE_UINT32_T:
forced_min = "0";
forced_max = "UINT16_MAX";
forced_min = "0U";
forced_max = "UINT32_MAX";
break;
case TYPE_ENUM:
forced_min = forced_max = NULL;
@ -975,7 +975,7 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
fprintf(source, "%sconst lua_Integer raw_data_%d = luaL_checkinteger(L, %d);\n", indentation, arg_number, arg_number);
break;
case TYPE_UINT32_T:
fprintf(source, "%sconst uint32_t raw_data_%d = coerce_to_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);
break;
case TYPE_NONE:
case TYPE_STRING:

View File

@ -472,6 +472,31 @@ const luaL_Reg Location_meta[] = {
{NULL, NULL}
};
static int GCS_set_message_interval(lua_State *L) {
GCS * ud = GCS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gcs not supported on this firmware");
}
binding_argcheck(L, 4);
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);
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);
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(
data_2,
data_3,
data_4);
lua_pushinteger(L, data);
return 1;
}
static int GCS_send_text(lua_State *L) {
GCS * ud = GCS::get_singleton();
if (ud == nullptr) {
@ -491,32 +516,6 @@ static int GCS_send_text(lua_State *L) {
return 0;
}
static int GCS_set_message_interval(lua_State *L) {
GCS * ud = GCS::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "gcs not supported on this firmware");
}
binding_argcheck(L, 4);
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 uint32_t data_2 = static_cast<uint32_t>(raw_data_2);
const lua_Unsigned raw_data_3 = luaL_checkinteger(L, 3);
luaL_argcheck(L, (raw_data_3 <= 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);
luaL_argcheck(L, ((raw_data_4 >= -1) && (raw_data_4 <= INT32_MAX)), 4, "argument out of range");
const int32_t data_4 = static_cast<int32_t>(raw_data_4);
const MAV_RESULT data = ud->set_message_interval(
data_2,
data_3,
data_4);
lua_pushinteger(L, data);
return 1;
}
static int AP_Relay_toggle(lua_State *L) {
AP_Relay * ud = AP_Relay::get_singleton();
if (ud == nullptr) {
@ -1544,8 +1543,8 @@ static int AP_AHRS_get_roll(lua_State *L) {
}
const luaL_Reg GCS_meta[] = {
{"send_text", GCS_send_text},
{"set_message_interval", GCS_set_message_interval},
{"send_text", GCS_send_text},
{NULL, NULL}
};