mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tools: arduroller balance bot param update
This commit is contained in:
parent
0697ce19d2
commit
e0ce8035b9
@ -1,19 +1,19 @@
|
|||||||
#NOTE: ArduRoller balance bot parameters for Rover-3.5 and higher
|
#NOTE: ArduRoller balance bot parameters for Rover-4.3 and higher
|
||||||
ACRO_TURN_RATE,90
|
ACRO_TURN_RATE,90
|
||||||
AHRS_ORIENTATION,29
|
AHRS_ORIENTATION,29
|
||||||
ATC_ACCEL_MAX,1
|
ATC_ACCEL_MAX,5
|
||||||
ATC_BAL_D,0.01
|
ATC_BAL_D,0.18
|
||||||
ATC_BAL_FF,0
|
ATC_BAL_FF,0
|
||||||
|
ATC_BAL_FLTD,0
|
||||||
ATC_BAL_FILT,0
|
ATC_BAL_FILT,0
|
||||||
ATC_BAL_FLTE,0
|
ATC_BAL_FLTE,0
|
||||||
ATC_BAL_I,7
|
ATC_BAL_I,7
|
||||||
ATC_BAL_IMAX,1
|
ATC_BAL_IMAX,1
|
||||||
ATC_BAL_P,1.2
|
ATC_BAL_P,5
|
||||||
ATC_BAL_SPD_FF,1.1
|
ATC_BAL_SPD_FF,1.0
|
||||||
ATC_BRAKE,1
|
ATC_BRAKE,1
|
||||||
ATC_STR_ACC_MAX,180
|
ATC_STR_ACC_MAX,120
|
||||||
BAL_PITCH_MAX,10
|
BAL_PITCH_MAX,10
|
||||||
BRD_PWM_COUNT,0
|
|
||||||
CRASH_ANGLE,45
|
CRASH_ANGLE,45
|
||||||
CRUISE_SPEED,0.4
|
CRUISE_SPEED,0.4
|
||||||
CRUISE_THROTTLE,50
|
CRUISE_THROTTLE,50
|
||||||
@ -36,33 +36,37 @@ SERVO3_MAX,2000
|
|||||||
SERVO3_MIN,1000
|
SERVO3_MIN,1000
|
||||||
SERVO3_REVERSED,1
|
SERVO3_REVERSED,1
|
||||||
SERVO3_TRIM,1500
|
SERVO3_TRIM,1500
|
||||||
|
SERVO11_FUNCTION,-1
|
||||||
|
SERVO12_FUNCTION,-1
|
||||||
|
SERVO13_FUNCTION,-1
|
||||||
|
SERVO14_FUNCTION,-1
|
||||||
ATC_TURN_MAX_G,0.2
|
ATC_TURN_MAX_G,0.2
|
||||||
WENC_CPR,3200
|
WENC_CPR,1600
|
||||||
WENC_PINA,55
|
WENC_PINA,55
|
||||||
WENC_PINB,54
|
WENC_PINB,54
|
||||||
WENC_POS_X,0
|
WENC_POS_X,0
|
||||||
WENC_POS_Y,-0.1
|
WENC_POS_Y,-0.1
|
||||||
WENC_POS_Z,0
|
WENC_POS_Z,0
|
||||||
WENC_RADIUS,0.05
|
WENC_RADIUS,0.06
|
||||||
WENC_TYPE,1
|
WENC_TYPE,1
|
||||||
WENC2_CPR,3200
|
WENC2_CPR,1600
|
||||||
WENC2_PINA,53
|
WENC2_PINA,53
|
||||||
WENC2_PINB,52
|
WENC2_PINB,52
|
||||||
WENC2_POS_X,0
|
WENC2_POS_X,0
|
||||||
WENC2_POS_Y,0.1
|
WENC2_POS_Y,0.1
|
||||||
WENC2_POS_Z,0
|
WENC2_POS_Z,0
|
||||||
WENC2_RADIUS,0.05
|
WENC2_RADIUS,0.06
|
||||||
WENC2_TYPE,1
|
WENC2_TYPE,1
|
||||||
WRC_RATE_D,0.01
|
WRC_RATE_D,0.2
|
||||||
WRC_RATE_FF,8
|
WRC_RATE_FF,4.2
|
||||||
WRC_RATE_FILT,50
|
WRC_RATE_FLTD,50
|
||||||
WRC_RATE_I,2
|
WRC_RATE_I,4
|
||||||
WRC_RATE_IMAX,1
|
WRC_RATE_IMAX,1
|
||||||
WRC_RATE_MAX,12
|
WRC_RATE_MAX,12
|
||||||
WRC_RATE_P,2
|
WRC_RATE_P,0
|
||||||
WRC2_RATE_D,0.01
|
WRC2_RATE_D,0.2
|
||||||
WRC2_RATE_FF,8
|
WRC2_RATE_FF,4.2
|
||||||
WRC2_RATE_FILT,50
|
WRC2_RATE_FLTD,50
|
||||||
WRC2_RATE_I,2
|
WRC2_RATE_I,4
|
||||||
WRC2_RATE_IMAX,1
|
WRC2_RATE_IMAX,1
|
||||||
WRC2_RATE_P,2
|
WRC2_RATE_P,0
|
||||||
|
Loading…
Reference in New Issue
Block a user