SITL: reduce max accel of simulated rover

This commit is contained in:
Peter Barker 2017-08-14 20:06:07 +10:00
parent efefdfa037
commit 62f7acff52
1 changed files with 1 additions and 1 deletions

View File

@ -26,7 +26,7 @@ namespace SITL {
SimRover::SimRover(const char *home_str, const char *frame_str) :
Aircraft(home_str, frame_str),
max_speed(20),
max_accel(30),
max_accel(10),
max_wheel_turn(35),
turning_circle(1.8),
skid_turn_rate(140), // degrees/sec