Browse Source

HAL_SITL: decrease wind with altitude

this prevents JSBSim crash on the runway
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
86afc26609
  1. 7
      libraries/AP_HAL_AVR_SITL/SITL_State.cpp

7
libraries/AP_HAL_AVR_SITL/SITL_State.cpp

@ -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;
// 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;
if (direction < 0) {
direction += 360;

Loading…
Cancel
Save