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

HAL_SITL: decrease wind with altitude

this prevents JSBSim crash on the runway
parent 2e75d5de
No related branches found
No related tags found
No related merge requests found
...@@ -490,7 +490,12 @@ void SITL_State::_simulator_output(void) ...@@ -490,7 +490,12 @@ void SITL_State::_simulator_output(void)
current_pin_value = ((current / 17.0) / 5.0) * 1024; current_pin_value = ((current / 17.0) / 5.0) * 1024;
// setup wind control // setup wind control
control.speed = _sitl->wind_speed * 100; float wind_speed = _sitl->wind_speed * 100;
float altitude = _barometer?_barometer->get_altitude():0;
if (altitude < 60) {
wind_speed *= altitude / 60.0f;
}
control.speed = wind_speed;
float direction = _sitl->wind_direction; float direction = _sitl->wind_direction;
if (direction < 0) { if (direction < 0) {
direction += 360; direction += 360;
......
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