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
This commit is contained in:
Andrew Tridgell 2017-09-18 10:24:45 +10:00
parent 35c1a732a6
commit 25c7ee4d42

View File

@ -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) {