Browse Source

SITL: prevent wind effects at negative altitudes

this prevents crashes on takeoff with barometer noise
master
Andrew Tridgell 11 years ago
parent
commit
a15e4633b7
  1. 3
      libraries/AP_HAL_AVR_SITL/SITL_State.cpp

3
libraries/AP_HAL_AVR_SITL/SITL_State.cpp

@ -495,6 +495,9 @@ void SITL_State::_simulator_output(void)
// setup wind control // setup wind control
float wind_speed = _sitl->wind_speed * 100; float wind_speed = _sitl->wind_speed * 100;
float altitude = _barometer?_barometer->get_altitude():0; float altitude = _barometer?_barometer->get_altitude():0;
if (altitude < 0) {
altitude = 0;
}
if (altitude < 60) { if (altitude < 60) {
wind_speed *= altitude / 60.0f; wind_speed *= altitude / 60.0f;
} }

Loading…
Cancel
Save