mirror of https://github.com/ArduPilot/ardupilot
autotest: support coaxcopter
This commit is contained in:
parent
969b6ebea9
commit
b76a993f7e
|
@ -0,0 +1,75 @@
|
|||
BATT_MONITOR 4.0000
|
||||
COMPASS_OFS2_X 5.0000
|
||||
COMPASS_OFS2_Y 13.0000
|
||||
COMPASS_OFS2_Z -18.0000
|
||||
COMPASS_OFS3_X 1.0000
|
||||
COMPASS_OFS3_Y 1.0000
|
||||
COMPASS_OFS3_Z 1.0000
|
||||
COMPASS_OFS_X 2.8749
|
||||
COMPASS_OFS_Y -21.8262
|
||||
COMPASS_OFS_Z -21.8422
|
||||
FLTMODE1 7.0000
|
||||
FLTMODE2 9.0000
|
||||
FLTMODE3 6.0000
|
||||
FLTMODE4 3.0000
|
||||
FLTMODE5 5.0000
|
||||
# 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_ACC3OFFS_X 0.000
|
||||
INS_ACC3OFFS_Y 0.000
|
||||
INS_ACC3OFFS_Z 0.000
|
||||
INS_ACC3SCAL_X 1.000
|
||||
INS_ACC3SCAL_Y 1.000
|
||||
INS_ACC3SCAL_Z 1.000
|
||||
RC1_MAX 2000.000000
|
||||
RC1_MIN 1000.000000
|
||||
RC1_TRIM 1500.000000
|
||||
RC2_MAX 2000.000000
|
||||
RC2_MIN 1000.000000
|
||||
RC2_TRIM 1500.000000
|
||||
RC3_MAX 2000.000000
|
||||
RC3_MIN 1000.000000
|
||||
RC3_TRIM 1500.000000
|
||||
RC4_MAX 2000.000000
|
||||
RC4_MIN 1000.000000
|
||||
RC4_TRIM 1500.000000
|
||||
RC5_MAX 2000.000000
|
||||
RC5_MIN 1000.000000
|
||||
RC5_TRIM 1500.000000
|
||||
RC6_MAX 2000.000000
|
||||
RC6_MIN 1000.000000
|
||||
RC6_TRIM 1500.000000
|
||||
RC7_MAX 2000.000000
|
||||
RC7_MIN 1000.000000
|
||||
RC7_TRIM 1500.000000
|
||||
RC8_MAX 2000.000000
|
||||
RC8_MIN 1000.000000
|
||||
RC8_TRIM 1500.000000
|
||||
# autotune values
|
||||
ATC_RATE_FF_ENAB 1.000000
|
||||
ATC_RAT_PIT_D 0.200000
|
||||
ATC_RAT_PIT_FILT 20.000000
|
||||
ATC_RAT_PIT_I 2.000000
|
||||
ATC_RAT_PIT_IMAX 1.000000
|
||||
ATC_RAT_PIT_P 2.000000
|
||||
ATC_RAT_RLL_D 0.200000
|
||||
ATC_RAT_RLL_FILT 20.000000
|
||||
ATC_RAT_RLL_I 2.000000
|
||||
ATC_RAT_RLL_IMAX 1.000000
|
||||
ATC_RAT_RLL_P 2.000000
|
||||
ATC_RAT_YAW_D 0.000000
|
||||
ATC_RAT_YAW_FILT 5.000000
|
||||
ATC_RAT_YAW_I 0.139709
|
||||
ATC_RAT_YAW_IMAX 0.222000
|
||||
ATC_RAT_YAW_P 1.397085
|
|
@ -340,6 +340,11 @@ _options_for_frame = {
|
|||
"waf_target": "bin/arducopter-single",
|
||||
"default_params_filename": "SingleCopter.parm",
|
||||
},
|
||||
"coaxcopter": {
|
||||
"make_target": "sitl-coax",
|
||||
"waf_target": "bin/arducopter-coax",
|
||||
"default_params_filename": "CoaxCopter.parm",
|
||||
},
|
||||
# PLANE
|
||||
"quadplane-tilttri" : {
|
||||
"build_target" : "sitl-tri",
|
||||
|
|
|
@ -296,6 +296,11 @@ case $FRAME in
|
|||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/SingleCopter.parm"
|
||||
;;
|
||||
coaxcopter*)
|
||||
BUILD_TARGET="sitl-coax"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/CoaxCopter.parm"
|
||||
;;
|
||||
IrisRos)
|
||||
BUILD_TARGET="sitl"
|
||||
DEFAULTS_PATH="$autotest/copter_params.parm"
|
||||
|
|
Loading…
Reference in New Issue