mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Cope with new AP_GPS::first_unconfigured_gps
This commit is contained in:
parent
4b2cb45ac0
commit
1677c11855
|
@ -77,8 +77,7 @@ 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 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 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 get_antenna_offset Vector3f uint8_t 0 ud->num_sensors()
|
||||||
singleton AP_GPS method all_configured boolean
|
singleton AP_GPS method first_unconfigured_gps boolean uint8_t'Null
|
||||||
singleton AP_GPS method first_unconfigured_gps uint8_t
|
|
||||||
|
|
||||||
include AP_Math/AP_Math.h
|
include AP_Math/AP_Math.h
|
||||||
|
|
||||||
|
|
|
@ -700,22 +700,15 @@ static int AP_GPS_first_unconfigured_gps(lua_State *L) {
|
||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->first_unconfigured_gps();
|
uint8_t data_5002 = {};
|
||||||
|
const bool data = ud->first_unconfigured_gps(
|
||||||
|
data_5002);
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
if (data) {
|
||||||
return 1;
|
lua_pushinteger(L, data_5002);
|
||||||
}
|
} else {
|
||||||
|
lua_pushnil(L);
|
||||||
static int AP_GPS_all_configured(lua_State *L) {
|
|
||||||
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();
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1582,7 +1575,6 @@ const luaL_Reg notify_meta[] = {
|
||||||
|
|
||||||
const luaL_Reg AP_GPS_meta[] = {
|
const luaL_Reg AP_GPS_meta[] = {
|
||||||
{"first_unconfigured_gps", AP_GPS_first_unconfigured_gps},
|
{"first_unconfigured_gps", AP_GPS_first_unconfigured_gps},
|
||||||
{"all_configured", AP_GPS_all_configured},
|
|
||||||
{"get_antenna_offset", AP_GPS_get_antenna_offset},
|
{"get_antenna_offset", AP_GPS_get_antenna_offset},
|
||||||
{"have_vertical_velocity", AP_GPS_have_vertical_velocity},
|
{"have_vertical_velocity", AP_GPS_have_vertical_velocity},
|
||||||
{"last_message_time_ms", AP_GPS_last_message_time_ms},
|
{"last_message_time_ms", AP_GPS_last_message_time_ms},
|
||||||
|
|
Loading…
Reference in New Issue