HAL_SITL: decrease wind with altitude

this prevents JSBSim crash on the runway
This commit is contained in:
Andrew Tridgell 2013-10-16 14:11:51 +11:00
parent 2e75d5dec3
commit 86afc26609
1 changed files with 6 additions and 1 deletions

View File

@ -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;