@ -1,6 +1,8 @@
@@ -1,6 +1,8 @@
// auto generated bindings, don't manually edit
# include "lua_generated_bindings.h"
# include "lua_boxed_numerics.h"
# include <SRV_Channel/SRV_Channel.h>
# include <AP_SerialLED/AP_SerialLED.h>
# include <AP_Vehicle/AP_Vehicle.h>
# include <GCS_MAVLink/GCS.h>
# include <AP_Relay/AP_Relay.h>
@ -485,6 +487,94 @@ const luaL_Reg Location_meta[] = {
@@ -485,6 +487,94 @@ const luaL_Reg Location_meta[] = {
{ NULL , NULL }
} ;
static int SRV_Channels_find_channel ( lua_State * L ) {
SRV_Channels * ud = SRV_Channels : : get_singleton ( ) ;
if ( ud = = nullptr ) {
return luaL_argerror ( L , 1 , " SRV_Channels 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 > ( SRV_Channel : : k_none ) ) & & ( raw_data_2 < = static_cast < int32_t > ( SRV_Channel : : k_nr_aux_servo_functions - 1 ) ) ) , 2 , " argument out of range " ) ;
const SRV_Channel : : Aux_servo_function_t data_2 = static_cast < SRV_Channel : : Aux_servo_function_t > ( raw_data_2 ) ;
uint8_t data_5003 = { } ;
const bool data = ud - > find_channel (
data_2 ,
data_5003 ) ;
if ( data ) {
lua_pushinteger ( L , data_5003 ) ;
} else {
lua_pushnil ( L ) ;
}
return 1 ;
}
static int AP_SerialLED_send ( 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 , 1 ) ;
ud - > send ( ) ;
return 0 ;
}
static int AP_SerialLED_set_RGB ( 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 , 6 ) ;
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 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 ( 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 lua_Integer raw_data_5 = luaL_checkinteger ( L , 5 ) ;
luaL_argcheck ( L , ( ( raw_data_5 > = MAX ( 0 , 0 ) ) & & ( raw_data_5 < = MIN ( UINT8_MAX , UINT8_MAX ) ) ) , 5 , " argument out of range " ) ;
const uint8_t data_5 = static_cast < uint8_t > ( raw_data_5 ) ;
const lua_Integer raw_data_6 = luaL_checkinteger ( L , 6 ) ;
luaL_argcheck ( L , ( ( raw_data_6 > = MAX ( 0 , 0 ) ) & & ( raw_data_6 < = MIN ( UINT8_MAX , UINT8_MAX ) ) ) , 6 , " argument out of range " ) ;
const uint8_t data_6 = static_cast < uint8_t > ( raw_data_6 ) ;
ud - > set_RGB (
data_2 ,
data_3 ,
data_4 ,
data_5 ,
data_6 ) ;
return 0 ;
}
static int AP_SerialLED_set_num_LEDs ( 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 ( 0 , 0 ) ) & & ( raw_data_2 < = MIN ( 15 , 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 ( 32 , 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_LEDs (
data_2 ,
data_3 ) ;
lua_pushboolean ( L , data ) ;
return 1 ;
}
static int AP_Vehicle_set_mode ( lua_State * L ) {
AP_Vehicle * ud = AP_Vehicle : : get_singleton ( ) ;
if ( ud = = nullptr ) {
@ -1573,6 +1663,18 @@ static int AP_AHRS_get_roll(lua_State *L) {
@@ -1573,6 +1663,18 @@ static int AP_AHRS_get_roll(lua_State *L) {
return 1 ;
}
const luaL_Reg SRV_Channels_meta [ ] = {
{ " find_channel " , SRV_Channels_find_channel } ,
{ NULL , NULL }
} ;
const luaL_Reg AP_SerialLED_meta [ ] = {
{ " send " , AP_SerialLED_send } ,
{ " set_RGB " , AP_SerialLED_set_RGB } ,
{ " set_num_LEDs " , AP_SerialLED_set_num_LEDs } ,
{ NULL , NULL }
} ;
const luaL_Reg AP_Vehicle_meta [ ] = {
{ " set_mode " , AP_Vehicle_set_mode } ,
{ NULL , NULL }
@ -1709,6 +1811,8 @@ const struct userdata_meta userdata_fun[] = {
@@ -1709,6 +1811,8 @@ const struct userdata_meta userdata_fun[] = {
} ;
const struct userdata_meta singleton_fun [ ] = {
{ " SRV_Channels " , SRV_Channels_meta , NULL } ,
{ " serialLED " , AP_SerialLED_meta , NULL } ,
{ " vehicle " , AP_Vehicle_meta , NULL } ,
{ " gcs " , GCS_meta , NULL } ,
{ " relay " , AP_Relay_meta , NULL } ,
@ -1760,6 +1864,8 @@ void load_generated_bindings(lua_State *L) {
@@ -1760,6 +1864,8 @@ void load_generated_bindings(lua_State *L) {
}
const char * singletons [ ] = {
" SRV_Channels " ,
" serialLED " ,
" vehicle " ,
" gcs " ,
" relay " ,