AP_Scripting: Tighten range checks on library calls
This commit is contained in:
parent
bb677756a0
commit
104164d2e4
@ -32,42 +32,42 @@ include AP_BattMonitor/AP_BattMonitor.h
|
||||
|
||||
singleton AP_BattMonitor alias battery
|
||||
singleton AP_BattMonitor method num_instances uint8_t
|
||||
singleton AP_BattMonitor method healthy boolean uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method has_consumed_energy boolean uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method has_current boolean uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method voltage float uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method voltage_resting_estimate float uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method current_amps float uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method consumed_mah float uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method consumed_wh float uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method capacity_remaining_pct uint8_t uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method pack_capacity_mah int32_t uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method healthy boolean uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method has_consumed_energy boolean uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method has_current boolean uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method voltage float uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method voltage_resting_estimate float uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method current_amps float uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method consumed_mah float uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method consumed_wh float uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method capacity_remaining_pct uint8_t uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method pack_capacity_mah int32_t uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method has_failsafed boolean
|
||||
singleton AP_BattMonitor method overpower_detected boolean uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method get_temperature boolean float'Null uint8_t 0 AP_BATT_MONITOR_MAX_INSTANCES
|
||||
singleton AP_BattMonitor method overpower_detected boolean uint8_t 0 ud->num_instances()
|
||||
singleton AP_BattMonitor method get_temperature boolean float'Null uint8_t 0 ud->num_instances()
|
||||
|
||||
include AP_GPS/AP_GPS.h
|
||||
|
||||
singleton AP_GPS alias gps
|
||||
singleton AP_GPS method num_sensors uint8_t
|
||||
singleton AP_GPS method primary_sensor uint8_t
|
||||
singleton AP_GPS method status uint8_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method location Location uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method speed_accuracy boolean uint8_t 0 GPS_MAX_INSTANCES float'Null
|
||||
singleton AP_GPS method horizontal_accuracy boolean uint8_t 0 GPS_MAX_INSTANCES float'Null
|
||||
singleton AP_GPS method vertical_accuracy boolean uint8_t 0 GPS_MAX_INSTANCES float'Null
|
||||
singleton AP_GPS method velocity Vector3f uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method ground_speed float uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method ground_course float uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method num_sats uint8_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method time_week uint16_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method time_week_ms uint32_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method get_hdop uint16_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method get_vdop uint16_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method last_fix_time_ms uint32_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method last_message_time_ms uint32_t uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method have_vertical_velocity boolean uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method get_antenna_offset Vector3f uint8_t 0 GPS_MAX_INSTANCES
|
||||
singleton AP_GPS method status uint8_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method location Location uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method speed_accuracy boolean uint8_t 0 ud->num_sensors() float'Null
|
||||
singleton AP_GPS method horizontal_accuracy boolean uint8_t 0 ud->num_sensors() float'Null
|
||||
singleton AP_GPS method vertical_accuracy boolean uint8_t 0 ud->num_sensors() float'Null
|
||||
singleton AP_GPS method velocity Vector3f uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method ground_speed float uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method ground_course float uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method num_sats uint8_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method time_week uint16_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method time_week_ms uint32_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method get_hdop uint16_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method get_vdop uint16_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method last_fix_time_ms uint32_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method last_message_time_ms uint32_t uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method have_vertical_velocity boolean uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method get_antenna_offset Vector3f uint8_t 0 ud->num_sensors()
|
||||
singleton AP_GPS method all_configured boolean
|
||||
singleton AP_GPS method first_unconfigured_gps uint8_t
|
||||
|
||||
|
@ -1028,7 +1028,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||
int arg_count = 1;
|
||||
|
||||
const char *access_name = data->alias ? data->alias : data->name;
|
||||
|
||||
// bind ud early if it's a singleton, so that we can use it in the range checks
|
||||
fprintf(source, "static int %s_%s(lua_State *L) {\n", data->name, method->name);
|
||||
// emit comments on expected arg/type
|
||||
struct argument *arg = method->arguments;
|
||||
@ -1038,6 +1038,15 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||
arg->line_num, arg->token_num);
|
||||
arg = arg->next;
|
||||
}
|
||||
|
||||
if (data->ud_type == UD_SINGLETON) {
|
||||
// fetch and check the singleton pointer
|
||||
fprintf(source, " %s * ud = %s::get_singleton();\n", data->name, data->name);
|
||||
fprintf(source, " if (ud == nullptr) {\n");
|
||||
fprintf(source, " return luaL_argerror(L, %d, \"%s not supported on this firmware\");\n", arg_count, access_name);
|
||||
fprintf(source, " }\n\n");
|
||||
}
|
||||
|
||||
// sanity check number of args called with
|
||||
arg = method->arguments;
|
||||
arg_count = 1;
|
||||
@ -1055,11 +1064,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
||||
fprintf(source, " %s * ud = check_%s(L, 1);\n", data->name, data->name);
|
||||
break;
|
||||
case UD_SINGLETON:
|
||||
// fetch and check the singleton pointer
|
||||
fprintf(source, " %s * ud = %s::get_singleton();\n", data->name, data->name);
|
||||
fprintf(source, " if (ud == nullptr) {\n");
|
||||
fprintf(source, " return luaL_argerror(L, %d, \"%s not supported on this firmware\");\n", arg_count, access_name);
|
||||
fprintf(source, " }\n\n");
|
||||
// this was bound early
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -476,12 +476,12 @@ const luaL_Reg Location_meta[] = {
|
||||
static int GCS_send_text(lua_State *L) {
|
||||
// 1 MAV_SEVERITY 126 : 8
|
||||
// 2 enum 126 : 9
|
||||
binding_argcheck(L, 3);
|
||||
GCS * ud = GCS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 3, "gcs 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 >= MAV_SEVERITY_EMERGENCY) && (raw_data_2 <= MAV_SEVERITY_DEBUG)), 2, "argument out of range");
|
||||
const MAV_SEVERITY data_2 = static_cast<MAV_SEVERITY>(raw_data_2);
|
||||
@ -495,12 +495,12 @@ static int GCS_send_text(lua_State *L) {
|
||||
|
||||
static int AP_Relay_toggle(lua_State *L) {
|
||||
// 1 uint8_t 122 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_Relay * ud = AP_Relay::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "relay 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(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
@ -512,12 +512,12 @@ static int AP_Relay_toggle(lua_State *L) {
|
||||
|
||||
static int AP_Relay_enabled(lua_State *L) {
|
||||
// 1 uint8_t 121 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_Relay * ud = AP_Relay::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "relay 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(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
@ -530,12 +530,12 @@ static int AP_Relay_enabled(lua_State *L) {
|
||||
|
||||
static int AP_Relay_off(lua_State *L) {
|
||||
// 1 uint8_t 120 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_Relay * ud = AP_Relay::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "relay 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(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
@ -547,12 +547,12 @@ static int AP_Relay_off(lua_State *L) {
|
||||
|
||||
static int AP_Relay_on(lua_State *L) {
|
||||
// 1 uint8_t 119 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_Relay * ud = AP_Relay::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "relay 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(AP_RELAY_NUM_RELAYS, UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
@ -565,12 +565,12 @@ static int AP_Relay_on(lua_State *L) {
|
||||
static int AP_Terrain_height_above_terrain(lua_State *L) {
|
||||
// 1 float 114 : 6
|
||||
// 2 bool 114 : 7
|
||||
binding_argcheck(L, 2);
|
||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "terrain not supported on this firmware");
|
||||
return luaL_argerror(L, 3, "terrain not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 2);
|
||||
float data_5002 = {};
|
||||
const bool data_3 = static_cast<bool>(lua_toboolean(L, 3));
|
||||
const bool data = ud->height_above_terrain(
|
||||
@ -589,12 +589,12 @@ static int AP_Terrain_height_relative_home_equivalent(lua_State *L) {
|
||||
// 1 float 113 : 8
|
||||
// 2 float 113 : 9
|
||||
// 3 bool 113 : 10
|
||||
binding_argcheck(L, 3);
|
||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 3, "terrain not supported on this firmware");
|
||||
return luaL_argerror(L, 4, "terrain not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 3);
|
||||
const float raw_data_2 = luaL_checknumber(L, 2);
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(-FLT_MAX, -INFINITY)) && (raw_data_2 <= MIN(FLT_MAX, INFINITY))), 2, "argument out of range");
|
||||
const float data_2 = raw_data_2;
|
||||
@ -616,12 +616,12 @@ static int AP_Terrain_height_relative_home_equivalent(lua_State *L) {
|
||||
static int AP_Terrain_height_terrain_difference_home(lua_State *L) {
|
||||
// 1 float 112 : 6
|
||||
// 2 bool 112 : 7
|
||||
binding_argcheck(L, 2);
|
||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "terrain not supported on this firmware");
|
||||
return luaL_argerror(L, 3, "terrain not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 2);
|
||||
float data_5002 = {};
|
||||
const bool data_3 = static_cast<bool>(lua_toboolean(L, 3));
|
||||
const bool data = ud->height_terrain_difference_home(
|
||||
@ -640,12 +640,12 @@ static int AP_Terrain_height_amsl(lua_State *L) {
|
||||
// 1 Location 111 : 6
|
||||
// 2 float 111 : 7
|
||||
// 3 bool 111 : 8
|
||||
binding_argcheck(L, 3);
|
||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 3, "terrain not supported on this firmware");
|
||||
return luaL_argerror(L, 4, "terrain not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 3);
|
||||
Location & data_2 = *check_Location(L, 2);
|
||||
float data_5003 = {};
|
||||
const bool data_4 = static_cast<bool>(lua_toboolean(L, 4));
|
||||
@ -663,12 +663,12 @@ static int AP_Terrain_height_amsl(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_Terrain_status(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "terrain not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const uint8_t data = ud->status(
|
||||
);
|
||||
|
||||
@ -677,12 +677,12 @@ static int AP_Terrain_status(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_Terrain_enabled(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_Terrain * ud = AP_Terrain::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "terrain not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const bool data = ud->enabled(
|
||||
);
|
||||
|
||||
@ -691,12 +691,12 @@ static int AP_Terrain_enabled(lua_State *L) {
|
||||
}
|
||||
|
||||
static int RangeFinder_num_sensors(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
RangeFinder * ud = RangeFinder::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "rangefinder not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const uint8_t data = ud->num_sensors(
|
||||
);
|
||||
|
||||
@ -706,12 +706,12 @@ static int RangeFinder_num_sensors(lua_State *L) {
|
||||
|
||||
static int AP_Notify_play_tune(lua_State *L) {
|
||||
// 1 enum 99 : 6
|
||||
binding_argcheck(L, 2);
|
||||
AP_Notify * ud = AP_Notify::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "AP_Notify not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 2);
|
||||
const char * data_2 = luaL_checkstring(L, 2);
|
||||
ud->play_tune(
|
||||
data_2);
|
||||
@ -720,12 +720,12 @@ static int AP_Notify_play_tune(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_GPS_first_unconfigured_gps(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const uint8_t data = ud->first_unconfigured_gps(
|
||||
);
|
||||
|
||||
@ -734,12 +734,12 @@ static int AP_GPS_first_unconfigured_gps(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_GPS_all_configured(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const bool data = ud->all_configured(
|
||||
);
|
||||
|
||||
@ -749,14 +749,14 @@ static int AP_GPS_all_configured(lua_State *L) {
|
||||
|
||||
static int AP_GPS_get_antenna_offset(lua_State *L) {
|
||||
// 1 uint8_t 70 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const Vector3f &data = ud->get_antenna_offset(
|
||||
data_2);
|
||||
@ -768,14 +768,14 @@ static int AP_GPS_get_antenna_offset(lua_State *L) {
|
||||
|
||||
static int AP_GPS_have_vertical_velocity(lua_State *L) {
|
||||
// 1 uint8_t 69 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const bool data = ud->have_vertical_velocity(
|
||||
data_2);
|
||||
@ -786,14 +786,14 @@ static int AP_GPS_have_vertical_velocity(lua_State *L) {
|
||||
|
||||
static int AP_GPS_last_message_time_ms(lua_State *L) {
|
||||
// 1 uint8_t 68 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint32_t data = ud->last_message_time_ms(
|
||||
data_2);
|
||||
@ -805,14 +805,14 @@ static int AP_GPS_last_message_time_ms(lua_State *L) {
|
||||
|
||||
static int AP_GPS_last_fix_time_ms(lua_State *L) {
|
||||
// 1 uint8_t 67 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint32_t data = ud->last_fix_time_ms(
|
||||
data_2);
|
||||
@ -824,14 +824,14 @@ static int AP_GPS_last_fix_time_ms(lua_State *L) {
|
||||
|
||||
static int AP_GPS_get_vdop(lua_State *L) {
|
||||
// 1 uint8_t 66 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint16_t data = ud->get_vdop(
|
||||
data_2);
|
||||
@ -842,14 +842,14 @@ static int AP_GPS_get_vdop(lua_State *L) {
|
||||
|
||||
static int AP_GPS_get_hdop(lua_State *L) {
|
||||
// 1 uint8_t 65 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint16_t data = ud->get_hdop(
|
||||
data_2);
|
||||
@ -860,14 +860,14 @@ static int AP_GPS_get_hdop(lua_State *L) {
|
||||
|
||||
static int AP_GPS_time_week_ms(lua_State *L) {
|
||||
// 1 uint8_t 64 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint32_t data = ud->time_week_ms(
|
||||
data_2);
|
||||
@ -879,14 +879,14 @@ static int AP_GPS_time_week_ms(lua_State *L) {
|
||||
|
||||
static int AP_GPS_time_week(lua_State *L) {
|
||||
// 1 uint8_t 63 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint16_t data = ud->time_week(
|
||||
data_2);
|
||||
@ -897,14 +897,14 @@ static int AP_GPS_time_week(lua_State *L) {
|
||||
|
||||
static int AP_GPS_num_sats(lua_State *L) {
|
||||
// 1 uint8_t 62 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint8_t data = ud->num_sats(
|
||||
data_2);
|
||||
@ -915,14 +915,14 @@ static int AP_GPS_num_sats(lua_State *L) {
|
||||
|
||||
static int AP_GPS_ground_course(lua_State *L) {
|
||||
// 1 uint8_t 61 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->ground_course(
|
||||
data_2);
|
||||
@ -933,14 +933,14 @@ static int AP_GPS_ground_course(lua_State *L) {
|
||||
|
||||
static int AP_GPS_ground_speed(lua_State *L) {
|
||||
// 1 uint8_t 60 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->ground_speed(
|
||||
data_2);
|
||||
@ -951,14 +951,14 @@ static int AP_GPS_ground_speed(lua_State *L) {
|
||||
|
||||
static int AP_GPS_velocity(lua_State *L) {
|
||||
// 1 uint8_t 59 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const Vector3f &data = ud->velocity(
|
||||
data_2);
|
||||
@ -971,14 +971,14 @@ static int AP_GPS_velocity(lua_State *L) {
|
||||
static int AP_GPS_vertical_accuracy(lua_State *L) {
|
||||
// 1 uint8_t 58 : 8
|
||||
// 2 float 58 : 9
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
||||
return luaL_argerror(L, 3, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
float data_5003 = {};
|
||||
const bool data = ud->vertical_accuracy(
|
||||
@ -996,14 +996,14 @@ static int AP_GPS_vertical_accuracy(lua_State *L) {
|
||||
static int AP_GPS_horizontal_accuracy(lua_State *L) {
|
||||
// 1 uint8_t 57 : 8
|
||||
// 2 float 57 : 9
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
||||
return luaL_argerror(L, 3, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
float data_5003 = {};
|
||||
const bool data = ud->horizontal_accuracy(
|
||||
@ -1021,14 +1021,14 @@ static int AP_GPS_horizontal_accuracy(lua_State *L) {
|
||||
static int AP_GPS_speed_accuracy(lua_State *L) {
|
||||
// 1 uint8_t 56 : 8
|
||||
// 2 float 56 : 9
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps not supported on this firmware");
|
||||
return luaL_argerror(L, 3, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
float data_5003 = {};
|
||||
const bool data = ud->speed_accuracy(
|
||||
@ -1045,14 +1045,14 @@ static int AP_GPS_speed_accuracy(lua_State *L) {
|
||||
|
||||
static int AP_GPS_location(lua_State *L) {
|
||||
// 1 uint8_t 55 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const Location &data = ud->location(
|
||||
data_2);
|
||||
@ -1064,14 +1064,14 @@ static int AP_GPS_location(lua_State *L) {
|
||||
|
||||
static int AP_GPS_status(lua_State *L) {
|
||||
// 1 uint8_t 54 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "gps 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(GPS_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_sensors(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint8_t data = ud->status(
|
||||
data_2);
|
||||
@ -1081,12 +1081,12 @@ static int AP_GPS_status(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_GPS_primary_sensor(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const uint8_t data = ud->primary_sensor(
|
||||
);
|
||||
|
||||
@ -1095,12 +1095,12 @@ static int AP_GPS_primary_sensor(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_GPS_num_sensors(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_GPS * ud = AP_GPS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "gps not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const uint8_t data = ud->num_sensors(
|
||||
);
|
||||
|
||||
@ -1111,15 +1111,15 @@ static int AP_GPS_num_sensors(lua_State *L) {
|
||||
static int AP_BattMonitor_get_temperature(lua_State *L) {
|
||||
// 1 float 47 : 6
|
||||
// 2 uint8_t 47 : 9
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery not supported on this firmware");
|
||||
return luaL_argerror(L, 3, "battery not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 2);
|
||||
float data_5002 = {};
|
||||
const lua_Integer raw_data_3 = luaL_checkinteger(L, 3);
|
||||
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 3, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_3 >= MAX(0, 0)) && (raw_data_3 <= MIN(ud->num_instances(), UINT8_MAX))), 3, "argument out of range");
|
||||
const uint8_t data_3 = static_cast<uint8_t>(raw_data_3);
|
||||
const bool data = ud->get_temperature(
|
||||
data_5002,
|
||||
@ -1135,14 +1135,14 @@ static int AP_BattMonitor_get_temperature(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_overpower_detected(lua_State *L) {
|
||||
// 1 uint8_t 46 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const bool data = ud->overpower_detected(
|
||||
data_2);
|
||||
@ -1152,12 +1152,12 @@ static int AP_BattMonitor_overpower_detected(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_BattMonitor_has_failsafed(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const bool data = ud->has_failsafed(
|
||||
);
|
||||
|
||||
@ -1167,14 +1167,14 @@ static int AP_BattMonitor_has_failsafed(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_pack_capacity_mah(lua_State *L) {
|
||||
// 1 uint8_t 44 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const int32_t data = ud->pack_capacity_mah(
|
||||
data_2);
|
||||
@ -1185,14 +1185,14 @@ static int AP_BattMonitor_pack_capacity_mah(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) {
|
||||
// 1 uint8_t 43 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const uint8_t data = ud->capacity_remaining_pct(
|
||||
data_2);
|
||||
@ -1203,14 +1203,14 @@ static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_consumed_wh(lua_State *L) {
|
||||
// 1 uint8_t 42 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->consumed_wh(
|
||||
data_2);
|
||||
@ -1221,14 +1221,14 @@ static int AP_BattMonitor_consumed_wh(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_consumed_mah(lua_State *L) {
|
||||
// 1 uint8_t 41 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->consumed_mah(
|
||||
data_2);
|
||||
@ -1239,14 +1239,14 @@ static int AP_BattMonitor_consumed_mah(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_current_amps(lua_State *L) {
|
||||
// 1 uint8_t 40 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->current_amps(
|
||||
data_2);
|
||||
@ -1257,14 +1257,14 @@ static int AP_BattMonitor_current_amps(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) {
|
||||
// 1 uint8_t 39 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->voltage_resting_estimate(
|
||||
data_2);
|
||||
@ -1275,14 +1275,14 @@ static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_voltage(lua_State *L) {
|
||||
// 1 uint8_t 38 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const float data = ud->voltage(
|
||||
data_2);
|
||||
@ -1293,14 +1293,14 @@ static int AP_BattMonitor_voltage(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_has_current(lua_State *L) {
|
||||
// 1 uint8_t 37 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const bool data = ud->has_current(
|
||||
data_2);
|
||||
@ -1311,14 +1311,14 @@ static int AP_BattMonitor_has_current(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_has_consumed_energy(lua_State *L) {
|
||||
// 1 uint8_t 36 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const bool data = ud->has_consumed_energy(
|
||||
data_2);
|
||||
@ -1329,14 +1329,14 @@ static int AP_BattMonitor_has_consumed_energy(lua_State *L) {
|
||||
|
||||
static int AP_BattMonitor_healthy(lua_State *L) {
|
||||
// 1 uint8_t 35 : 8
|
||||
binding_argcheck(L, 2);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 2, "battery 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(AP_BATT_MONITOR_MAX_INSTANCES, UINT8_MAX))), 2, "argument out of range");
|
||||
luaL_argcheck(L, ((raw_data_2 >= MAX(0, 0)) && (raw_data_2 <= MIN(ud->num_instances(), UINT8_MAX))), 2, "argument out of range");
|
||||
const uint8_t data_2 = static_cast<uint8_t>(raw_data_2);
|
||||
const bool data = ud->healthy(
|
||||
data_2);
|
||||
@ -1346,12 +1346,12 @@ static int AP_BattMonitor_healthy(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_BattMonitor_num_instances(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_BattMonitor * ud = AP_BattMonitor::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "battery not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
const uint8_t data = ud->num_instances(
|
||||
);
|
||||
|
||||
@ -1360,12 +1360,12 @@ static int AP_BattMonitor_num_instances(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_AHRS_prearm_healthy(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
ud->get_semaphore().take_blocking();
|
||||
const bool data = ud->prearm_healthy(
|
||||
);
|
||||
@ -1376,12 +1376,12 @@ static int AP_AHRS_prearm_healthy(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_AHRS_home_is_set(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
ud->get_semaphore().take_blocking();
|
||||
const bool data = ud->home_is_set(
|
||||
);
|
||||
@ -1393,12 +1393,12 @@ static int AP_AHRS_home_is_set(lua_State *L) {
|
||||
|
||||
static int AP_AHRS_get_relative_position_NED_home(lua_State *L) {
|
||||
// 1 Vector3f 27 : 6
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
Vector3f data_5002 = {};
|
||||
ud->get_semaphore().take_blocking();
|
||||
const bool data = ud->get_relative_position_NED_home(
|
||||
@ -1416,12 +1416,12 @@ static int AP_AHRS_get_relative_position_NED_home(lua_State *L) {
|
||||
|
||||
static int AP_AHRS_get_velocity_NED(lua_State *L) {
|
||||
// 1 Vector3f 26 : 6
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
Vector3f data_5002 = {};
|
||||
ud->get_semaphore().take_blocking();
|
||||
const bool data = ud->get_velocity_NED(
|
||||
@ -1438,12 +1438,12 @@ static int AP_AHRS_get_velocity_NED(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_AHRS_groundspeed_vector(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
ud->get_semaphore().take_blocking();
|
||||
const Vector2f &data = ud->groundspeed_vector(
|
||||
);
|
||||
@ -1455,12 +1455,12 @@ static int AP_AHRS_groundspeed_vector(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_AHRS_wind_estimate(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
ud->get_semaphore().take_blocking();
|
||||
const Vector3f &data = ud->wind_estimate(
|
||||
);
|
||||
@ -1473,12 +1473,12 @@ static int AP_AHRS_wind_estimate(lua_State *L) {
|
||||
|
||||
static int AP_AHRS_get_hagl(lua_State *L) {
|
||||
// 1 float 23 : 6
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
float data_5002 = {};
|
||||
ud->get_semaphore().take_blocking();
|
||||
const bool data = ud->get_hagl(
|
||||
@ -1494,12 +1494,12 @@ static int AP_AHRS_get_hagl(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_AHRS_get_gyro(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
ud->get_semaphore().take_blocking();
|
||||
const Vector3f &data = ud->get_gyro(
|
||||
);
|
||||
@ -1511,12 +1511,12 @@ static int AP_AHRS_get_gyro(lua_State *L) {
|
||||
}
|
||||
|
||||
static int AP_AHRS_get_home(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
ud->get_semaphore().take_blocking();
|
||||
const Location &data = ud->get_home(
|
||||
);
|
||||
@ -1529,12 +1529,12 @@ static int AP_AHRS_get_home(lua_State *L) {
|
||||
|
||||
static int AP_AHRS_get_position(lua_State *L) {
|
||||
// 1 Location 20 : 6
|
||||
binding_argcheck(L, 1);
|
||||
AP_AHRS * ud = AP_AHRS::get_singleton();
|
||||
if (ud == nullptr) {
|
||||
return luaL_argerror(L, 1, "ahrs not supported on this firmware");
|
||||
return luaL_argerror(L, 2, "ahrs not supported on this firmware");
|
||||
}
|
||||
|
||||
binding_argcheck(L, 1);
|
||||
Location data_5002 = {};
|
||||
ud->get_semaphore().take_blocking();
|
||||
const bool data = ud->get_position(
|
||||
|
Loading…
Reference in New Issue
Block a user