AP_Scripting: regenerate bindings

This commit is contained in:
Peter Hall 2020-04-07 00:35:48 +01:00 committed by Andrew Tridgell
parent 6704059834
commit 3b907b9baa
1 changed files with 35 additions and 9 deletions

View File

@ -516,8 +516,12 @@ static int AP_SerialLED_send(lua_State *L) {
return luaL_argerror(L, 1, "serialLED not supported on this firmware"); return luaL_argerror(L, 1, "serialLED not supported on this firmware");
} }
binding_argcheck(L, 1); binding_argcheck(L, 2);
ud->send(); const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
ud->send(
data_2);
return 0; return 0;
} }
@ -532,9 +536,9 @@ static int AP_SerialLED_set_RGB(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(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range"); luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, 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, 3); const lua_Integer raw_data_3 = luaL_checkinteger(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(-1, INT8_MIN)) && (raw_data_3 <= MIN(INT8_MAX, INT8_MAX))), 3, "argument out of range");
const uint32_t data_3 = static_cast<uint32_t>(raw_data_3); const int8_t data_3 = static_cast<int8_t>(raw_data_3);
const lua_Integer raw_data_4 = luaL_checkinteger(L, 4); const lua_Integer raw_data_4 = luaL_checkinteger(L, 4);
luaL_argcheck(L, ((raw_data_4 >= MAX(0, 0)) && (raw_data_4 <= MIN(UINT8_MAX, UINT8_MAX))), 4, "argument out of range"); luaL_argcheck(L, ((raw_data_4 >= MAX(0, 0)) && (raw_data_4 <= MIN(UINT8_MAX, UINT8_MAX))), 4, "argument out of range");
const uint8_t data_4 = static_cast<uint8_t>(raw_data_4); const uint8_t data_4 = static_cast<uint8_t>(raw_data_4);
@ -554,7 +558,7 @@ static int AP_SerialLED_set_RGB(lua_State *L) {
return 0; return 0;
} }
static int AP_SerialLED_set_num_LEDs(lua_State *L) { static int AP_SerialLED_set_num_profiled(lua_State *L) {
AP_SerialLED * ud = AP_SerialLED::get_singleton(); AP_SerialLED * ud = AP_SerialLED::get_singleton();
if (ud == nullptr) { if (ud == nullptr) {
return luaL_argerror(L, 1, "serialLED not supported on this firmware"); return luaL_argerror(L, 1, "serialLED not supported on this firmware");
@ -565,9 +569,30 @@ static int AP_SerialLED_set_num_LEDs(lua_State *L) {
luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range"); luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, 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 lua_Integer raw_data_3 = luaL_checkinteger(L, 3); const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(32, UINT8_MAX))), 3, "argument out of range"); luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(AP_SERIALLED_MAX_LEDS, UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3); const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->set_num_LEDs( const bool data = ud->set_num_profiled(
data_2,
data_3);
lua_pushboolean(L, data);
return 1;
}
static int AP_SerialLED_set_num_neopixel(lua_State *L) {
AP_SerialLED * ud = AP_SerialLED::get_singleton();
if (ud == nullptr) {
return luaL_argerror(L, 1, "serialLED not supported on this firmware");
}
binding_argcheck(L, 3);
const lua_Integer raw_data_2 = luaL_checkinteger(L, 2);
luaL_argcheck(L, ((raw_data_2 >= MAX(1, 0)) && (raw_data_2 <= MIN(16, UINT8_MAX))), 2, "argument out of range");
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(AP_SERIALLED_MAX_LEDS, UINT8_MAX))), 3, "argument out of range");
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
const bool data = ud->set_num_neopixel(
data_2, data_2,
data_3); data_3);
@ -1671,7 +1696,8 @@ const luaL_Reg SRV_Channels_meta[] = {
const luaL_Reg AP_SerialLED_meta[] = { const luaL_Reg AP_SerialLED_meta[] = {
{"send", AP_SerialLED_send}, {"send", AP_SerialLED_send},
{"set_RGB", AP_SerialLED_set_RGB}, {"set_RGB", AP_SerialLED_set_RGB},
{"set_num_LEDs", AP_SerialLED_set_num_LEDs}, {"set_num_profiled", AP_SerialLED_set_num_profiled},
{"set_num_neopixel", AP_SerialLED_set_num_neopixel},
{NULL, NULL} {NULL, NULL}
}; };