mirror of https://github.com/ArduPilot/ardupilot
add Aerofox AYK320 drone param config file
This commit is contained in:
parent
a76ab91cbb
commit
f44df3cbf1
|
@ -0,0 +1,110 @@
|
|||
# parameters for Foxtech AYK320
|
||||
|
||||
# airspeed
|
||||
ARSPD_FBW_MAX 35
|
||||
ARSPD_FBW_MIN 18
|
||||
TRIM_ARSPD_CM 2300
|
||||
TRIM_THROTTLE 60
|
||||
|
||||
# notch filter
|
||||
INS_HNTCH_ENABLE 1
|
||||
INS_HNTCH_ATT 50.000000
|
||||
INS_HNTCH_BW 38.000000
|
||||
INS_HNTCH_ENABLE 1.000000
|
||||
INS_HNTCH_FREQ 75.000000
|
||||
INS_HNTCH_HMNCS 15.000000
|
||||
INS_HNTCH_MODE 1.000000
|
||||
INS_HNTCH_REF 0.337000
|
||||
|
||||
# fixed wing limits
|
||||
LIM_PITCH_MIN -2000
|
||||
LIM_ROLL_CD 4000
|
||||
LEVEL_ROLL_LIMIT 12
|
||||
|
||||
FBWB_CLIMB_RATE 5
|
||||
WP_LOITER_RAD 250
|
||||
WP_RADIUS 200
|
||||
RTL_RADIUS 200
|
||||
|
||||
# fixed wing tune
|
||||
RLL2SRV_RMAX 75
|
||||
RLL_RATE_D 0.009886
|
||||
RLL_RATE_FF 0.442834
|
||||
RLL_RATE_FLTD 12.5
|
||||
RLL_RATE_FLTT 3.183099
|
||||
RLL_RATE_I 0.442834
|
||||
RLL_RATE_P 0.385863
|
||||
RLL_RATE_SMAX 100
|
||||
|
||||
PTCH2SRV_RMAX_DN 75
|
||||
PTCH2SRV_RMAX_UP 75
|
||||
PTCH2SRV_TCONST 0.75
|
||||
PTCH_RATE_D 0.027
|
||||
PTCH_RATE_FF 1.835124
|
||||
PTCH_RATE_FLTD 12.5
|
||||
PTCH_RATE_FLTT 2.122066
|
||||
PTCH_RATE_I 1.835124
|
||||
PTCH_RATE_P 1.113065
|
||||
PTCH_RATE_SMAX 100
|
||||
|
||||
# quadplane parameters
|
||||
Q_ENABLE 1
|
||||
Q_FRAME_CLASS 1
|
||||
Q_FRAME_TYPE 1
|
||||
Q_ANGLE_MAX 1500
|
||||
Q_ASSIST_ANGLE 30
|
||||
Q_ASSIST_SPEED 15
|
||||
Q_A_ACCEL_P_MAX 30000
|
||||
Q_A_ACCEL_R_MAX 30000
|
||||
Q_A_ACCEL_Y_MAX 9000
|
||||
Q_A_ANG_PIT_P 3
|
||||
Q_A_ANG_RLL_P 3
|
||||
Q_A_ANG_YAW_P 3
|
||||
Q_A_RATE_P_MAX 60
|
||||
Q_A_RATE_R_MAX 60
|
||||
Q_A_RATE_Y_MAX 60
|
||||
Q_A_RAT_PIT_D 0.005523
|
||||
Q_A_RAT_PIT_FLTD 12.5
|
||||
Q_A_RAT_PIT_FLTT 12.5
|
||||
Q_A_RAT_PIT_I 0.198349
|
||||
Q_A_RAT_PIT_P 0.198349
|
||||
Q_A_RAT_RLL_D 0.003301
|
||||
Q_A_RAT_RLL_FLTD 12.5
|
||||
Q_A_RAT_RLL_FLTT 12.5
|
||||
Q_A_RAT_RLL_I 0.233438
|
||||
Q_A_RAT_RLL_P 0.233438
|
||||
Q_A_RAT_YAW_D 0.01
|
||||
Q_A_RAT_YAW_FLTD 12.5
|
||||
Q_A_RAT_YAW_FLTE 2
|
||||
Q_A_RAT_YAW_FLTT 12.5
|
||||
Q_A_RAT_YAW_P 1
|
||||
Q_A_SLEW_YAW 3000
|
||||
Q_LAND_FINAL_ALT 12
|
||||
Q_LAND_SPEED 40
|
||||
Q_M_BAT_IDX 1
|
||||
Q_M_BAT_VOLT_MAX 50.4
|
||||
Q_M_BAT_VOLT_MIN 40
|
||||
Q_M_THST_HOVER 0.338
|
||||
|
||||
# soften VTOL position controller
|
||||
Q_P_POSXY_P 0.5
|
||||
Q_P_VELXY_D 0.17
|
||||
Q_P_VELXY_I 0.35
|
||||
Q_P_VELXY_P 0.7
|
||||
|
||||
Q_RTL_ALT 40
|
||||
Q_TRANS_DECEL 1.5
|
||||
Q_TRANS_FAIL 20
|
||||
Q_VELZ_MAX 200
|
||||
Q_VELZ_MAX_DN 130
|
||||
Q_VFWD_ALT 6
|
||||
Q_VFWD_GAIN 0.05
|
||||
Q_WVANE_GAIN 0.3
|
||||
Q_WVANE_TAKEOFF 0
|
||||
|
||||
# servo setup
|
||||
SERVO1_REVERSED 1
|
||||
SERVO2_FUNCTION 79
|
||||
SERVO2_REVERSED 1
|
||||
SERVO4_FUNCTION 80
|
||||
SERVO_AUTO_TRIM 1
|
Loading…
Reference in New Issue