mirror of https://github.com/ArduPilot/ardupilot
Tools: added frame parameters for two quadplanes
This commit is contained in:
parent
6eaf2c545a
commit
8c1c948e24
|
@ -0,0 +1,111 @@
|
||||||
|
# MakeFlyEasy Striver Mini Parameters
|
||||||
|
|
||||||
|
# http://en.makeflyeasy.com/index.php/striver-mini-vtol/
|
||||||
|
|
||||||
|
SCALING_SPEED 15
|
||||||
|
TECS_CLMB_MAX 3
|
||||||
|
TECS_LAND_ARSPD 20
|
||||||
|
TKOFF_THR_MAX 85
|
||||||
|
TRIM_PITCH_CD 100
|
||||||
|
TRIM_THROTTLE 40
|
||||||
|
WP_LOITER_RAD 120
|
||||||
|
WP_RADIUS 110
|
||||||
|
|
||||||
|
# harmonic notch filter
|
||||||
|
INS_HNTCH_ENABLE 1
|
||||||
|
INS_HNTCH_ATT 60
|
||||||
|
INS_HNTCH_BW 34
|
||||||
|
INS_HNTCH_FREQ 68
|
||||||
|
INS_HNTCH_HMNCS 15
|
||||||
|
INS_HNTCH_MODE 1
|
||||||
|
INS_HNTCH_REF 0.26
|
||||||
|
|
||||||
|
# airspeed
|
||||||
|
TRIM_ARSPD_CM 2300
|
||||||
|
ARSPD_FBW_MAX 30
|
||||||
|
ARSPD_FBW_MIN 15
|
||||||
|
|
||||||
|
# limits
|
||||||
|
LIM_PITCH_MAX 2000
|
||||||
|
LIM_PITCH_MIN -2000
|
||||||
|
LIM_ROLL_CD 5500
|
||||||
|
|
||||||
|
# pitch tuning
|
||||||
|
PTCH_RATE_D 0.017718
|
||||||
|
PTCH_RATE_FF 0.600786
|
||||||
|
PTCH_RATE_FLTD 15
|
||||||
|
PTCH_RATE_FLTT 2.122066
|
||||||
|
PTCH_RATE_I 0.600786
|
||||||
|
PTCH_RATE_IMAX 0.666000
|
||||||
|
PTCH_RATE_P 0.716340
|
||||||
|
PTCH_RATE_SMAX 100
|
||||||
|
|
||||||
|
# roll tuning
|
||||||
|
RLL_RATE_D 0.003669
|
||||||
|
RLL_RATE_FF 0.435239
|
||||||
|
RLL_RATE_FLTD 15
|
||||||
|
RLL_RATE_FLTT 3.183099
|
||||||
|
RLL_RATE_I 0.435239
|
||||||
|
RLL_RATE_IMAX 0.666000
|
||||||
|
RLL_RATE_P 0.228321
|
||||||
|
RLL_RATE_SMAX 100
|
||||||
|
|
||||||
|
# quadplane parameters
|
||||||
|
Q_ENABLE 1
|
||||||
|
Q_ANGLE_MAX 2000
|
||||||
|
Q_ASSIST_SPEED 13
|
||||||
|
Q_A_ACCEL_P_MAX 70000
|
||||||
|
Q_A_ACCEL_R_MAX 70000
|
||||||
|
Q_A_ACCEL_Y_MAX 20000
|
||||||
|
Q_A_ANG_PIT_P 5.500000
|
||||||
|
Q_A_ANG_RLL_P 6
|
||||||
|
Q_A_ANG_YAW_P 3
|
||||||
|
Q_A_RATE_P_MAX 75
|
||||||
|
Q_A_RATE_R_MAX 75
|
||||||
|
Q_A_RATE_Y_MAX 75
|
||||||
|
Q_A_RAT_PIT_D 0.004961
|
||||||
|
Q_A_RAT_PIT_FF 0
|
||||||
|
Q_A_RAT_PIT_FLTD 15
|
||||||
|
Q_A_RAT_PIT_FLTT 15
|
||||||
|
Q_A_RAT_PIT_I 0.257666
|
||||||
|
Q_A_RAT_PIT_IMAX 0.500000
|
||||||
|
Q_A_RAT_PIT_P 0.257666
|
||||||
|
Q_A_RAT_PIT_SMAX 20
|
||||||
|
Q_A_RAT_RLL_D 0.001420
|
||||||
|
Q_A_RAT_RLL_FF 0
|
||||||
|
Q_A_RAT_RLL_FLTD 15
|
||||||
|
Q_A_RAT_RLL_FLTT 15
|
||||||
|
Q_A_RAT_RLL_I 0.198000
|
||||||
|
Q_A_RAT_RLL_IMAX 0.500000
|
||||||
|
Q_A_RAT_RLL_P 0.198000
|
||||||
|
Q_A_RAT_RLL_SMAX 20
|
||||||
|
Q_A_RAT_YAW_D 0.003001
|
||||||
|
Q_A_RAT_YAW_FF 0
|
||||||
|
Q_A_RAT_YAW_FLTD 15
|
||||||
|
Q_A_RAT_YAW_FLTE 2
|
||||||
|
Q_A_RAT_YAW_FLTT 15
|
||||||
|
Q_A_RAT_YAW_I 0.015000
|
||||||
|
Q_A_RAT_YAW_IMAX 0.500000
|
||||||
|
Q_A_RAT_YAW_P 0.150000
|
||||||
|
Q_A_RAT_YAW_SMAX 20
|
||||||
|
Q_A_THR_MIX_MAN 0.500000
|
||||||
|
Q_A_THR_MIX_MAX 0.850000
|
||||||
|
Q_A_THR_MIX_MIN 0.400000
|
||||||
|
Q_FRAME_CLASS 1
|
||||||
|
Q_FRAME_TYPE 1
|
||||||
|
Q_M_BAT_IDX 0
|
||||||
|
Q_M_BAT_VOLT_MAX 25.200001
|
||||||
|
Q_M_BAT_VOLT_MIN 19.200001
|
||||||
|
Q_M_THST_EXPO 0.650000
|
||||||
|
Q_M_THST_HOVER 0.247719
|
||||||
|
Q_RTL_ALT 30
|
||||||
|
Q_TRANS_DECEL 1.700000
|
||||||
|
Q_VELZ_MAX 150
|
||||||
|
Q_VFWD_ALT 5
|
||||||
|
Q_VFWD_GAIN 0.050000
|
||||||
|
Q_WVANE_ENABLE 1
|
||||||
|
Q_WVANE_GAIN 0.200000
|
||||||
|
Q_WVANE_LAND 1
|
||||||
|
Q_WVANE_TAKEOFF 0
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,127 @@
|
||||||
|
# parameter file for Mugin EV350 quadplane
|
||||||
|
|
||||||
|
# https://www.muginuav.com/product/mugin-ev350-carbon-fiber-full-electric-vtol-uav-platform/
|
||||||
|
|
||||||
|
ALT_HOLD_RTL 8000
|
||||||
|
LIM_PITCH_MAX 2000
|
||||||
|
LIM_PITCH_MIN -2000
|
||||||
|
LIM_ROLL_CD 4000
|
||||||
|
NAVL1_PERIOD 17
|
||||||
|
PTCH2SRV_TCONST 0.75
|
||||||
|
RTL_RADIUS 180
|
||||||
|
SCALING_SPEED 15
|
||||||
|
TRIM_THROTTLE 50
|
||||||
|
WP_LOITER_RAD 300
|
||||||
|
WP_RADIUS 220
|
||||||
|
|
||||||
|
# harmonic notch filter
|
||||||
|
INS_HNTCH_ENABLE 1
|
||||||
|
INS_HNTCH_ATT 50
|
||||||
|
INS_HNTCH_BW 30
|
||||||
|
INS_HNTCH_FREQ 51
|
||||||
|
INS_HNTCH_HMNCS 15
|
||||||
|
INS_HNTCH_MODE 1
|
||||||
|
INS_HNTCH_REF 0.245000
|
||||||
|
|
||||||
|
# airspeed
|
||||||
|
TRIM_ARSPD_CM 2300
|
||||||
|
ARSPD_FBW_MAX 28
|
||||||
|
ARSPD_FBW_MIN 18
|
||||||
|
|
||||||
|
# FW pitch tuning
|
||||||
|
PTCH_RATE_D 0.021381
|
||||||
|
PTCH_RATE_FF 1.093860
|
||||||
|
PTCH_RATE_FLTD 10
|
||||||
|
PTCH_RATE_FLTE 0
|
||||||
|
PTCH_RATE_FLTT 2.122066
|
||||||
|
PTCH_RATE_I 1.093860
|
||||||
|
PTCH_RATE_IMAX 0.666
|
||||||
|
PTCH_RATE_P 0.786900
|
||||||
|
PTCH_RATE_SMAX 100
|
||||||
|
|
||||||
|
# FW roll tuning
|
||||||
|
RLL2SRV_TCONST 0.5
|
||||||
|
RLL_RATE_D 0.021381
|
||||||
|
RLL_RATE_FF 0.541178
|
||||||
|
RLL_RATE_FLTD 12
|
||||||
|
RLL_RATE_FLTE 0
|
||||||
|
RLL_RATE_FLTT 3
|
||||||
|
RLL_RATE_I 0.541178
|
||||||
|
RLL_RATE_IMAX 0.666
|
||||||
|
RLL_RATE_P 0.325935
|
||||||
|
RLL_RATE_SMAX 150
|
||||||
|
|
||||||
|
# quadplane parameters
|
||||||
|
Q_ENABLE 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 15000
|
||||||
|
Q_A_RATE_P_MAX 60
|
||||||
|
Q_A_RATE_R_MAX 60
|
||||||
|
Q_A_RATE_Y_MAX 30
|
||||||
|
Q_A_RAT_PIT_D 0.015
|
||||||
|
Q_A_RAT_PIT_FF 0
|
||||||
|
Q_A_RAT_PIT_FLTD 10
|
||||||
|
Q_A_RAT_PIT_FLTE 0
|
||||||
|
Q_A_RAT_PIT_FLTT 20
|
||||||
|
Q_A_RAT_PIT_I 0.3
|
||||||
|
Q_A_RAT_PIT_IMAX 0.5
|
||||||
|
Q_A_RAT_PIT_P 0.3
|
||||||
|
Q_A_RAT_PIT_SMAX 20
|
||||||
|
Q_A_RAT_RLL_D 0.004
|
||||||
|
Q_A_RAT_RLL_FF 0
|
||||||
|
Q_A_RAT_RLL_FLTD 10
|
||||||
|
Q_A_RAT_RLL_FLTE 0
|
||||||
|
Q_A_RAT_RLL_FLTT 10
|
||||||
|
Q_A_RAT_RLL_I 0.1
|
||||||
|
Q_A_RAT_RLL_IMAX 0.5
|
||||||
|
Q_A_RAT_RLL_P 0.1
|
||||||
|
Q_A_RAT_RLL_SMAX 20
|
||||||
|
Q_A_RAT_YAW_D 0.01
|
||||||
|
Q_A_RAT_YAW_FF 0
|
||||||
|
Q_A_RAT_YAW_FLTD 0
|
||||||
|
Q_A_RAT_YAW_FLTE 2.5
|
||||||
|
Q_A_RAT_YAW_FLTT 20
|
||||||
|
Q_A_RAT_YAW_I 0.018
|
||||||
|
Q_A_RAT_YAW_IMAX 0.5
|
||||||
|
Q_A_RAT_YAW_P 0.5
|
||||||
|
Q_A_RAT_YAW_SMAX 10
|
||||||
|
Q_A_THR_MIX_MAX 0.9
|
||||||
|
Q_FRAME_CLASS 1
|
||||||
|
Q_FRAME_TYPE 1
|
||||||
|
Q_LAND_FINAL_ALT 12
|
||||||
|
Q_LAND_SPEED 40
|
||||||
|
Q_LOIT_ANG_MAX 20
|
||||||
|
Q_LOIT_BRK_ACCEL 40
|
||||||
|
Q_LOIT_BRK_JERK 200
|
||||||
|
Q_LOIT_SPEED 600
|
||||||
|
Q_M_BAT_IDX 0
|
||||||
|
Q_M_BAT_VOLT_MAX 50.4
|
||||||
|
Q_M_BAT_VOLT_MIN 39.0
|
||||||
|
Q_M_THST_EXPO 0.7
|
||||||
|
Q_M_THST_HOVER 0.264
|
||||||
|
Q_M_YAW_HEADROOM 200
|
||||||
|
Q_P_JERK_XY 2
|
||||||
|
Q_P_POSXY_P 0.5
|
||||||
|
Q_P_VELXY_D 0.17
|
||||||
|
Q_P_VELXY_I 0.37
|
||||||
|
Q_P_VELXY_P 0.7
|
||||||
|
Q_RTL_ALT 40
|
||||||
|
Q_THROTTLE_EXPO 0.2
|
||||||
|
Q_TRANS_DECEL 1.5
|
||||||
|
Q_TRAN_PIT_MAX 7
|
||||||
|
Q_VELZ_MAX 200
|
||||||
|
Q_VELZ_MAX_DN 130
|
||||||
|
Q_VFWD_ALT 5
|
||||||
|
Q_VFWD_GAIN 0.05
|
||||||
|
Q_WP_RADIUS 300
|
||||||
|
Q_WP_SPEED 600
|
||||||
|
Q_WP_SPEED_DN 150
|
||||||
|
Q_WP_SPEED_UP 220
|
||||||
|
Q_WVANE_ANG_MIN 3
|
||||||
|
Q_WVANE_ENABLE 1
|
||||||
|
Q_WVANE_GAIN 0.3
|
||||||
|
Q_WVANE_TAKEOFF 0
|
Loading…
Reference in New Issue