mirror of https://github.com/ArduPilot/ardupilot
Tools: add default params for rover-vectored
Co-authored-by: srmainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
30a08dda0a
commit
d00e63d14b
|
@ -0,0 +1,11 @@
|
|||
ACRO_TURN_RATE 90
|
||||
ATC_STR_ACC_MAX 60
|
||||
ATC_STR_RAT_FF 0.65
|
||||
ATC_STR_RAT_I 0.30
|
||||
ATC_STR_RAT_P 0.30
|
||||
ATC_STR_RAT_MAX 90
|
||||
ATC_ACCEL_MAX 1
|
||||
CRUISE_SPEED 10
|
||||
CRUISE_THROTTLE 50
|
||||
MOT_VEC_ANGLEMAX 90
|
||||
WP_SPEED 10
|
Loading…
Reference in New Issue