Browse Source

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
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
25c7ee4d42
  1. 2
      libraries/AP_HAL_SITL/sitl_gps.cpp

2
libraries/AP_HAL_SITL/sitl_gps.cpp

@ -1126,6 +1126,8 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude, @@ -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) {

Loading…
Cancel
Save