2018-10-03 17:37:43 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2018-10-30 03:01:15 -03:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
2019-04-29 04:42:26 -03:00
|
|
|
#include <AP_HAL/HAL.h>
|
2018-10-03 17:37:43 -03:00
|
|
|
|
|
|
|
#include "lua_bindings.h"
|
|
|
|
|
2019-04-29 04:42:26 -03:00
|
|
|
#include "lua_boxed_numerics.h"
|
2020-05-10 06:37:10 -03:00
|
|
|
#include <AP_Scripting/lua_generated_bindings.h>
|
2019-03-14 04:38:12 -03:00
|
|
|
|
2019-04-29 04:42:26 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2019-01-21 19:00:57 -04:00
|
|
|
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name);
|
2019-01-10 20:00:06 -04:00
|
|
|
int check_arguments(lua_State *L, int expected_arguments, const char *fn_name) {
|
2019-01-21 19:00:57 -04:00
|
|
|
#if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1
|
|
|
|
if (expected_arguments < 0) {
|
|
|
|
AP_HAL::panic("Lua: Attempted to check for negative arguments");
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-01-10 20:00:06 -04:00
|
|
|
const int args = lua_gettop(L);
|
|
|
|
if (args != expected_arguments) {
|
|
|
|
return luaL_error(L, "%s expected %d arguments got %d", fn_name, expected_arguments, args);
|
|
|
|
}
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2019-04-29 04:42:26 -03:00
|
|
|
// millis
|
2019-04-29 05:21:20 -03:00
|
|
|
static int lua_millis(lua_State *L) {
|
2019-04-29 04:42:26 -03:00
|
|
|
check_arguments(L, 0, "millis");
|
|
|
|
|
|
|
|
new_uint32_t(L);
|
|
|
|
*check_uint32_t(L, -1) = AP_HAL::millis();
|
|
|
|
|
|
|
|
return 1;
|
|
|
|
}
|
|
|
|
|
2020-02-13 16:50:17 -04:00
|
|
|
static const luaL_Reg global_functions[] =
|
|
|
|
{
|
|
|
|
{"millis", lua_millis},
|
|
|
|
{NULL, NULL}
|
|
|
|
};
|
|
|
|
|
2019-01-21 19:00:57 -04:00
|
|
|
void load_lua_bindings(lua_State *L) {
|
2020-02-13 16:50:17 -04:00
|
|
|
luaL_setfuncs(L, global_functions, 0);
|
2018-10-03 17:37:43 -03:00
|
|
|
}
|
|
|
|
|