mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: Added the new skid steering parameters file for SITL.
This commit is contained in:
parent
d993c25cb1
commit
2f7a386b30
36
Tools/autotest/Rover-skid.parm
Normal file
36
Tools/autotest/Rover-skid.parm
Normal file
@ -0,0 +1,36 @@
|
||||
SKID_STEER_OUT 1
|
||||
EK2_ENABLE 1
|
||||
WP_RADIUS 3
|
||||
LOG_BITMASK 65535
|
||||
MAG_ENABLE 1
|
||||
CRUISE_SPEED 5
|
||||
CRUISE_THROTTLE 30
|
||||
THR_MAX 100
|
||||
RC3_MAX 2000
|
||||
RC3_MIN 1000
|
||||
RC3_TRIM 1500
|
||||
RC1_MAX 2000
|
||||
RC1_MIN 1000
|
||||
RC1_TRIM 1500
|
||||
MODE1 0
|
||||
MODE2 0
|
||||
MODE3 11
|
||||
MODE4 10
|
||||
MODE5 2
|
||||
MODE6 0
|
||||
STEER2SRV_P 1.8
|
||||
SIM_GPS_DELAY 1
|
||||
NAVL1_PERIOD 6
|
||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
INS_ACCSCAL_X 1.001
|
||||
INS_ACCSCAL_Y 1.001
|
||||
INS_ACCSCAL_Z 1.001
|
||||
INS_ACC2OFFS_X 0.001
|
||||
INS_ACC2OFFS_Y 0.001
|
||||
INS_ACC2OFFS_Z 0.001
|
||||
INS_ACC2SCAL_X 1.001
|
||||
INS_ACC2SCAL_Y 1.001
|
||||
INS_ACC2SCAL_Z 1.001
|
Loading…
Reference in New Issue
Block a user