Skip to content
Snippets Groups Projects
Commit a15e4633 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

SITL: prevent wind effects at negative altitudes

this prevents crashes on takeoff with barometer noise
parent e7d73aa8
No related branches found
No related tags found
No related merge requests found
...@@ -495,6 +495,9 @@ void SITL_State::_simulator_output(void) ...@@ -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;
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment