2022-05-04 00:55:42 -03:00
|
|
|
# param file for MFD CrossWind VTOL
|
|
|
|
|
|
|
|
# http://myflydream.com/products/c-0/369.html
|
|
|
|
|
|
|
|
# airspeed
|
2024-01-18 01:37:42 -04:00
|
|
|
AIRSPEED_MAX 29
|
|
|
|
AIRSPEED_MIN 16
|
2024-01-17 22:34:22 -04:00
|
|
|
AIRSPEED_CRUISE 20.00
|
2022-05-04 00:55:42 -03:00
|
|
|
TRIM_THROTTLE 52
|
|
|
|
|
|
|
|
# fixed wing limits
|
|
|
|
LIM_PITCH_MAX 2200
|
|
|
|
LIM_ROLL_CD 3500
|
|
|
|
NAVL1_PERIOD 24
|
|
|
|
ALT_HOLD_RTL 9000
|
|
|
|
FBWB_CLIMB_RATE 5
|
|
|
|
WP_LOITER_RAD 150
|
|
|
|
WP_RADIUS 150
|
|
|
|
|
|
|
|
# fixed wing tuning
|
|
|
|
RLL2SRV_RMAX 90
|
|
|
|
RLL2SRV_TCONST 0.3
|
|
|
|
RLL_RATE_D 0.001916
|
|
|
|
RLL_RATE_FF 0.473694
|
|
|
|
RLL_RATE_FLTD 10
|
|
|
|
RLL_RATE_FLTT 7.957747
|
|
|
|
RLL_RATE_I 0.473694
|
|
|
|
RLL_RATE_P 0.01
|
|
|
|
|
|
|
|
PTCH2SRV_RLL 1.2
|
|
|
|
PTCH2SRV_RMAX_DN 75
|
|
|
|
PTCH2SRV_RMAX_UP 75
|
|
|
|
PTCH_RATE_D 0.012
|
|
|
|
PTCH_RATE_FF 0.329676
|
|
|
|
PTCH_RATE_FLTD 15
|
|
|
|
PTCH_RATE_FLTT 5.305164
|
|
|
|
PTCH_RATE_I 0.329676
|
|
|
|
PTCH_RATE_P 0.148952
|
|
|
|
PTCH_RATE_SMAX 300
|
|
|
|
|
|
|
|
# actuators
|
|
|
|
SERVO1_REVERSED 1
|
|
|
|
SERVO2_REVERSED 1
|
|
|
|
SERVO_AUTO_TRIM 1
|
|
|
|
SERVO_RATE 150
|
|
|
|
|
2022-05-05 04:49:24 -03:00
|
|
|
# harmonic notch filter
|
|
|
|
INS_HNTCH_ENABLE 1
|
|
|
|
INS_HNTCH_ATT 40
|
|
|
|
INS_HNTCH_BW 40
|
|
|
|
INS_HNTCH_FREQ 81
|
|
|
|
INS_HNTCH_HMNCS 3
|
|
|
|
INS_HNTCH_MODE 1
|
|
|
|
INS_HNTCH_REF 0.39
|
|
|
|
|
2022-05-04 00:55:42 -03:00
|
|
|
# quadplane parameters
|
|
|
|
Q_ENABLE 1
|
|
|
|
Q_FRAME_CLASS 1
|
|
|
|
Q_FRAME_TYPE 1
|
|
|
|
|
|
|
|
Q_ANGLE_MAX 2000
|
|
|
|
Q_ASSIST_ANGLE 45
|
|
|
|
Q_ASSIST_SPEED 14
|
|
|
|
|
|
|
|
# vtol tune
|
|
|
|
Q_A_ANG_PIT_P 4
|
|
|
|
Q_A_ANG_RLL_P 4
|
|
|
|
Q_A_RAT_PIT_D 0.0105
|
|
|
|
Q_A_RAT_PIT_FLTD 15
|
|
|
|
Q_A_RAT_PIT_I 0.2
|
|
|
|
Q_A_RAT_PIT_P 0.2
|
|
|
|
Q_A_RAT_PIT_SMAX 40
|
|
|
|
Q_A_RAT_RLL_D 0.0198
|
|
|
|
Q_A_RAT_RLL_I 0.225
|
|
|
|
Q_A_RAT_RLL_P 0.225
|
|
|
|
Q_A_RAT_RLL_SMAX 40
|
|
|
|
|
|
|
|
Q_M_BAT_VOLT_MAX 25.2
|
|
|
|
Q_M_BAT_VOLT_MIN 18.6
|
|
|
|
|
|
|
|
Q_M_THST_EXPO 0.7
|
|
|
|
Q_M_THST_HOVER 0.445192
|
|
|
|
Q_P_JERK_Z 2
|
|
|
|
Q_P_POSXY_P 0.7
|
|
|
|
Q_P_VELXY_P 1
|
|
|
|
|
|
|
|
Q_RTL_ALT 60
|
|
|
|
|
|
|
|
Q_TRANSITION_MS 8000
|
|
|
|
Q_TRANS_DECEL 1.2
|
|
|
|
Q_TRANS_FAIL 20
|
|
|
|
Q_TRAN_PIT_MAX 5
|
|
|
|
Q_VFWD_ALT 5
|
|
|
|
Q_VFWD_GAIN 0.05
|
|
|
|
|
|
|
|
Q_WP_RADIUS 500
|
|
|
|
Q_WP_RFND_USE 0
|
|
|
|
Q_WP_SPEED 800
|
|
|
|
Q_WP_SPEED_DN 100
|
|
|
|
Q_WVANE_ANG_MIN 3
|
|
|
|
Q_WVANE_GAIN 0.2
|
|
|
|
|
|
|
|
# TECS tuning
|
|
|
|
TECS_CLMB_MAX 3
|
|
|
|
TECS_PTCH_DAMP 0.2
|
|
|
|
TECS_THR_DAMP 0.6
|
|
|
|
TECS_TIME_CONST 6
|
|
|
|
|