mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Tools: add arduroller balance bot parameter defaults
This commit is contained in:
parent
c028aa8dad
commit
31bfedafa2
67
Tools/Frame_params/ArduRoller-balancebot.param
Normal file
67
Tools/Frame_params/ArduRoller-balancebot.param
Normal file
@ -0,0 +1,67 @@
|
||||
#NOTE: ArduRoller balance bot parameters for Rover-3.5 and higher
|
||||
ACRO_TURN_RATE,90
|
||||
AHRS_ORIENTATION,29
|
||||
ATC_ACCEL_MAX,1
|
||||
ATC_BAL_D,0.01
|
||||
ATC_BAL_FF,0
|
||||
ATC_BAL_FILT,0
|
||||
ATC_BAL_I,7
|
||||
ATC_BAL_IMAX,1
|
||||
ATC_BAL_P,1.2
|
||||
ATC_BAL_SPD_FF,1.1
|
||||
ATC_BRAKE,1
|
||||
ATC_STR_ACC_MAX,180
|
||||
BAL_PITCH_MAX,10
|
||||
BRD_PWM_COUNT,0
|
||||
CRASH_ANGLE,45
|
||||
CRUISE_SPEED,0.4
|
||||
CRUISE_THROTTLE,50
|
||||
FRAME_CLASS,3
|
||||
FS_CRASH_CHECK,1
|
||||
MOT_PWM_TYPE,0
|
||||
MOT_SLEWRATE,0
|
||||
MOT_THR_MIN,6
|
||||
MOT_THST_EXPO,-0.5
|
||||
RELAY_PIN,-1
|
||||
RELAY_PIN2,-1
|
||||
SCHED_LOOP_RATE,200
|
||||
SERVO1_FUNCTION,73
|
||||
SERVO1_MAX,2000
|
||||
SERVO1_MIN,1000
|
||||
SERVO1_REVERSED,0
|
||||
SERVO1_TRIM,1500
|
||||
SERVO3_FUNCTION,74
|
||||
SERVO3_MAX,2000
|
||||
SERVO3_MIN,1000
|
||||
SERVO3_REVERSED,1
|
||||
SERVO3_TRIM,1500
|
||||
TURN_MAX_G,0.2
|
||||
WENC_CPR,3200
|
||||
WENC_PINA,55
|
||||
WENC_PINB,54
|
||||
WENC_POS_X,0
|
||||
WENC_POS_Y,-0.1
|
||||
WENC_POS_Z,0
|
||||
WENC_RADIUS,0.05
|
||||
WENC_TYPE,1
|
||||
WENC2_CPR,3200
|
||||
WENC2_PINA,53
|
||||
WENC2_PINB,52
|
||||
WENC2_POS_X,0
|
||||
WENC2_POS_Y,0.1
|
||||
WENC2_POS_Z,0
|
||||
WENC2_RADIUS,0.05
|
||||
WENC2_TYPE,1
|
||||
WRC_RATE_D,0.01
|
||||
WRC_RATE_FF,8
|
||||
WRC_RATE_FILT,50
|
||||
WRC_RATE_I,2
|
||||
WRC_RATE_IMAX,1
|
||||
WRC_RATE_MAX,12
|
||||
WRC_RATE_P,2
|
||||
WRC2_RATE_D,0.01
|
||||
WRC2_RATE_FF,8
|
||||
WRC2_RATE_FILT,50
|
||||
WRC2_RATE_I,2
|
||||
WRC2_RATE_IMAX,1
|
||||
WRC2_RATE_P,2
|
Loading…
Reference in New Issue
Block a user