autotest: fixed parameters for tilt quadplanes

and enable autotest of the disabled tilt quadplane frames
This commit is contained in:
Andrew Tridgell 2024-02-17 19:28:05 +11:00
parent 9225b9f76d
commit 1d08662c72
8 changed files with 113 additions and 388 deletions

View File

@ -3948,11 +3948,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
vinfo = vehicleinfo.VehicleInfo()
vinfo_options = vinfo.options[self.vehicleinfo_key()]
known_broken_frames = {
"firefly": "falls out of sky after transition",
"plane-tailsitter": "does not take off; immediately emits 'AP: Transition VTOL done' while on ground",
"quadplane-cl84": "falls out of sky instead of transitioning",
"quadplane-tilttri": "falls out of sky instead of transitioning",
"quadplane-tilttrivec": "loses attitude control and crashes",
"plane-ice" : "needs ICE control channel for ignition",
"quadplane-ice" : "needs ICE control channel for ignition",
"quadplane-can" : "needs CAN periph",

View File

@ -1,97 +1,28 @@
Q_ENABLE 1
Q_FRAME_CLASS 5
Q_FRAME_TYPE 11
Q_TILT_ENABLE 1
Q_TILT_MASK 54
Q_TILT_MAX 60
Q_TILT_RATE_DN 15
Q_VFWD_GAIN 0.1
Q_WVANE_GAIN 0.3
SERVO1_FUNCTION = 78
SERVO2_FUNCTION = 77
SERVO1_REVERSED = 1
SERVO2_REVERSED = 1
SERVO1_MAX = 2000
SERVO1_MIN = 1000
SERVO2_MAX = 2000
SERVO2_MIN = 1000
AHRS_EKF_TYPE 2
ARMING_RUDDER 2
AIRSPEED_MAX 35
AIRSPEED_MIN 6
ARSPD_USE 1
AUTOTUNE_LEVEL 8
COMPASS_OFS2_X -0.420265
COMPASS_OFS2_Y -0.726942
COMPASS_OFS2_Z 6.665476
COMPASS_OFS3_X -0.420265
COMPASS_OFS3_Y -0.726942
COMPASS_OFS3_Z 6.665476
COMPASS_OFS_X -0.453570
COMPASS_OFS_Y -0.585846
COMPASS_OFS_Z 6.815743
EK2_ENABLE 1
EK2_IMU_MASK 3
FBWB_CLIMB_RATE 10
FLTMODE1 10
FLTMODE2 11
FLTMODE3 12
FLTMODE4 5
FLTMODE5 19
FLTMODE6 5
FLTMODE_CH 5
INS_ACC2OFFS_X 0.001000
INS_ACC2OFFS_Y 0.001000
INS_ACC2OFFS_Z 0.001000
INS_ACC2SCAL_X 1.001000
INS_ACC2SCAL_Y 1.001000
INS_ACC2SCAL_Z 1.001000
INS_ACCOFFS_X 0.001000
INS_ACCOFFS_Y 0.001000
INS_ACCOFFS_Z 0.001000
INS_ACCSCAL_X 1.001000
INS_ACCSCAL_Y 1.001000
INS_ACCSCAL_Z 1.001000
INS_GYR_CAL 0
KFF_RDDRMIX 0.500000
PTCH_LIM_MAX_DEG 30.00
PTCH_LIM_MIN_DEG -30.00
ROLL_LIMIT_DEG 65.00
NAVL1_PERIOD 8
PTCH_RATE_D 0.000000
PTCH_RATE_I 0.212500
PTCH_RATE_IMAX 0.888889
PTCH_RATE_P 0.309954
PTCH2SRV_RLL 1
RALLY_INCL_HOME 0
RALLY_LIMIT_KM 5
RALLY_TOTAL 0
RC1_DZ 30
RC1_MAX 1886
RC1_MIN 1087
RC1_TRIM 1500
RC3_MAX 2000
RC3_MIN 1000
SERVO3_MIN 1000
SERVO3_MAX 2000
RLL_RATE_D 0.000000
RLL_RATE_I 0.212500
RLL_RATE_IMAX 0.888889
RLL_RATE_P 0.141009
SCHED_LOOP_RATE 300
THR_MAX 100
AIRSPEED_CRUISE 25.00
LOG_BITMASK 65534
# map channel 13 out for tilt
Q_ENABLE 1
Q_FRAME_CLASS 5
Q_FRAME_TYPE 11
Q_ASSIST_SPEED 10
Q_TILT_MASK 54
Q_TILT_MAX 60
Q_TILT_RATE_DN 15
Q_RTL_MODE 1
Q_VFWD_GAIN 0.1
Q_WVANE_GAIN 0.3
SERVO9_FUNCTION 41
SERVO9_MIN 1000
SERVO9_MAX 2000
SERVO3_FUNCTION 33
SERVO4_FUNCTION 34
SERVO5_FUNCTION 35
SERVO6_FUNCTION 36
SERVO7_FUNCTION 37
SERVO8_FUNCTION 38
PTCH_RATE_FF 1.407055
RLL_RATE_FF 0.752741
SERVO9_FUNCTION 41
SERVO9_MIN 1000
SERVO9_MAX 2000

View File

@ -1,70 +1,14 @@
ARMING_RUDDER 2
ARSPD_TYPE 0
AIRSPEED_MAX 35
AIRSPEED_MIN 6
AUTOTUNE_LEVEL 8
COMPASS_OFS2_X -0.420265
COMPASS_OFS2_Y -0.726942
COMPASS_OFS2_Z 6.665476
COMPASS_OFS3_X -0.420265
COMPASS_OFS3_Y -0.726942
COMPASS_OFS3_Z 6.665476
COMPASS_OFS_X -0.453570
COMPASS_OFS_Y -0.585846
COMPASS_OFS_Z 6.815743
FBWB_CLIMB_RATE 10
FLTMODE1 10
FLTMODE2 11
FLTMODE3 12
FLTMODE4 5
FLTMODE5 19
FLTMODE6 5
FLTMODE_CH 5
INS_ACC2OFFS_X 0.001000
INS_ACC2OFFS_Y 0.001000
INS_ACC2OFFS_Z 0.001000
INS_ACC2SCAL_X 1.001000
INS_ACC2SCAL_Y 1.001000
INS_ACC2SCAL_Z 1.001000
INS_ACCOFFS_X 0.001000
INS_ACCOFFS_Y 0.001000
INS_ACCOFFS_Z 0.001000
INS_ACCSCAL_X 1.001000
INS_ACCSCAL_Y 1.001000
INS_ACCSCAL_Z 1.001000
INS_GYR_CAL 0
KFF_RDDRMIX 0.500000
PTCH_LIM_MAX_DEG 30.00
PTCH_LIM_MIN_DEG -30.00
ROLL_LIMIT_DEG 65.00
NAVL1_PERIOD 14
PTCH_RATE_D 0.000000
PTCH_RATE_I 0.212500
PTCH_RATE_IMAX 0.888889
PTCH_RATE_P 0.309954
PTCH2SRV_RLL 1
RALLY_INCL_HOME 0
RALLY_LIMIT_KM 5
RALLY_TOTAL 0
RLL_RATE_D 0.000000
RLL_RATE_I 0.212500
RLL_RATE_IMAX 0.888889
RLL_RATE_P 0.141009
THR_MAX 100
AIRSPEED_CRUISE 25.00
SERVO12_FUNCTION 41
SERVO12_MIN 1000
SERVO12_MAX 2000
SERVO11_TRIM 1500
RTL_RADIUS 80
RTL_ALTITUDE 20.00
Q_ENABLE 1
Q_FRAME_CLASS 7
Q_ANGLE_MAX 4500
Q_ASSIST_SPEED 6
Q_TILT_ENABLE 1
Q_TILT_MASK 3
Q_TILT_RATE 13
Q_TILT_TYPE 1
Q_RTL_MODE 1
PTCH_RATE_FF 1.407055
RLL_RATE_FF 0.552741
# 7 seconds to move servo
Q_TILT_RATE_DN 12.85
Q_TILT_RATE_UP 12.85
SERVO12_FUNCTION 41
SERVO12_MIN 1000
SERVO12_MAX 2000

View File

@ -0,0 +1,18 @@
Q_ENABLE 1
Q_FRAME_CLASS 1
Q_FRAME_TYPE 1
Q_TILT_ENABLE 1
Q_TILT_TYPE 2
Q_TILT_YAW_ANGLE 10
Q_TILT_MASK 5
SERVO3_FUNCTION 0
SERVO12_FUNCTION 76
SERVO13_FUNCTION 75
SERVO12_MIN 1000
SERVO12_MAX 2000
SERVO13_MIN 1000
SERVO13_MAX 2000

View File

@ -1,81 +1,11 @@
AHRS_EKF_TYPE 2
ARMING_RUDDER 2
AIRSPEED_MAX 35
AIRSPEED_MIN 6
ARSPD_USE 1
AUTOTUNE_LEVEL 8
COMPASS_OFS2_X -0.420265
COMPASS_OFS2_Y -0.726942
COMPASS_OFS2_Z 6.665476
COMPASS_OFS3_X -0.420265
COMPASS_OFS3_Y -0.726942
COMPASS_OFS3_Z 6.665476
COMPASS_OFS_X -0.453570
COMPASS_OFS_Y -0.585846
COMPASS_OFS_Z 6.815743
EK2_ENABLE 1
EK2_IMU_MASK 3
FBWB_CLIMB_RATE 10
FLTMODE1 10
FLTMODE2 11
FLTMODE3 12
FLTMODE4 5
FLTMODE5 19
FLTMODE6 5
FLTMODE_CH 5
INS_ACC2OFFS_X 0.001000
INS_ACC2OFFS_Y 0.001000
INS_ACC2OFFS_Z 0.001000
INS_ACC2SCAL_X 1.001000
INS_ACC2SCAL_Y 1.001000
INS_ACC2SCAL_Z 1.001000
INS_ACCOFFS_X 0.001000
INS_ACCOFFS_Y 0.001000
INS_ACCOFFS_Z 0.001000
INS_ACCSCAL_X 1.001000
INS_ACCSCAL_Y 1.001000
INS_ACCSCAL_Z 1.001000
INS_GYR_CAL 0
KFF_RDDRMIX 0.500000
PTCH_LIM_MAX_DEG 30.00
PTCH_LIM_MIN_DEG -30.00
ROLL_LIMIT_DEG 65.00
NAVL1_PERIOD 14
PTCH_RATE_D 0.000000
PTCH_RATE_I 0.212500
PTCH_RATE_IMAX 0.888889
PTCH_RATE_P 0.309954
PTCH2SRV_RLL 1
Q_ANGLE_MAX 4500
Q_ASSIST_SPEED 6
Q_ENABLE 1
Q_FRAME_CLASS 7
RALLY_INCL_HOME 0
RALLY_LIMIT_KM 5
RALLY_TOTAL 0
RC1_DZ 30
RC1_MAX 1886
RC1_MIN 1087
RC1_TRIM 1500
RC3_MAX 2000
RC3_MIN 1000
SERVO3_MIN 1000
SERVO3_MAX 2000
RLL_RATE_D 0.000000
RLL_RATE_I 0.212500
RLL_RATE_IMAX 0.888889
RLL_RATE_P 0.141009
SCHED_LOOP_RATE 300
THR_MAX 100
AIRSPEED_CRUISE 25.00
LOG_BITMASK 65534
SERVO3_FUNCTION 0
Q_TILT_ENABLE 1
Q_TILT_MASK 3
Q_VFWD_GAIN 0.1
Q_TILT_TYPE 0
SERVO12_FUNCTION 41
SERVO12_MIN 1000
SERVO12_MAX 2000
RTL_RADIUS 80
Q_RTL_MODE 1
RTL_ALTITUDE 20.00
PTCH_RATE_FF 1.407055
RLL_RATE_FF 0.552741

View File

@ -1,86 +1,54 @@
AHRS_EKF_TYPE 2
ARMING_RUDDER 2
AIRSPEED_MAX 35
AIRSPEED_MIN 6
ARSPD_USE 1
AUTOTUNE_LEVEL 8
COMPASS_OFS2_X -0.420265
COMPASS_OFS2_Y -0.726942
COMPASS_OFS2_Z 6.665476
COMPASS_OFS3_X -0.420265
COMPASS_OFS3_Y -0.726942
COMPASS_OFS3_Z 6.665476
COMPASS_OFS_X -0.453570
COMPASS_OFS_Y -0.585846
COMPASS_OFS_Z 6.815743
EK2_ENABLE 1
EK2_IMU_MASK 3
FBWB_CLIMB_RATE 10
FLTMODE1 10
FLTMODE2 11
FLTMODE3 12
FLTMODE4 5
FLTMODE5 19
FLTMODE6 5
FLTMODE_CH 5
INS_ACC2OFFS_X 0.001000
INS_ACC2OFFS_Y 0.001000
INS_ACC2OFFS_Z 0.001000
INS_ACC2SCAL_X 1.001000
INS_ACC2SCAL_Y 1.001000
INS_ACC2SCAL_Z 1.001000
INS_ACCOFFS_X 0.001000
INS_ACCOFFS_Y 0.001000
INS_ACCOFFS_Z 0.001000
INS_ACCSCAL_X 1.001000
INS_ACCSCAL_Y 1.001000
INS_ACCSCAL_Z 1.001000
INS_GYR_CAL 0
KFF_RDDRMIX 0.500000
PTCH_LIM_MAX_DEG 30.00
PTCH_LIM_MIN_DEG -30.00
ROLL_LIMIT_DEG 65.00
NAVL1_PERIOD 14
PTCH_RATE_D 0.000000
PTCH_RATE_I 0.212500
PTCH_RATE_IMAX 0.888889
PTCH_RATE_P 0.309954
PTCH2SRV_RLL 1
Q_ANGLE_MAX 4500
Q_ASSIST_SPEED 6
Q_ENABLE 1
Q_FRAME_CLASS 7
RALLY_INCL_HOME 0
RALLY_LIMIT_KM 5
RALLY_TOTAL 0
RC1_DZ 30
RC1_MAX 1886
RC1_MIN 1087
RC1_TRIM 1500
RC3_MAX 2000
RC3_MIN 1000
SERVO3_MIN 1000
SERVO3_MAX 2000
RLL_RATE_D 0.000000
RLL_RATE_I 0.212500
RLL_RATE_IMAX 0.888889
RLL_RATE_P 0.141009
SCHED_LOOP_RATE 300
THR_MAX 100
AIRSPEED_CRUISE 25.00
LOG_BITMASK 65534
Q_TILT_ENABLE 1
Q_TILT_MASK 3
Q_VFWD_GAIN 0.1
Q_TILT_TYPE 2
Q_TILT_YAW_ANGLE 10
SERVO3_FUNCTION 0
SERVO12_FUNCTION 76
SERVO12_MIN 1000
SERVO12_MAX 2000
SERVO13_FUNCTION 75
SERVO12_MIN 1000
SERVO12_MAX 2000
RTL_RADIUS 80
Q_RTL_MODE 1
RTL_ALTITUDE 20.00
Q_TILT_TYPE 2
Q_TILT_YAW_ANGLE 10
PTCH_RATE_FF 1.407055
RLL_RATE_FF 0.552741
SERVO13_MIN 1000
SERVO13_MAX 2000
Q_A_RAT_RLL_P 0.126
Q_A_RAT_RLL_I 0.126
Q_A_RAT_RLL_D 0.003
Q_A_RAT_RLL_FLTT 10
Q_A_RAT_PIT_P 0.12
Q_A_RAT_PIT_I 0.12
Q_A_RAT_PIT_D 0.0025
Q_A_RAT_PIT_FLTT 10
Q_A_RAT_YAW_P 0.5
Q_A_RAT_YAW_I 0.05
Q_A_RAT_YAW_D 0.01
Q_A_RAT_YAW_FLTT 10
Q_A_RAT_YAW_FLTE 0
Q_A_RAT_YAW_FLTD 10
RLL2SRV_TCONST 0.2
RLL2SRV_RMAX 120
RLL_RATE_P 0.74
RLL_RATE_I 0.218
RLL_RATE_D 0.012
RLL_RATE_FF 0.218
RLL_RATE_FLTT 7.957
RLL_RATE_FLTD 10
PTCH2SRV_TCONST 0.3
PTCH2SRV_RMAX_UP 120
PTCH2SRV_RMAX_DN 120
PTCH_RATE_P 0.574
PTCH_RATE_I 0.933
PTCH_RATE_D 0.016
PTCH_RATE_FF 0.933
PTCH_RATE_FLTT 5.305
PTCH_RATE_FLTD 10

View File

@ -1,73 +1 @@
AHRS_EKF_TYPE 2
ARMING_RUDDER 2
AIRSPEED_MAX 35
AIRSPEED_MIN 13
ARSPD_USE 1
AUTOTUNE_LEVEL 8
COMPASS_OFS2_X -0.420265
COMPASS_OFS2_Y -0.726942
COMPASS_OFS2_Z 6.665476
COMPASS_OFS3_X -0.420265
COMPASS_OFS3_Y -0.726942
COMPASS_OFS3_Z 6.665476
COMPASS_OFS_X -0.453570
COMPASS_OFS_Y -0.585846
COMPASS_OFS_Z 6.815743
EK2_ENABLE 1
EK2_IMU_MASK 3
FBWB_CLIMB_RATE 10
FLTMODE1 10
FLTMODE2 11
FLTMODE3 12
FLTMODE4 5
FLTMODE5 19
FLTMODE6 5
FLTMODE_CH 5
INS_ACC2OFFS_X 0.001000
INS_ACC2OFFS_Y 0.001000
INS_ACC2OFFS_Z 0.001000
INS_ACC2SCAL_X 1.001000
INS_ACC2SCAL_Y 1.001000
INS_ACC2SCAL_Z 1.001000
INS_ACCOFFS_X 0.001000
INS_ACCOFFS_Y 0.001000
INS_ACCOFFS_Z 0.001000
INS_ACCSCAL_X 1.001000
INS_ACCSCAL_Y 1.001000
INS_ACCSCAL_Z 1.001000
INS_GYR_CAL 0
KFF_RDDRMIX 0.500000
PTCH_LIM_MAX_DEG 30.00
PTCH_LIM_MIN_DEG -30.00
ROLL_LIMIT_DEG 65.00
NAVL1_PERIOD 14
PTCH_RATE_D 0.000000
PTCH_RATE_I 0.212500
PTCH_RATE_IMAX 0.888889
PTCH_RATE_P 0.309954
PTCH2SRV_RLL 1
Q_ANGLE_MAX 4500
Q_ASSIST_SPEED 18
Q_ENABLE 1
Q_FRAME_CLASS 7
RALLY_INCL_HOME 0
RALLY_LIMIT_KM 5
RALLY_TOTAL 0
RC1_DZ 30
RC1_MAX 1886
RC1_MIN 1087
RC1_TRIM 1500
RC3_MAX 2000
RC3_MIN 1000
SERVO3_MIN 1000
SERVO3_MAX 2000
RLL_RATE_D 0.000000
RLL_RATE_I 0.212500
RLL_RATE_IMAX 0.888889
RLL_RATE_P 0.141009
SCHED_LOOP_RATE 300
THR_MAX 100
AIRSPEED_CRUISE 25.00
LOG_BITMASK 65534
PTCH_RATE_FF 1.407055
RLL_RATE_FF 0.552741

View File

@ -239,11 +239,13 @@ class VehicleInfo(object):
# PLANE
"quadplane-tilttri": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/quadplane-tilttri.parm",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tilttri.parm"],
},
"quadplane-tilttrivec": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/quadplane-tilttrivec.parm",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tilttrivec.parm"],
},
"quadplane-tilthvec": {
"waf_target": "bin/arduplane",
@ -251,11 +253,13 @@ class VehicleInfo(object):
},
"quadplane-tri": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/quadplane-tri.parm",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tri.parm"],
},
"quadplane-cl84" : {
"waf_target" : "bin/arduplane",
"default_params_filename": "default_params/quadplane-cl84.parm",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-cl84.parm"],
},
"quadplane": {
"waf_target": "bin/arduplane",
@ -270,9 +274,15 @@ class VehicleInfo(object):
"default_params_filename": ["default_params/quadplane.parm", "default_params/quadplane-can.parm"],
"periph_params_filename": ["default_params/periph.parm", "default_params/quadplane-periph.parm"],
},
"quadplane-tilt": {
"waf_target": "bin/arduplane",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/quadplane-tilt.parm"],
},
"firefly": {
"waf_target": "bin/arduplane",
"default_params_filename": "default_params/firefly.parm",
"default_params_filename": ["default_params/quadplane.parm",
"default_params/firefly.parm"]
},
"plane-elevon": {
"waf_target": "bin/arduplane",