SITL: raise default simulation rate to 1200Hz

this greatly improves things for the heli sim
This commit is contained in:
Andrew Tridgell 2015-09-01 16:30:57 +10:00
parent ee91a41405
commit a3d7156f28

View File

@ -48,7 +48,7 @@ Aircraft::Aircraft(const char *home_str, const char *frame_str) :
time_now_us(0),
gyro_noise(radians(0.1f)),
accel_noise(0.3),
rate_hz(400),
rate_hz(1200),
autotest_dir(NULL),
frame(frame_str),
#ifdef __CYGWIN__