mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
SITL: don't enable wind until we are off the ground
this makes it possible to test with much larger wind speeds, without the sim crashing due to the wind flipping us over on the runway
This commit is contained in:
parent
7a77832f45
commit
e54e3f813d
@ -257,7 +257,9 @@ def main_loop():
|
|||||||
paused = False
|
paused = False
|
||||||
jsb_console.send('resume\n')
|
jsb_console.send('resume\n')
|
||||||
|
|
||||||
if tnow - last_wind_update > 0.1:
|
# only simulate wind above 5 meters, to prevent crashes while
|
||||||
|
# waiting for takeoff
|
||||||
|
if tnow - last_wind_update > 0.1 and fdm.get('agl', units='meters') > 2:
|
||||||
update_wind(wind)
|
update_wind(wind)
|
||||||
last_wind_update = tnow
|
last_wind_update = tnow
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user