From be7e142888a4f8a9c9ea28368b7b53e650c72368 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 6 Mar 2020 10:56:45 +1100 Subject: [PATCH] AP_Scripting: regenerate bindings for RPM --- .../AP_Scripting/lua_generated_bindings.cpp | 31 +++++++++++++++++++ .../AP_Scripting/lua_generated_bindings.h | 1 + 2 files changed, 32 insertions(+) diff --git a/libraries/AP_Scripting/lua_generated_bindings.cpp b/libraries/AP_Scripting/lua_generated_bindings.cpp index c0ce852a1d..39a2fc79c2 100644 --- a/libraries/AP_Scripting/lua_generated_bindings.cpp +++ b/libraries/AP_Scripting/lua_generated_bindings.cpp @@ -1,6 +1,7 @@ // auto generated bindings, don't manually edit. See README.md for details. #include "lua_generated_bindings.h" #include "lua_boxed_numerics.h" +#include #include #include #include @@ -552,6 +553,29 @@ const luaL_Reg Location_meta[] = { {NULL, NULL} }; +static int AP_RPM_get_rpm(lua_State *L) { + AP_RPM * ud = AP_RPM::get_singleton(); + if (ud == nullptr) { + return luaL_argerror(L, 1, "RPM 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 >= MAX(0, 0)) && (raw_data_2 <= MIN(RPM_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range"); + const uint8_t data_2 = static_cast(raw_data_2); + float data_5003 = {}; + const bool data = ud->get_rpm( + data_2, + data_5003); + + if (data) { + lua_pushnumber(L, data_5003); + } else { + lua_pushnil(L); + } + return 1; +} + static int AP_Mission_num_commands(lua_State *L) { AP_Mission * ud = AP_Mission::get_singleton(); if (ud == nullptr) { @@ -2220,6 +2244,11 @@ static int AP_AHRS_get_roll(lua_State *L) { return 1; } +const luaL_Reg AP_RPM_meta[] = { + {"get_rpm", AP_RPM_get_rpm}, + {NULL, NULL} +}; + const luaL_Reg AP_Mission_meta[] = { {"num_commands", AP_Mission_num_commands}, {"get_current_do_cmd_id", AP_Mission_get_current_do_cmd_id}, @@ -2506,6 +2535,7 @@ const struct userdata_meta userdata_fun[] = { }; const struct userdata_meta singleton_fun[] = { + {"RPM", AP_RPM_meta, NULL}, {"mission", AP_Mission_meta, AP_Mission_enums}, {"param", AP_Param_meta, NULL}, {"esc_telem", AP_ESC_Telem_meta, NULL}, @@ -2579,6 +2609,7 @@ void load_generated_bindings(lua_State *L) { } const char *singletons[] = { + "RPM", "mission", "param", "esc_telem", diff --git a/libraries/AP_Scripting/lua_generated_bindings.h b/libraries/AP_Scripting/lua_generated_bindings.h index e40eb46413..1b83f6d9c8 100644 --- a/libraries/AP_Scripting/lua_generated_bindings.h +++ b/libraries/AP_Scripting/lua_generated_bindings.h @@ -1,5 +1,6 @@ #pragma once // auto generated bindings, don't manually edit. See README.md for details. +#include #include #include #include