From 25c7ee4d4225974ed469e2c2ebbc0031d6cf3a53 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Sep 2017 10:24:45 +1000 Subject: [PATCH] AP_HAL_SITL: added SIM_GPS_ALT_OFS this is used to give a bad GPS height in SITL, which is very useful for testing origin vs home issues --- libraries/AP_HAL_SITL/sitl_gps.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_SITL/sitl_gps.cpp b/libraries/AP_HAL_SITL/sitl_gps.cpp index 1900c4ce2b..d9235d1d28 100644 --- a/libraries/AP_HAL_SITL/sitl_gps.cpp +++ b/libraries/AP_HAL_SITL/sitl_gps.cpp @@ -1126,6 +1126,8 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude, if (AP_HAL::millis() < _sitl->gps_lock_time*1000UL) { have_lock = false; } + + altitude += _sitl->gps_alt_offset; //Capture current position as basestation location for if (!_gps_has_basestation_position) {