mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Scripting: Add more primitive types
This commit is contained in:
parent
40245cabf1
commit
746240ebe3
@ -28,7 +28,9 @@ An example script is given below:
|
||||
|
||||
```lua
|
||||
function update () -- periodic function that will be called
|
||||
distance = ahrs:position():distance(ahrs:home()) -- calculate the distance from home
|
||||
current_pos = Location()
|
||||
AP_AHRS:get_position(current_pos)
|
||||
distance = current_pos:get_distance(AP_AHRS:get_home()) -- calculate the distance from home
|
||||
if distance > 1000 then -- if more then 1000 meters away
|
||||
distance = 1000; -- clamp the distance to 1000 meters
|
||||
end
|
||||
@ -36,6 +38,4 @@ function update () -- periodic function that will be called
|
||||
|
||||
return update, 1000 -- request to be rerun again 1000 milliseconds (1 second) from now
|
||||
end
|
||||
|
||||
return update, 0 -- immediately run the update function
|
||||
```
|
||||
|
@ -15,8 +15,8 @@ userdata Location method get_vector_from_origin_NEU boolean Vector3f
|
||||
|
||||
include AP_AHRS/AP_AHRS.h
|
||||
|
||||
singleton ahrs method get_position boolean Location
|
||||
singleton ahrs method get_home Location
|
||||
singleton AP_AHRS method get_position boolean Location
|
||||
singleton AP_AHRS method get_home Location
|
||||
|
||||
include AP_Math/AP_Math.h
|
||||
|
||||
@ -25,4 +25,7 @@ userdata Vector3f field y float read write -FLT_MAX FLT_MAX
|
||||
userdata Vector3f field z float read write -FLT_MAX FLT_MAX
|
||||
|
||||
include AP_Notify/AP_Notify.h
|
||||
singleton notify method play_tune void string
|
||||
singleton AP_Notify method play_tune void string
|
||||
|
||||
include AP_RangeFinder/AP_RangeFinder.h
|
||||
singleton RangeFinder method num_sensors uint8_t
|
||||
|
@ -16,11 +16,15 @@ char keyword_userdata[] = "userdata";
|
||||
char keyword_write[] = "write";
|
||||
|
||||
// type keywords
|
||||
char keyword_boolean[] = "boolean";
|
||||
char keyword_float[] = "float";
|
||||
char keyword_int32_t[] = "int32_t";
|
||||
char keyword_string[] = "string";
|
||||
char keyword_void[] = "void";
|
||||
char keyword_boolean[] = "boolean";
|
||||
char keyword_float[] = "float";
|
||||
char keyword_int8_t[] = "int8_t";
|
||||
char keyword_int16_t[] = "int16_t";
|
||||
char keyword_int32_t[] = "int32_t";
|
||||
char keyword_string[] = "string";
|
||||
char keyword_uint8_t[] = "uint8_t";
|
||||
char keyword_uint16_t[] = "uint16_t";
|
||||
char keyword_void[] = "void";
|
||||
|
||||
enum error_codes {
|
||||
ERROR_OUT_OF_MEMORY = 1, // ran out of memory
|
||||
@ -67,7 +71,11 @@ enum access_flags {
|
||||
enum field_type {
|
||||
TYPE_BOOLEAN,
|
||||
TYPE_FLOAT,
|
||||
TYPE_INT8_T,
|
||||
TYPE_INT16_T,
|
||||
TYPE_INT32_T,
|
||||
TYPE_UINT8_T,
|
||||
TYPE_UINT16_T,
|
||||
TYPE_NONE,
|
||||
TYPE_STRING,
|
||||
TYPE_USERDATA,
|
||||
@ -282,7 +290,11 @@ unsigned int parse_access_flags(struct type * type) {
|
||||
flags |= ACCESS_FLAG_WRITE;
|
||||
switch (type->type) {
|
||||
case TYPE_FLOAT:
|
||||
case TYPE_INT8_T:
|
||||
case TYPE_INT16_T:
|
||||
case TYPE_INT32_T:
|
||||
case TYPE_UINT8_T:
|
||||
case TYPE_UINT16_T:
|
||||
type->range = parse_range_check();
|
||||
break;
|
||||
case TYPE_USERDATA:
|
||||
@ -343,8 +355,16 @@ int parse_type(struct type *type, const enum type_restriction restrictions, enum
|
||||
type->type = TYPE_BOOLEAN;
|
||||
} else if (strcmp(data_type, keyword_float) == 0) {
|
||||
type->type = TYPE_FLOAT;
|
||||
} else if (strcmp(data_type, keyword_int8_t) == 0) {
|
||||
type->type = TYPE_INT8_T;
|
||||
} else if (strcmp(data_type, keyword_int16_t) == 0) {
|
||||
type->type = TYPE_INT16_T;
|
||||
} else if (strcmp(data_type, keyword_int32_t) == 0) {
|
||||
type->type = TYPE_INT32_T;
|
||||
} else if (strcmp(data_type, keyword_uint8_t) == 0) {
|
||||
type->type = TYPE_UINT8_T;
|
||||
} else if (strcmp(data_type, keyword_uint16_t) == 0) {
|
||||
type->type = TYPE_UINT16_T;
|
||||
} else if (strcmp(data_type, keyword_string) == 0) {
|
||||
type->type = TYPE_STRING;
|
||||
} else if (strcmp(data_type, keyword_void) == 0) {
|
||||
@ -358,8 +378,11 @@ int parse_type(struct type *type, const enum type_restriction restrictions, enum
|
||||
if (range_type != RANGE_CHECK_NONE) {
|
||||
switch (type->type) {
|
||||
case TYPE_FLOAT:
|
||||
case TYPE_INT8_T:
|
||||
case TYPE_INT16_T:
|
||||
case TYPE_INT32_T:
|
||||
printf("loading a range");
|
||||
case TYPE_UINT8_T:
|
||||
case TYPE_UINT16_T:
|
||||
type->range = parse_range_check();
|
||||
break;
|
||||
case TYPE_BOOLEAN:
|
||||
@ -580,6 +603,8 @@ void emit_range_check(const struct range_check *range, const char * name, const
|
||||
if (range == NULL) {
|
||||
error(ERROR_INTERNAL, "Internal Error: Attempted to emit a range check for %s but no range check information was found", name);
|
||||
}
|
||||
// FIXME: emit an implict range check on primitive int types to ensure that they are within a representable range
|
||||
// should be able to use MAX() around the call
|
||||
fprintf(source, "%sluaL_argcheck(L, ((%s >= %s) && (%s <= %s)), 2, \"%s out of range\");\n",
|
||||
indentation != NULL ? indentation : "",
|
||||
internal_name, range->low,
|
||||
@ -593,13 +618,25 @@ void emit_checker(const struct type t, int arg_number, const char *indentation,
|
||||
// consider the arg numberto provide both the name, and the stack position of the variable
|
||||
switch (t.type) {
|
||||
case TYPE_BOOLEAN:
|
||||
fprintf(source, "%sconst bool data_%d = lua_toboolean(L, %d);\n", indentation, arg_number, arg_number);
|
||||
fprintf(source, "%sconst bool data_%d = static_cast<bool>(lua_toboolean(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, "%sconst float data_%d = luaL_checknumber(L, %d);\n", indentation, arg_number, arg_number);
|
||||
fprintf(source, "%sconst float data_%d = static_cast<float>(luaL_checknumber(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
fprintf(source, "%sconst int8_t data_%d = static_cast<int8_t>(luaL_checkinteger(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_INT16_T:
|
||||
fprintf(source, "%sconst int16_t data_%d = static_cast<int16_t>(luaL_checkinteger(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_INT32_T:
|
||||
fprintf(source, "%sconst int32_t data_%d = luaL_checkinteger(L, %d);\n", indentation, arg_number, arg_number);
|
||||
fprintf(source, "%sconst int32_t data_%d = static_cast<int32_t>(luaL_checkinteger(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_UINT8_T:
|
||||
fprintf(source, "%sconst uint8_t data_%d = static_cast<uint8_t>(luaL_checkinteger(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_UINT16_T:
|
||||
fprintf(source, "%sconst uint16_t data_%d = static_cast<uint16_t>luaL_checkinteger(L, %d));\n", indentation, arg_number, arg_number);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
return; // nothing to do here, this should potentially be checked outside of this, but it makes an easier implementation to accept it
|
||||
@ -634,7 +671,11 @@ void emit_userdata_field(const struct userdata *data, const struct userdata_fiel
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, " lua_pushnumber(L, ud->%s);\n", field->name);
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
case TYPE_INT16_T:
|
||||
case TYPE_INT32_T:
|
||||
case TYPE_UINT8_T:
|
||||
case TYPE_UINT16_T:
|
||||
fprintf(source, " lua_pushinteger(L, ud->%s);\n", field->name);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
@ -712,9 +753,21 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, " const float data = ud->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
fprintf(source, " const int8_t data = ud->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_INT16_T:
|
||||
fprintf(source, " const int16_t data = ud->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_INT32_T:
|
||||
fprintf(source, " const int32_t data = ud->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_UINT8_T:
|
||||
fprintf(source, " const uint8_t data = ud->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_UINT16_T:
|
||||
fprintf(source, " const uint16_t data = ud->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
fprintf(source, " const char * data = ud->%s(\n", method->name);
|
||||
break;
|
||||
@ -745,7 +798,11 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, " lua_pushnumber(L, data);\n");
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
case TYPE_INT16_T:
|
||||
case TYPE_INT32_T:
|
||||
case TYPE_UINT8_T:
|
||||
case TYPE_UINT16_T:
|
||||
fprintf(source, " lua_pushinteger(L, data);\n");
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
@ -783,7 +840,6 @@ void emit_singleton_method(const struct singleton *data, const struct method *me
|
||||
arg_count++;
|
||||
arg = arg->next;
|
||||
}
|
||||
const char * dereference = ".";
|
||||
|
||||
fprintf(source, "int %s_%s(lua_State *L) {\n", data->name, method->name);
|
||||
fprintf(source, " const int args = lua_gettop(L);\n");
|
||||
@ -792,7 +848,13 @@ void emit_singleton_method(const struct singleton *data, const struct method *me
|
||||
fprintf(source, " } else if (args < %d) {\n", arg_count);
|
||||
fprintf(source, " return luaL_argerror(L, args, \"too few arguments\");\n");
|
||||
fprintf(source, " }\n\n");
|
||||
fprintf(source, " luaL_checkudata(L, 1, \"%s\");\n", data->name);
|
||||
fprintf(source, " luaL_checkudata(L, 1, \"%s\");\n\n", data->name);
|
||||
|
||||
// fetch and check the singleton pointer
|
||||
fprintf(source, " %s *singleton = %s::get_singleton();", data->name, data->name);
|
||||
fprintf(source, " if (singleton == nullptr) {\n");
|
||||
fprintf(source, " return luaL_argerror(L, args, \"%s not supported on this firmware\");\n", data->name);
|
||||
fprintf(source, " }\n\n");
|
||||
|
||||
// extract the arguments
|
||||
arg = method->arguments;
|
||||
@ -806,22 +868,34 @@ void emit_singleton_method(const struct singleton *data, const struct method *me
|
||||
|
||||
switch (method->return_type.type) {
|
||||
case TYPE_BOOLEAN:
|
||||
fprintf(source, " const bool data = AP::%s()%s%s(\n", data->name, dereference, method->name);
|
||||
fprintf(source, " const bool data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, " const float data = AP::%s()%s%s(\n", data->name, dereference, method->name);
|
||||
fprintf(source, " const float data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
fprintf(source, " const int8_t data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_INT16_T:
|
||||
fprintf(source, " const int6_t data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_INT32_T:
|
||||
fprintf(source, " const int32_t data = AP::%s()%s%s(\n", data->name, dereference, method->name);
|
||||
fprintf(source, " const int32_t data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
fprintf(source, " const char * data = AP::%s()%s%s(\n", data->name, dereference, method->name);
|
||||
fprintf(source, " const char * data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_UINT8_T:
|
||||
fprintf(source, " const uint8_t data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_UINT16_T:
|
||||
fprintf(source, " const uint6_t data = singleton->%s(\n", method->name);
|
||||
break;
|
||||
case TYPE_USERDATA:
|
||||
fprintf(source, " const %s &data = AP::%s()%s%s(\n", method->return_type.data.userdata_name, data->name, dereference, method->name);
|
||||
fprintf(source, " const %s &data = singleton->%s(\n", method->return_type.data.userdata_name, method->name);
|
||||
break;
|
||||
case TYPE_NONE:
|
||||
fprintf(source, " AP::%s()%s%s(\n", data->name, dereference, method->name);
|
||||
fprintf(source, " singleton->%s(\n", method->name);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -845,7 +919,11 @@ void emit_singleton_method(const struct singleton *data, const struct method *me
|
||||
case TYPE_FLOAT:
|
||||
fprintf(source, " lua_pushnumber(L, data);\n");
|
||||
break;
|
||||
case TYPE_INT8_T:
|
||||
case TYPE_INT16_T:
|
||||
case TYPE_INT32_T:
|
||||
case TYPE_UINT8_T:
|
||||
case TYPE_UINT16_T:
|
||||
fprintf(source, " lua_pushinteger(L, data);\n");
|
||||
break;
|
||||
case TYPE_STRING:
|
||||
|
@ -1,5 +1,6 @@
|
||||
// auto generated bindings, don't manually edit
|
||||
#include "lua_generated_bindings.h"
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
@ -39,7 +40,7 @@ int Vector3f_z(lua_State *L) {
|
||||
lua_pushnumber(L, ud->z);
|
||||
return 1;
|
||||
case 2: {
|
||||
const float data_2 = luaL_checknumber(L, 2);
|
||||
const float data_2 = static_cast<float>(luaL_checknumber(L, 2));
|
||||
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "z out of range");
|
||||
ud->z = data_2;
|
||||
return 0;
|
||||
@ -56,7 +57,7 @@ int Vector3f_y(lua_State *L) {
|
||||
lua_pushnumber(L, ud->y);
|
||||
return 1;
|
||||
case 2: {
|
||||
const float data_2 = luaL_checknumber(L, 2);
|
||||
const float data_2 = static_cast<float>(luaL_checknumber(L, 2));
|
||||
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "y out of range");
|
||||
ud->y = data_2;
|
||||
return 0;
|
||||
@ -73,7 +74,7 @@ int Vector3f_x(lua_State *L) {
|
||||
lua_pushnumber(L, ud->x);
|
||||
return 1;
|
||||
case 2: {
|
||||
const float data_2 = luaL_checknumber(L, 2);
|
||||
const float data_2 = static_cast<float>(luaL_checknumber(L, 2));
|
||||
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "x out of range");
|
||||
ud->x = data_2;
|
||||
return 0;
|
||||
@ -90,7 +91,7 @@ int Location_loiter_xtrack(lua_State *L) {
|
||||
lua_pushinteger(L, ud->loiter_xtrack);
|
||||
return 1;
|
||||
case 2: {
|
||||
const bool data_2 = lua_toboolean(L, 2);
|
||||
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
|
||||
ud->loiter_xtrack = data_2;
|
||||
return 0;
|
||||
}
|
||||
@ -106,7 +107,7 @@ int Location_origin_alt(lua_State *L) {
|
||||
lua_pushinteger(L, ud->origin_alt);
|
||||
return 1;
|
||||
case 2: {
|
||||
const bool data_2 = lua_toboolean(L, 2);
|
||||
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
|
||||
ud->origin_alt = data_2;
|
||||
return 0;
|
||||
}
|
||||
@ -122,7 +123,7 @@ int Location_terrain_alt(lua_State *L) {
|
||||
lua_pushinteger(L, ud->terrain_alt);
|
||||
return 1;
|
||||
case 2: {
|
||||
const bool data_2 = lua_toboolean(L, 2);
|
||||
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
|
||||
ud->terrain_alt = data_2;
|
||||
return 0;
|
||||
}
|
||||
@ -138,7 +139,7 @@ int Location_relative_alt(lua_State *L) {
|
||||
lua_pushinteger(L, ud->relative_alt);
|
||||
return 1;
|
||||
case 2: {
|
||||
const bool data_2 = lua_toboolean(L, 2);
|
||||
const bool data_2 = static_cast<bool>(lua_toboolean(L, 2));
|
||||
ud->relative_alt = data_2;
|
||||
return 0;
|
||||
}
|
||||
@ -154,7 +155,7 @@ int Location_lng(lua_State *L) {
|
||||
lua_pushinteger(L, ud->lng);
|
||||
return 1;
|
||||
case 2: {
|
||||
const int32_t data_2 = luaL_checkinteger(L, 2);
|
||||
const int32_t data_2 = static_cast<int32_t>(luaL_checkinteger(L, 2));
|
||||
luaL_argcheck(L, ((data_2 >= -1800000000) && (data_2 <= 1800000000)), 2, "lng out of range");
|
||||
ud->lng = data_2;
|
||||
return 0;
|
||||
@ -171,7 +172,7 @@ int Location_lat(lua_State *L) {
|
||||
lua_pushinteger(L, ud->lat);
|
||||
return 1;
|
||||
case 2: {
|
||||
const int32_t data_2 = luaL_checkinteger(L, 2);
|
||||
const int32_t data_2 = static_cast<int32_t>(luaL_checkinteger(L, 2));
|
||||
luaL_argcheck(L, ((data_2 >= -900000000) && (data_2 <= 900000000)), 2, "lat out of range");
|
||||
ud->lat = data_2;
|
||||
return 0;
|
||||
@ -207,9 +208,9 @@ int Location_offset(lua_State *L) {
|
||||
}
|
||||
|
||||
Location * ud = check_Location(L, 1);
|
||||
const float data_2 = luaL_checknumber(L, 2);
|
||||
const float data_2 = static_cast<float>(luaL_checknumber(L, 2));
|
||||
luaL_argcheck(L, ((data_2 >= -FLT_MAX) && (data_2 <= FLT_MAX)), 2, "argument out of range");
|
||||
const float data_3 = luaL_checknumber(L, 3);
|
||||
const float data_3 = static_cast<float>(luaL_checknumber(L, 3));
|
||||
luaL_argcheck(L, ((data_3 >= -FLT_MAX) && (data_3 <= FLT_MAX)), 3, "argument out of range");
|
||||
ud->offset(
|
||||
data_2,
|
||||
@ -255,23 +256,7 @@ const luaL_Reg Location_meta[] = {
|
||||
{NULL, NULL}
|
||||
};
|
||||
|
||||
int notify_play_tune(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
if (args > 2) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
} else if (args < 2) {
|
||||
return luaL_argerror(L, args, "too few arguments");
|
||||
}
|
||||
|
||||
luaL_checkudata(L, 1, "notify");
|
||||
const char * data_2 = luaL_checkstring(L, 2);
|
||||
AP::notify().play_tune(
|
||||
data_2);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int ahrs_get_home(lua_State *L) {
|
||||
int RangeFinder_num_sensors(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
if (args > 1) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
@ -279,16 +264,20 @@ int ahrs_get_home(lua_State *L) {
|
||||
return luaL_argerror(L, args, "too few arguments");
|
||||
}
|
||||
|
||||
luaL_checkudata(L, 1, "ahrs");
|
||||
const Location &data = AP::ahrs().get_home(
|
||||
luaL_checkudata(L, 1, "RangeFinder");
|
||||
|
||||
RangeFinder *singleton = RangeFinder::get_singleton(); if (singleton == nullptr) {
|
||||
return luaL_argerror(L, args, "RangeFinder not supported on this firmware");
|
||||
}
|
||||
|
||||
const uint8_t data = singleton->num_sensors(
|
||||
);
|
||||
|
||||
new_Location(L);
|
||||
*check_Location(L, -1) = data;
|
||||
lua_pushinteger(L, data);
|
||||
return 1;
|
||||
}
|
||||
|
||||
int ahrs_get_position(lua_State *L) {
|
||||
int AP_Notify_play_tune(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
if (args > 2) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
@ -296,23 +285,76 @@ int ahrs_get_position(lua_State *L) {
|
||||
return luaL_argerror(L, args, "too few arguments");
|
||||
}
|
||||
|
||||
luaL_checkudata(L, 1, "ahrs");
|
||||
luaL_checkudata(L, 1, "AP_Notify");
|
||||
|
||||
AP_Notify *singleton = AP_Notify::get_singleton(); if (singleton == nullptr) {
|
||||
return luaL_argerror(L, args, "AP_Notify not supported on this firmware");
|
||||
}
|
||||
|
||||
const char * data_2 = luaL_checkstring(L, 2);
|
||||
singleton->play_tune(
|
||||
data_2);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int AP_AHRS_get_home(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
if (args > 1) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
} else if (args < 1) {
|
||||
return luaL_argerror(L, args, "too few arguments");
|
||||
}
|
||||
|
||||
luaL_checkudata(L, 1, "AP_AHRS");
|
||||
|
||||
AP_AHRS *singleton = AP_AHRS::get_singleton(); if (singleton == nullptr) {
|
||||
return luaL_argerror(L, args, "AP_AHRS not supported on this firmware");
|
||||
}
|
||||
|
||||
const Location &data = singleton->get_home(
|
||||
);
|
||||
|
||||
new_Location(L);
|
||||
*check_Location(L, -1) = data;
|
||||
return 1;
|
||||
}
|
||||
|
||||
int AP_AHRS_get_position(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
if (args > 2) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
} else if (args < 2) {
|
||||
return luaL_argerror(L, args, "too few arguments");
|
||||
}
|
||||
|
||||
luaL_checkudata(L, 1, "AP_AHRS");
|
||||
|
||||
AP_AHRS *singleton = AP_AHRS::get_singleton(); if (singleton == nullptr) {
|
||||
return luaL_argerror(L, args, "AP_AHRS not supported on this firmware");
|
||||
}
|
||||
|
||||
Location & data_2 = *check_Location(L, 2);
|
||||
const bool data = AP::ahrs().get_position(
|
||||
const bool data = singleton->get_position(
|
||||
data_2);
|
||||
|
||||
lua_pushboolean(L, data);
|
||||
return 1;
|
||||
}
|
||||
|
||||
const luaL_Reg notify_meta[] = {
|
||||
{"play_tune", notify_play_tune},
|
||||
const luaL_Reg RangeFinder_meta[] = {
|
||||
{"num_sensors", RangeFinder_num_sensors},
|
||||
{NULL, NULL}
|
||||
};
|
||||
|
||||
const luaL_Reg ahrs_meta[] = {
|
||||
{"get_home", ahrs_get_home},
|
||||
{"get_position", ahrs_get_position},
|
||||
const luaL_Reg AP_Notify_meta[] = {
|
||||
{"play_tune", AP_Notify_play_tune},
|
||||
{NULL, NULL}
|
||||
};
|
||||
|
||||
const luaL_Reg AP_AHRS_meta[] = {
|
||||
{"get_home", AP_AHRS_get_home},
|
||||
{"get_position", AP_AHRS_get_position},
|
||||
{NULL, NULL}
|
||||
};
|
||||
|
||||
@ -328,8 +370,9 @@ const struct singleton_fun {
|
||||
const char *name;
|
||||
const luaL_Reg *reg;
|
||||
} singleton_fun[] = {
|
||||
{"notify", notify_meta},
|
||||
{"ahrs", ahrs_meta},
|
||||
{"RangeFinder", RangeFinder_meta},
|
||||
{"AP_Notify", AP_Notify_meta},
|
||||
{"AP_AHRS", AP_AHRS_meta},
|
||||
};
|
||||
|
||||
void load_generated_bindings(lua_State *L) {
|
||||
@ -359,8 +402,9 @@ void load_generated_bindings(lua_State *L) {
|
||||
}
|
||||
|
||||
const char *singletons[] = {
|
||||
"notify",
|
||||
"ahrs",
|
||||
"RangeFinder",
|
||||
"AP_Notify",
|
||||
"AP_AHRS",
|
||||
};
|
||||
|
||||
const struct userdata {
|
||||
|
@ -1,5 +1,6 @@
|
||||
#pragma once
|
||||
// auto generated bindings, don't manually edit
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
Loading…
Reference in New Issue
Block a user