From 199d4fd6c1d816ae252d5360bf643ff7367f8ed9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 Apr 2016 10:27:42 +1000 Subject: [PATCH] autotest: added parameters for elevon plane, vtail plane and fireflyy6 --- Tools/autotest/firefly.parm | 79 +++++++++++++++++++++++++++++ Tools/autotest/plane-elevons.parm | 82 +++++++++++++++++++++++++++++++ Tools/autotest/plane-vtail.parm | 81 ++++++++++++++++++++++++++++++ Tools/autotest/plane.parm | 81 ++++++++++++++++++++++++++++++ Tools/autotest/sim_vehicle.sh | 20 ++++++++ 5 files changed, 343 insertions(+) create mode 100644 Tools/autotest/firefly.parm create mode 100644 Tools/autotest/plane-elevons.parm create mode 100644 Tools/autotest/plane-vtail.parm create mode 100644 Tools/autotest/plane.parm diff --git a/Tools/autotest/firefly.parm b/Tools/autotest/firefly.parm new file mode 100644 index 0000000000..d8a49c4a77 --- /dev/null +++ b/Tools/autotest/firefly.parm @@ -0,0 +1,79 @@ +ELEVON_OUTPUT 4 +AHRS_EKF_TYPE 2 +ARMING_RUDDER 2 +ARSPD_ENABLE 1 +ARSPD_FBW_MAX 35 +ARSPD_FBW_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 +COMPASS_OFS3_Y 0 +COMPASS_OFS3_Z 0 +COMPASS_OFS_X -0.453570 +COMPASS_OFS_Y -0.585846 +COMPASS_OFS_Z 6.815743 +EK2_ENABLE 1 +EK2_IMU_MASK 3 +EKF_ENABLE 1 +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 +LIM_PITCH_MAX 3000 +LIM_PITCH_MIN -3000 +LIM_ROLL_CD 6500 +NAVL1_PERIOD 14 +PTCH2SRV_D 0.309954 +PTCH2SRV_I 0.425000 +PTCH2SRV_IMAX 4000 +PTCH2SRV_P 3.646518 +PTCH2SRV_RLL 1 +Q_ACCEL_Z 250 +Q_ANGLE_MAX 4500 +Q_ASSIST_SPEED 18 +Q_ENABLE 1 +Q_FRAME_CLASS 4 +Q_LAND_FINAL_ALT 6 +Q_LAND_SPEED 50 +RALLY_INCL_HOME 0 +RALLY_LIMIT_KM 5 +RALLY_TOTAL 0 +RC1_DZ 30 +RC1_MAX 1886 +RC1_MIN 1087 +RC1_REV 1 +RC1_TRIM 1500 +RC2_REV 1 +RC3_MAX 2000 +RC3_MIN 1000 +RC4_REV 1 +RLL2SRV_D 0.141009 +RLL2SRV_I 0.425000 +RLL2SRV_IMAX 4000 +RLL2SRV_P 1.600000 +SCHED_LOOP_RATE 300 +THR_MAX 100 +TRIM_ARSPD_CM 2500 +LOG_BITMASK 65534 + diff --git a/Tools/autotest/plane-elevons.parm b/Tools/autotest/plane-elevons.parm new file mode 100644 index 0000000000..dc308223f0 --- /dev/null +++ b/Tools/autotest/plane-elevons.parm @@ -0,0 +1,82 @@ +EK2_ENABLE 1 +ALT_CTRL_ALG 2 +BATT_MONITOR 4 +LOG_BITMASK 65535 +MAG_ENABLE 1 +TRIM_ARSPD_CM 2200 +TRIM_PITCH_CD 0 +TRIM_THROTTLE 50 +LIM_PITCH_MIN -2000 +LIM_PITCH_MAX 2500 +LIM_ROLL_CD 6500 +LAND_PITCH_CD 100 +LAND_FLARE_SEC 5 +ARSPD_ENABLE 1 +ARSPD_USE 1 +ARSPD_FBW_MAX 30 +ARSPD_FBW_MIN 10 +KFF_RDDRMIX 0.5 +THR_MAX 100 +ELEVON_OUTPUT 4 +KFF_RDDRMIX 0 +RC2_REV 1 +RC4_REV 1 +RC1_MAX 2000 +RC1_MIN 1000 +RC1_TRIM 1500 +RC2_MAX 2000 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_MAX 2000 +RC3_MIN 1000 +RC3_TRIM 1000 +RC4_MAX 2000 +RC4_MIN 1000 +RC4_TRIM 1500 +RC5_MAX 2000 +RC5_MIN 1000 +RC5_TRIM 1500 +RC6_MAX 2000 +RC6_MIN 1000 +RC6_TRIM 1500 +RC7_MAX 2000 +RC7_MIN 1000 +RC7_TRIM 1500 +RC8_MAX 2000 +RC8_MIN 1000 +RC8_TRIM 1500 +FLTMODE1 10 +FLTMODE2 11 +FLTMODE3 12 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 0 +FLTMODE_CH 8 +WP_LOITER_RAD 80 +WP_RADIUS 50 +RLL2SRV_D 0.2 +RLL2SRV_I 0.3 +RLL2SRV_P 2.5 +RLL2SRV_RMAX 0 +RLL2SRV_TCONST 0.5 +PTCH2SRV_D 0.2 +PTCH2SRV_I 0.3 +PTCH2SRV_P 2.5 +PTCH2SRV_RLL 1 +NAVL1_PERIOD 15 +ACRO_LOCKING 1 +VTAIL_OUTPUT 0 +# we need small INS_ACC offsets so INS is recognised as being calibrated +INS_ACCOFFS_X 0.001 +INS_ACCOFFS_Y 0.001 +INS_ACCOFFS_Z 0.001 +INS_ACCSCAL_X 1.001 +INS_ACCSCAL_Y 1.001 +INS_ACCSCAL_Z 1.001 +INS_ACC2OFFS_X 0.001 +INS_ACC2OFFS_Y 0.001 +INS_ACC2OFFS_Z 0.001 +INS_ACC2SCAL_X 1.001 +INS_ACC2SCAL_Y 1.001 +INS_ACC2SCAL_Z 1.001 +INS_GYR_CAL 0 diff --git a/Tools/autotest/plane-vtail.parm b/Tools/autotest/plane-vtail.parm new file mode 100644 index 0000000000..5e99f23828 --- /dev/null +++ b/Tools/autotest/plane-vtail.parm @@ -0,0 +1,81 @@ +EK2_ENABLE 1 +ALT_CTRL_ALG 2 +BATT_MONITOR 4 +LOG_BITMASK 65535 +MAG_ENABLE 1 +TRIM_ARSPD_CM 2200 +TRIM_PITCH_CD 0 +TRIM_THROTTLE 50 +LIM_PITCH_MIN -2000 +LIM_PITCH_MAX 2500 +LIM_ROLL_CD 6500 +LAND_PITCH_CD 100 +LAND_FLARE_SEC 5 +ARSPD_ENABLE 1 +ARSPD_USE 1 +ARSPD_FBW_MAX 30 +ARSPD_FBW_MIN 10 +KFF_RDDRMIX 0.5 +THR_MAX 100 +RC2_REV 1 +RC4_REV 1 +RC1_MAX 2000 +RC1_MIN 1000 +RC1_TRIM 1500 +RC2_MAX 2000 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_MAX 2000 +RC3_MIN 1000 +RC3_TRIM 1000 +RC4_MAX 2000 +RC4_MIN 1000 +RC4_TRIM 1500 +RC5_MAX 2000 +RC5_MIN 1000 +RC5_TRIM 1500 +RC6_MAX 2000 +RC6_MIN 1000 +RC6_TRIM 1500 +RC7_MAX 2000 +RC7_MIN 1000 +RC7_TRIM 1500 +RC8_MAX 2000 +RC8_MIN 1000 +RC8_TRIM 1500 +FLTMODE1 10 +FLTMODE2 11 +FLTMODE3 12 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 0 +FLTMODE_CH 8 +WP_LOITER_RAD 80 +WP_RADIUS 50 +RLL2SRV_D 0.2 +RLL2SRV_I 0.3 +RLL2SRV_P 2.5 +RLL2SRV_RMAX 0 +RLL2SRV_TCONST 0.5 +PTCH2SRV_D 0.2 +PTCH2SRV_I 0.3 +PTCH2SRV_P 2.5 +PTCH2SRV_RLL 1 +NAVL1_PERIOD 15 +ACRO_LOCKING 1 +ELEVON_OUTPUT 0 +VTAIL_OUTPUT 3 +# we need small INS_ACC offsets so INS is recognised as being calibrated +INS_ACCOFFS_X 0.001 +INS_ACCOFFS_Y 0.001 +INS_ACCOFFS_Z 0.001 +INS_ACCSCAL_X 1.001 +INS_ACCSCAL_Y 1.001 +INS_ACCSCAL_Z 1.001 +INS_ACC2OFFS_X 0.001 +INS_ACC2OFFS_Y 0.001 +INS_ACC2OFFS_Z 0.001 +INS_ACC2SCAL_X 1.001 +INS_ACC2SCAL_Y 1.001 +INS_ACC2SCAL_Z 1.001 +INS_GYR_CAL 0 diff --git a/Tools/autotest/plane.parm b/Tools/autotest/plane.parm new file mode 100644 index 0000000000..6512993522 --- /dev/null +++ b/Tools/autotest/plane.parm @@ -0,0 +1,81 @@ +EK2_ENABLE 1 +ALT_CTRL_ALG 2 +BATT_MONITOR 4 +LOG_BITMASK 65535 +MAG_ENABLE 1 +TRIM_ARSPD_CM 2200 +TRIM_PITCH_CD 0 +TRIM_THROTTLE 50 +LIM_PITCH_MIN -2000 +LIM_PITCH_MAX 2500 +LIM_ROLL_CD 6500 +LAND_PITCH_CD 100 +LAND_FLARE_SEC 5 +ARSPD_ENABLE 1 +ARSPD_USE 1 +ARSPD_FBW_MAX 30 +ARSPD_FBW_MIN 10 +KFF_RDDRMIX 0.5 +THR_MAX 100 +RC2_REV 1 +RC4_REV 1 +RC1_MAX 2000 +RC1_MIN 1000 +RC1_TRIM 1500 +RC2_MAX 2000 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_MAX 2000 +RC3_MIN 1000 +RC3_TRIM 1000 +RC4_MAX 2000 +RC4_MIN 1000 +RC4_TRIM 1500 +RC5_MAX 2000 +RC5_MIN 1000 +RC5_TRIM 1500 +RC6_MAX 2000 +RC6_MIN 1000 +RC6_TRIM 1500 +RC7_MAX 2000 +RC7_MIN 1000 +RC7_TRIM 1500 +RC8_MAX 2000 +RC8_MIN 1000 +RC8_TRIM 1500 +FLTMODE1 10 +FLTMODE2 11 +FLTMODE3 12 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 0 +FLTMODE_CH 8 +WP_LOITER_RAD 80 +WP_RADIUS 50 +RLL2SRV_D 0.2 +RLL2SRV_I 0.3 +RLL2SRV_P 2.5 +RLL2SRV_RMAX 0 +RLL2SRV_TCONST 0.5 +PTCH2SRV_D 0.2 +PTCH2SRV_I 0.3 +PTCH2SRV_P 2.5 +PTCH2SRV_RLL 1 +NAVL1_PERIOD 15 +ACRO_LOCKING 1 +ELEVON_OUTPUT 0 +VTAIL_OUTPUT 0 +# we need small INS_ACC offsets so INS is recognised as being calibrated +INS_ACCOFFS_X 0.001 +INS_ACCOFFS_Y 0.001 +INS_ACCOFFS_Z 0.001 +INS_ACCSCAL_X 1.001 +INS_ACCSCAL_Y 1.001 +INS_ACCSCAL_Z 1.001 +INS_ACC2OFFS_X 0.001 +INS_ACC2OFFS_Y 0.001 +INS_ACC2OFFS_Z 0.001 +INS_ACC2SCAL_X 1.001 +INS_ACC2SCAL_Y 1.001 +INS_ACC2SCAL_Z 1.001 +INS_GYR_CAL 0 diff --git a/Tools/autotest/sim_vehicle.sh b/Tools/autotest/sim_vehicle.sh index fa6714562a..458dedcd17 100755 --- a/Tools/autotest/sim_vehicle.sh +++ b/Tools/autotest/sim_vehicle.sh @@ -268,6 +268,11 @@ case $FRAME in MODEL="$FRAME" DEFAULTS_PATH="$autotest/y6_params.parm" ;; + firefly*) + BUILD_TARGET="sitl" + MODEL="$FRAME" + DEFAULTS_PATH="$autotest/firefly.parm" + ;; heli*) BUILD_TARGET="sitl-heli" MODEL="$FRAME" @@ -308,6 +313,21 @@ case $FRAME in MODEL="$FRAME" DEFAULTS_PATH="$autotest/quadplane.parm" ;; + plane-elevon*) + BUILD_TARGET="sitl" + MODEL="$FRAME" + DEFAULTS_PATH="$autotest/plane-elevons.parm" + ;; + plane-vtail*) + BUILD_TARGET="sitl" + MODEL="$FRAME" + DEFAULTS_PATH="$autotest/plane-vtail.parm" + ;; + plane*) + BUILD_TARGET="sitl" + MODEL="$FRAME" + DEFAULTS_PATH="$autotest/plane.parm" + ;; *-heli) BUILD_TARGET="sitl-heli" MODEL="$FRAME"