diff --git a/libraries/AP_Scripting/lua_generated_bindings.cpp b/libraries/AP_Scripting/lua_generated_bindings.cpp index e11c4c7b74..c0ce852a1d 100644 --- a/libraries/AP_Scripting/lua_generated_bindings.cpp +++ b/libraries/AP_Scripting/lua_generated_bindings.cpp @@ -858,8 +858,12 @@ static int AP_SerialLED_send(lua_State *L) { return luaL_argerror(L, 1, "serialLED not supported on this firmware"); } - binding_argcheck(L, 1); - ud->send(); + binding_argcheck(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"); + const uint8_t data_2 = static_cast(raw_data_2); + ud->send( + data_2); return 0; } @@ -896,7 +900,7 @@ static int AP_SerialLED_set_RGB(lua_State *L) { 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(); if (ud == nullptr) { return luaL_argerror(L, 1, "serialLED not supported on this firmware"); @@ -909,7 +913,28 @@ static int AP_SerialLED_set_num_LEDs(lua_State *L) { 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(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(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(raw_data_3); + const bool data = ud->set_num_neopixel( data_2, data_3); @@ -2243,7 +2268,8 @@ const luaL_Reg SRV_Channels_meta[] = { const luaL_Reg AP_SerialLED_meta[] = { {"send", AP_SerialLED_send}, {"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} };