mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
autotest: added Y6 to sim_vehicle.sh
This commit is contained in:
parent
21fb38da8f
commit
bcc4a653d7
@ -263,6 +263,11 @@ case $FRAME in
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/tri_params.parm"
|
||||
;;
|
||||
y6*)
|
||||
BUILD_TARGET="sitl-y6"
|
||||
MODEL="$FRAME"
|
||||
DEFAULTS_PATH="$autotest/y6_params.parm"
|
||||
;;
|
||||
heli*)
|
||||
BUILD_TARGET="sitl-heli"
|
||||
MODEL="$FRAME"
|
||||
|
89
Tools/autotest/y6_params.parm
Normal file
89
Tools/autotest/y6_params.parm
Normal file
@ -0,0 +1,89 @@
|
||||
EK2_ENABLE 1
|
||||
FRAME 0
|
||||
MAG_ENABLE 1
|
||||
FS_THR_ENABLE 1
|
||||
BATT_MONITOR 4
|
||||
CH7_OPT 7
|
||||
COMPASS_LEARN 0
|
||||
COMPASS_OFS_X 5
|
||||
COMPASS_OFS_Y 13
|
||||
COMPASS_OFS_Z -18
|
||||
COMPASS_OFS2_X 5
|
||||
COMPASS_OFS2_Y 13
|
||||
COMPASS_OFS2_Z -18
|
||||
FENCE_RADIUS 150
|
||||
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
|
||||
FLTMODE1 7
|
||||
FLTMODE2 9
|
||||
FLTMODE3 6
|
||||
FLTMODE4 3
|
||||
FLTMODE5 5
|
||||
FLTMODE6 0
|
||||
SUPER_SIMPLE 0
|
||||
SIM_GPS_DELAY 1
|
||||
SIM_ACC_RND 0
|
||||
SIM_GYR_RND 0
|
||||
SIM_WIND_SPD 0
|
||||
SIM_WIND_TURB 0
|
||||
SIM_BARO_RND 0
|
||||
SIM_MAG_RND 0
|
||||
SIM_GPS_GLITCH_X 0
|
||||
SIM_GPS_GLITCH_Y 0
|
||||
SIM_GPS_GLITCH_Z 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_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
|
||||
MOT_THST_EXPO 0.5
|
||||
# autotune results
|
||||
ATC_RATE_FF_ENAB 1.000000
|
||||
ATC_RAT_PIT_D 0.002706
|
||||
ATC_RAT_PIT_I 0.331873
|
||||
ATC_RAT_PIT_IMAX 0.444000
|
||||
ATC_RAT_PIT_P 0.331873
|
||||
ATC_RAT_RLL_D 0.003133
|
||||
ATC_RAT_RLL_I 0.349340
|
||||
ATC_RAT_RLL_IMAX 0.444000
|
||||
ATC_RAT_RLL_P 0.349340
|
||||
ATC_RAT_YAW_D 0.000000
|
||||
ATC_RAT_YAW_I 0.060954
|
||||
ATC_RAT_YAW_IMAX 0.222000
|
||||
ATC_RAT_YAW_P 0.609544
|
Loading…
Reference in New Issue
Block a user