mirror of https://github.com/ArduPilot/ardupilot
autotest: added blimp simulator type
This commit is contained in:
parent
7d42c3c834
commit
cd18e16ffb
|
@ -0,0 +1,87 @@
|
||||||
|
EK2_ENABLE 1
|
||||||
|
FRAME_TYPE 0
|
||||||
|
FS_THR_ENABLE 1
|
||||||
|
BATT_MONITOR 4
|
||||||
|
COMPASS_OFS_X 5
|
||||||
|
COMPASS_OFS_Y 13
|
||||||
|
COMPASS_OFS_Z -18
|
||||||
|
COMPASS_OFS2_X 5
|
||||||
|
COMPASS_OFS2_Y 13
|
||||||
|
COMPASS_OFS2_Z -18
|
||||||
|
COMPASS_OFS3_X 5
|
||||||
|
COMPASS_OFS3_Y 13
|
||||||
|
COMPASS_OFS3_Z -18
|
||||||
|
FRAME_CLASS 1
|
||||||
|
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
|
||||||
|
# setting servo functions for the four fins
|
||||||
|
SERVO1_FUNCTION 33
|
||||||
|
SERVO1_FUNCTION 34
|
||||||
|
SERVO1_FUNCTION 35
|
||||||
|
SERVO1_FUNCTION 36
|
||||||
|
|
||||||
|
FLTMODE1 7
|
||||||
|
FLTMODE2 9
|
||||||
|
FLTMODE3 6
|
||||||
|
FLTMODE4 3
|
||||||
|
FLTMODE5 5
|
||||||
|
FLTMODE6 0
|
||||||
|
SIM_BARO_RND 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
|
||||||
|
# flightmodes
|
||||||
|
# switch 1 Circle
|
||||||
|
# switch 2 LAND
|
||||||
|
# switch 3 RTL
|
||||||
|
# switch 4 Auto
|
||||||
|
# switch 5 Loiter
|
||||||
|
# switch 6 Stab
|
||||||
|
# STABILIZE 0 !
|
||||||
|
# ACRO 1
|
||||||
|
# ALT_HOLD 2
|
||||||
|
# AUTO 3 !
|
||||||
|
# GUIDED 4
|
||||||
|
# LOITER 5 !
|
||||||
|
# RTL 6 !
|
||||||
|
# CIRCLE 7 !
|
||||||
|
# POSITION 8
|
||||||
|
# LAND 9 !
|
|
@ -154,6 +154,17 @@ class VehicleInfo(object):
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
|
"Blimp": {
|
||||||
|
"default_frame": "quad",
|
||||||
|
"frames": {
|
||||||
|
# BLIMP
|
||||||
|
"quad": {
|
||||||
|
"model": "+",
|
||||||
|
"waf_target": "bin/blimp",
|
||||||
|
"default_params_filename": "default_params/blimp.parm",
|
||||||
|
},
|
||||||
|
},
|
||||||
|
},
|
||||||
"ArduPlane": {
|
"ArduPlane": {
|
||||||
"default_frame": "plane",
|
"default_frame": "plane",
|
||||||
"frames": {
|
"frames": {
|
||||||
|
|
Loading…
Reference in New Issue