mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Remove unneeded debug output, fix the index for singleton errors
This commit is contained in:
parent
b3c6d3d75a
commit
ed584313bd
|
@ -1031,12 +1031,6 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||||
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, method->name);
|
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, method->name);
|
||||||
// emit comments on expected arg/type
|
// emit comments on expected arg/type
|
||||||
struct argument *arg = method->arguments;
|
struct argument *arg = method->arguments;
|
||||||
while (arg != NULL) {
|
|
||||||
fprintf(source, " // %d %s %d : %d\n", arg_count++, arg->type.type == TYPE_USERDATA ? arg->type.data.userdata_name :
|
|
||||||
arg->type.type == TYPE_ENUM ? arg->type.data.enum_name : type_labels[arg->type.type],
|
|
||||||
arg->line_num, arg->token_num);
|
|
||||||
arg = arg->next;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (data->ud_type == UD_SINGLETON) {
|
if (data->ud_type == UD_SINGLETON) {
|
||||||
// fetch and check the singleton pointer
|
// fetch and check the singleton pointer
|
||||||
|
@ -1047,7 +1041,6 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||||
}
|
}
|
||||||
|
|
||||||
// sanity check number of args called with
|
// sanity check number of args called with
|
||||||
arg = method->arguments;
|
|
||||||
arg_count = 1;
|
arg_count = 1;
|
||||||
while (arg != NULL) {
|
while (arg != NULL) {
|
||||||
if (!(arg->type.flags & TYPE_FLAGS_NULLABLE)) {
|
if (!(arg->type.flags & TYPE_FLAGS_NULLABLE)) {
|
||||||
|
|
|
@ -387,7 +387,6 @@ static int Vector3f___sub(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int Location_get_vector_from_origin_NEU(lua_State *L) {
|
static int Location_get_vector_from_origin_NEU(lua_State *L) {
|
||||||
// 1 Vector3f 14 : 6
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Location * ud = check_Location(L, 1);
|
Location * ud = check_Location(L, 1);
|
||||||
Vector3f data_5002 = {};
|
Vector3f data_5002 = {};
|
||||||
|
@ -404,8 +403,6 @@ static int Location_get_vector_from_origin_NEU(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int Location_offset(lua_State *L) {
|
static int Location_offset(lua_State *L) {
|
||||||
// 1 float 13 : 8
|
|
||||||
// 2 float 13 : 11
|
|
||||||
binding_argcheck(L, 3);
|
binding_argcheck(L, 3);
|
||||||
Location * ud = check_Location(L, 1);
|
Location * ud = check_Location(L, 1);
|
||||||
const float raw_data_2 = luaL_checknumber(L, 2);
|
const float raw_data_2 = luaL_checknumber(L, 2);
|
||||||
|
@ -422,7 +419,6 @@ static int Location_offset(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int Location_get_distance(lua_State *L) {
|
static int Location_get_distance(lua_State *L) {
|
||||||
// 1 Location 12 : 6
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
Location * ud = check_Location(L, 1);
|
Location * ud = check_Location(L, 1);
|
||||||
Location & data_2 = *check_Location(L, 2);
|
Location & data_2 = *check_Location(L, 2);
|
||||||
|
@ -474,11 +470,9 @@ const luaL_Reg Location_meta[] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static int GCS_send_text(lua_State *L) {
|
static int GCS_send_text(lua_State *L) {
|
||||||
// 1 MAV_SEVERITY 127 : 8
|
|
||||||
// 2 enum 127 : 9
|
|
||||||
GCS * ud = GCS::get_singleton();
|
GCS * ud = GCS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "gcs not supported on this firmware");
|
return luaL_argerror(L, 1, "gcs not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 3);
|
binding_argcheck(L, 3);
|
||||||
|
@ -494,10 +488,9 @@ static int GCS_send_text(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Relay_toggle(lua_State *L) {
|
static int AP_Relay_toggle(lua_State *L) {
|
||||||
// 1 uint8_t 123 : 8
|
|
||||||
AP_Relay * ud = AP_Relay::get_singleton();
|
AP_Relay * ud = AP_Relay::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "relay not supported on this firmware");
|
return luaL_argerror(L, 1, "relay not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -511,10 +504,9 @@ static int AP_Relay_toggle(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Relay_enabled(lua_State *L) {
|
static int AP_Relay_enabled(lua_State *L) {
|
||||||
// 1 uint8_t 122 : 8
|
|
||||||
AP_Relay * ud = AP_Relay::get_singleton();
|
AP_Relay * ud = AP_Relay::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "relay not supported on this firmware");
|
return luaL_argerror(L, 1, "relay not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -529,10 +521,9 @@ static int AP_Relay_enabled(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Relay_off(lua_State *L) {
|
static int AP_Relay_off(lua_State *L) {
|
||||||
// 1 uint8_t 121 : 8
|
|
||||||
AP_Relay * ud = AP_Relay::get_singleton();
|
AP_Relay * ud = AP_Relay::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "relay not supported on this firmware");
|
return luaL_argerror(L, 1, "relay not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -546,10 +537,9 @@ static int AP_Relay_off(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Relay_on(lua_State *L) {
|
static int AP_Relay_on(lua_State *L) {
|
||||||
// 1 uint8_t 120 : 8
|
|
||||||
AP_Relay * ud = AP_Relay::get_singleton();
|
AP_Relay * ud = AP_Relay::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "relay not supported on this firmware");
|
return luaL_argerror(L, 1, "relay not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -563,11 +553,9 @@ static int AP_Relay_on(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Terrain_height_above_terrain(lua_State *L) {
|
static int AP_Terrain_height_above_terrain(lua_State *L) {
|
||||||
// 1 float 115 : 6
|
|
||||||
// 2 bool 115 : 7
|
|
||||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "terrain not supported on this firmware");
|
return luaL_argerror(L, 1, "terrain not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -586,12 +574,9 @@ static int AP_Terrain_height_above_terrain(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Terrain_height_relative_home_equivalent(lua_State *L) {
|
static int AP_Terrain_height_relative_home_equivalent(lua_State *L) {
|
||||||
// 1 float 114 : 8
|
|
||||||
// 2 float 114 : 9
|
|
||||||
// 3 bool 114 : 10
|
|
||||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 4, "terrain not supported on this firmware");
|
return luaL_argerror(L, 1, "terrain not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 3);
|
binding_argcheck(L, 3);
|
||||||
|
@ -614,11 +599,9 @@ static int AP_Terrain_height_relative_home_equivalent(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Terrain_height_terrain_difference_home(lua_State *L) {
|
static int AP_Terrain_height_terrain_difference_home(lua_State *L) {
|
||||||
// 1 float 113 : 6
|
|
||||||
// 2 bool 113 : 7
|
|
||||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "terrain not supported on this firmware");
|
return luaL_argerror(L, 1, "terrain not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -637,12 +620,9 @@ static int AP_Terrain_height_terrain_difference_home(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Terrain_height_amsl(lua_State *L) {
|
static int AP_Terrain_height_amsl(lua_State *L) {
|
||||||
// 1 Location 112 : 6
|
|
||||||
// 2 float 112 : 7
|
|
||||||
// 3 bool 112 : 8
|
|
||||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 4, "terrain not supported on this firmware");
|
return luaL_argerror(L, 1, "terrain not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 3);
|
binding_argcheck(L, 3);
|
||||||
|
@ -705,10 +685,9 @@ static int RangeFinder_num_sensors(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_Notify_play_tune(lua_State *L) {
|
static int AP_Notify_play_tune(lua_State *L) {
|
||||||
// 1 enum 100 : 6
|
|
||||||
AP_Notify * ud = AP_Notify::get_singleton();
|
AP_Notify * ud = AP_Notify::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "AP_Notify not supported on this firmware");
|
return luaL_argerror(L, 1, "AP_Notify not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -748,10 +727,9 @@ static int AP_GPS_all_configured(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_get_antenna_offset(lua_State *L) {
|
static int AP_GPS_get_antenna_offset(lua_State *L) {
|
||||||
// 1 uint8_t 71 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -767,10 +745,9 @@ static int AP_GPS_get_antenna_offset(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_have_vertical_velocity(lua_State *L) {
|
static int AP_GPS_have_vertical_velocity(lua_State *L) {
|
||||||
// 1 uint8_t 70 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -785,10 +762,9 @@ static int AP_GPS_have_vertical_velocity(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_last_message_time_ms(lua_State *L) {
|
static int AP_GPS_last_message_time_ms(lua_State *L) {
|
||||||
// 1 uint8_t 69 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -804,10 +780,9 @@ static int AP_GPS_last_message_time_ms(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_last_fix_time_ms(lua_State *L) {
|
static int AP_GPS_last_fix_time_ms(lua_State *L) {
|
||||||
// 1 uint8_t 68 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -823,10 +798,9 @@ static int AP_GPS_last_fix_time_ms(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_get_vdop(lua_State *L) {
|
static int AP_GPS_get_vdop(lua_State *L) {
|
||||||
// 1 uint8_t 67 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -841,10 +815,9 @@ static int AP_GPS_get_vdop(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_get_hdop(lua_State *L) {
|
static int AP_GPS_get_hdop(lua_State *L) {
|
||||||
// 1 uint8_t 66 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -859,10 +832,9 @@ static int AP_GPS_get_hdop(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_time_week_ms(lua_State *L) {
|
static int AP_GPS_time_week_ms(lua_State *L) {
|
||||||
// 1 uint8_t 65 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -878,10 +850,9 @@ static int AP_GPS_time_week_ms(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_time_week(lua_State *L) {
|
static int AP_GPS_time_week(lua_State *L) {
|
||||||
// 1 uint8_t 64 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -896,10 +867,9 @@ static int AP_GPS_time_week(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_num_sats(lua_State *L) {
|
static int AP_GPS_num_sats(lua_State *L) {
|
||||||
// 1 uint8_t 63 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -914,10 +884,9 @@ static int AP_GPS_num_sats(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_ground_course(lua_State *L) {
|
static int AP_GPS_ground_course(lua_State *L) {
|
||||||
// 1 uint8_t 62 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -932,10 +901,9 @@ static int AP_GPS_ground_course(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_ground_speed(lua_State *L) {
|
static int AP_GPS_ground_speed(lua_State *L) {
|
||||||
// 1 uint8_t 61 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -950,10 +918,9 @@ static int AP_GPS_ground_speed(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_velocity(lua_State *L) {
|
static int AP_GPS_velocity(lua_State *L) {
|
||||||
// 1 uint8_t 60 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -969,11 +936,9 @@ static int AP_GPS_velocity(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_vertical_accuracy(lua_State *L) {
|
static int AP_GPS_vertical_accuracy(lua_State *L) {
|
||||||
// 1 uint8_t 59 : 8
|
|
||||||
// 2 float 59 : 9
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -994,11 +959,9 @@ static int AP_GPS_vertical_accuracy(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_horizontal_accuracy(lua_State *L) {
|
static int AP_GPS_horizontal_accuracy(lua_State *L) {
|
||||||
// 1 uint8_t 58 : 8
|
|
||||||
// 2 float 58 : 9
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1019,11 +982,9 @@ static int AP_GPS_horizontal_accuracy(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_speed_accuracy(lua_State *L) {
|
static int AP_GPS_speed_accuracy(lua_State *L) {
|
||||||
// 1 uint8_t 57 : 8
|
|
||||||
// 2 float 57 : 9
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1044,10 +1005,9 @@ static int AP_GPS_speed_accuracy(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_location(lua_State *L) {
|
static int AP_GPS_location(lua_State *L) {
|
||||||
// 1 uint8_t 56 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1063,10 +1023,9 @@ static int AP_GPS_location(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_GPS_status(lua_State *L) {
|
static int AP_GPS_status(lua_State *L) {
|
||||||
// 1 uint8_t 55 : 8
|
|
||||||
AP_GPS * ud = AP_GPS::get_singleton();
|
AP_GPS * ud = AP_GPS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1109,11 +1068,9 @@ static int AP_GPS_num_sensors(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_get_temperature(lua_State *L) {
|
static int AP_BattMonitor_get_temperature(lua_State *L) {
|
||||||
// 1 float 48 : 6
|
|
||||||
// 2 uint8_t 48 : 9
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1134,10 +1091,9 @@ static int AP_BattMonitor_get_temperature(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_overpower_detected(lua_State *L) {
|
static int AP_BattMonitor_overpower_detected(lua_State *L) {
|
||||||
// 1 uint8_t 47 : 8
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1166,10 +1122,9 @@ static int AP_BattMonitor_has_failsafed(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_pack_capacity_mah(lua_State *L) {
|
static int AP_BattMonitor_pack_capacity_mah(lua_State *L) {
|
||||||
// 1 uint8_t 45 : 8
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1184,10 +1139,9 @@ static int AP_BattMonitor_pack_capacity_mah(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) {
|
static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) {
|
||||||
// 1 uint8_t 44 : 8
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1202,11 +1156,9 @@ static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_consumed_wh(lua_State *L) {
|
static int AP_BattMonitor_consumed_wh(lua_State *L) {
|
||||||
// 1 float 43 : 6
|
|
||||||
// 2 uint8_t 43 : 9
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1227,11 +1179,9 @@ static int AP_BattMonitor_consumed_wh(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_consumed_mah(lua_State *L) {
|
static int AP_BattMonitor_consumed_mah(lua_State *L) {
|
||||||
// 1 float 42 : 6
|
|
||||||
// 2 uint8_t 42 : 9
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1252,11 +1202,9 @@ static int AP_BattMonitor_consumed_mah(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_current_amps(lua_State *L) {
|
static int AP_BattMonitor_current_amps(lua_State *L) {
|
||||||
// 1 float 41 : 6
|
|
||||||
// 2 uint8_t 41 : 9
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 3, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1277,10 +1225,9 @@ static int AP_BattMonitor_current_amps(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) {
|
static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) {
|
||||||
// 1 uint8_t 40 : 8
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1295,10 +1242,9 @@ static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_voltage(lua_State *L) {
|
static int AP_BattMonitor_voltage(lua_State *L) {
|
||||||
// 1 uint8_t 39 : 8
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1313,10 +1259,9 @@ static int AP_BattMonitor_voltage(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_BattMonitor_healthy(lua_State *L) {
|
static int AP_BattMonitor_healthy(lua_State *L) {
|
||||||
// 1 uint8_t 38 : 8
|
|
||||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 2);
|
binding_argcheck(L, 2);
|
||||||
|
@ -1377,10 +1322,9 @@ static int AP_AHRS_home_is_set(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_AHRS_get_relative_position_NED_home(lua_State *L) {
|
static int AP_AHRS_get_relative_position_NED_home(lua_State *L) {
|
||||||
// 1 Vector3f 30 : 6
|
|
||||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
|
@ -1400,10 +1344,9 @@ static int AP_AHRS_get_relative_position_NED_home(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_AHRS_get_velocity_NED(lua_State *L) {
|
static int AP_AHRS_get_velocity_NED(lua_State *L) {
|
||||||
// 1 Vector3f 29 : 6
|
|
||||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
|
@ -1457,10 +1400,9 @@ static int AP_AHRS_wind_estimate(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_AHRS_get_hagl(lua_State *L) {
|
static int AP_AHRS_get_hagl(lua_State *L) {
|
||||||
// 1 float 26 : 6
|
|
||||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
|
@ -1513,10 +1455,9 @@ static int AP_AHRS_get_home(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
static int AP_AHRS_get_position(lua_State *L) {
|
static int AP_AHRS_get_position(lua_State *L) {
|
||||||
// 1 Location 23 : 6
|
|
||||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||||
if (ud == nullptr) {
|
if (ud == nullptr) {
|
||||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
|
|
Loading…
Reference in New Issue