diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index e9dad34fdf..251e3942d6 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -508,6 +508,11 @@ void SITL_State::set_height_agl(void) { static float home_alt = -1; + if (!_sitl) { + // in example program + return; + } + if (is_equal(home_alt, -1.0f) && _sitl->state.altitude > 0) { // remember home altitude as first non-zero altitude home_alt = _sitl->state.altitude;