AP_Scripting: regenerate bindings

This commit is contained in:
Peter Hall 2020-04-03 15:05:21 +01:00 committed by Andrew Tridgell
parent 16d01f03fa
commit 936cc1b1d3
1 changed files with 3 additions and 3 deletions

View File

@ -425,7 +425,7 @@ static int Location_offset(lua_State *L) {
const float raw_data_2 = luaL_checknumber(L, 2); 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"); luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "argument out of range");
const float data_2 = raw_data_2; const float data_2 = raw_data_2;
const float raw_data_3 = luaL_checknumber(L, 2); const float raw_data_3 = luaL_checknumber(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range"); luaL_argcheck(L, ((raw_data_3 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_3 <= MIN(FLT_MAX, INFINITY))), 3, "argument out of range");
const float data_3 = raw_data_3; const float data_3 = raw_data_3;
ud->offset( ud->offset(
@ -603,10 +603,10 @@ static int GCS_set_message_interval(lua_State *L) {
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 >= MAX(0, 0)) && (raw_data_2 <= MIN(MAVLINK_COMM_NUM_BUFFERS, UINT8_MAX))), 2, "argument out of range"); 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 uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const uint32_t raw_data_3 = *check_uint32_t(L, 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"); 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 uint32_t data_3 = static_cast<uint32_t>(raw_data_3);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 2); 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"); 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 int32_t data_4 = raw_data_4;
const MAV_RESULT &data = ud->set_message_interval( const MAV_RESULT &data = ud->set_message_interval(