mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
SITL: raise default simulation rate to 1200Hz
this greatly improves things for the heli sim
This commit is contained in:
parent
ee91a41405
commit
a3d7156f28
@ -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__
|
||||
|
Loading…
Reference in New Issue
Block a user