mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Tools: AION R1 default params use steering feed-forward
Also add wheel encoder defaults
This commit is contained in:
parent
368698d173
commit
7b0b9f10de
@ -9,8 +9,9 @@ ATC_SPEED_P,0.2
|
|||||||
ATC_SPEED_I,0.2
|
ATC_SPEED_I,0.2
|
||||||
ATC_SPEED_D,0.0
|
ATC_SPEED_D,0.0
|
||||||
ATC_SPEED_FILT,10
|
ATC_SPEED_FILT,10
|
||||||
ATC_STR_RAT_P,0.5
|
ATC_STR_RAT_FF,0.2
|
||||||
ATC_STR_RAT_I,0.6
|
ATC_STR_RAT_P,0.0
|
||||||
|
ATC_STR_RAT_I,0.1
|
||||||
ATC_STR_RAT_D,0.0
|
ATC_STR_RAT_D,0.0
|
||||||
ATC_STR_RAT_FILT,20
|
ATC_STR_RAT_FILT,20
|
||||||
AUX_CH,7
|
AUX_CH,7
|
||||||
@ -25,6 +26,7 @@ BATT_MONITOR,4
|
|||||||
BATT_SERIAL_NUM,-1
|
BATT_SERIAL_NUM,-1
|
||||||
BATT_VOLT_MULT,13.99818
|
BATT_VOLT_MULT,13.99818
|
||||||
BATT_VOLT_PIN,2
|
BATT_VOLT_PIN,2
|
||||||
|
BRD_PWM_COUNT,2
|
||||||
#default save waypoint
|
#default save waypoint
|
||||||
CH7_OPTION,1
|
CH7_OPTION,1
|
||||||
#default use only first (hopefully external) compass
|
#default use only first (hopefully external) compass
|
||||||
@ -59,19 +61,19 @@ SERVO3_MIN,1000
|
|||||||
SPEED_TURN_GAIN,50
|
SPEED_TURN_GAIN,50
|
||||||
TURN_MAX_G,0.3
|
TURN_MAX_G,0.3
|
||||||
TURN_RADIUS,0.9
|
TURN_RADIUS,0.9
|
||||||
WENC_CPR,3200
|
WENC_CPR,1120
|
||||||
WENC_PINA,55
|
WENC_PINA,55
|
||||||
WENC_PINB,54
|
WENC_PINB,54
|
||||||
WENC_POS_X,0
|
WENC_POS_X,-0.15
|
||||||
WENC_POS_Y,0
|
WENC_POS_Y,-0.16
|
||||||
WENC_POS_Z,0
|
WENC_POS_Z,0
|
||||||
WENC_RADIUS,0.078
|
WENC_RADIUS,0.0775
|
||||||
WENC_TYPE,0
|
WENC_TYPE,0
|
||||||
WENC2_CPR,3200
|
WENC2_CPR,1120
|
||||||
WENC2_PINA,53
|
WENC2_PINA,53
|
||||||
WENC2_PINB,52
|
WENC2_PINB,52
|
||||||
WENC2_POS_X,0
|
WENC2_POS_X,-0.15
|
||||||
WENC2_POS_Y,0
|
WENC2_POS_Y,0.16
|
||||||
WENC2_POS_Z,0
|
WENC2_POS_Z,0
|
||||||
WENC_RADIUS,0.078
|
WENC_RADIUS,0.0775
|
||||||
WENC2_TYPE,0
|
WENC2_TYPE,0
|
||||||
|
Loading…
Reference in New Issue
Block a user