mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
autotest: Fixed blimp default params
This commit is contained in:
parent
f77e64ac83
commit
aa643e5637
@ -12,43 +12,46 @@ COMPASS_OFS3_X 5
|
|||||||
COMPASS_OFS3_Y 13
|
COMPASS_OFS3_Y 13
|
||||||
COMPASS_OFS3_Z -18
|
COMPASS_OFS3_Z -18
|
||||||
FRAME_CLASS 1
|
FRAME_CLASS 1
|
||||||
RC1_MAX 2000.000000
|
RC1_MAX 2000
|
||||||
RC1_MIN 1000.000000
|
RC1_MIN 1000
|
||||||
RC1_TRIM 1500.000000
|
RC1_TRIM 1500
|
||||||
RC2_MAX 2000.000000
|
RC2_MAX 2000
|
||||||
RC2_MIN 1000.000000
|
RC2_MIN 1000
|
||||||
RC2_TRIM 1500.000000
|
RC2_TRIM 1500
|
||||||
RC3_MAX 2000.000000
|
RC3_MAX 2000
|
||||||
RC3_MIN 1000.000000
|
RC3_MIN 1000
|
||||||
RC3_TRIM 1500.000000
|
RC3_TRIM 1500
|
||||||
RC4_MAX 2000.000000
|
RC4_MAX 2000
|
||||||
RC4_MIN 1000.000000
|
RC4_MIN 1000
|
||||||
RC4_TRIM 1500.000000
|
RC4_TRIM 1500
|
||||||
RC5_MAX 2000.000000
|
RC5_MAX 2000
|
||||||
RC5_MIN 1000.000000
|
RC5_MIN 1000
|
||||||
RC5_TRIM 1500.000000
|
RC5_TRIM 1500
|
||||||
RC6_MAX 2000.000000
|
RC6_MAX 2000
|
||||||
RC6_MIN 1000.000000
|
RC6_MIN 1000
|
||||||
RC6_TRIM 1500.000000
|
RC6_TRIM 1500
|
||||||
RC7_MAX 2000.000000
|
RC7_MAX 2000
|
||||||
RC7_MIN 1000.000000
|
RC7_MIN 1000
|
||||||
RC7_TRIM 1500.000000
|
RC7_TRIM 1500
|
||||||
RC8_MAX 2000.000000
|
RC8_MAX 2000
|
||||||
RC8_MIN 1000.000000
|
RC8_MIN 1000
|
||||||
RC8_TRIM 1500.000000
|
RC8_TRIM 1500
|
||||||
|
|
||||||
# setting servo functions for the four fins
|
# setting servo functions for the four fins
|
||||||
SERVO1_FUNCTION 33
|
SERVO1_FUNCTION 33
|
||||||
SERVO1_FUNCTION 34
|
SERVO2_FUNCTION 34
|
||||||
SERVO1_FUNCTION 35
|
SERVO3_FUNCTION 35
|
||||||
SERVO1_FUNCTION 36
|
SERVO4_FUNCTION 36
|
||||||
|
|
||||||
|
FLTMODE1 0
|
||||||
|
FLTMODE2 1
|
||||||
|
FLTMODE3 2
|
||||||
|
FLTMODE4 3
|
||||||
|
FLTMODE5 1
|
||||||
|
FLTMODE6 1
|
||||||
|
|
||||||
FLTMODE1 7
|
|
||||||
FLTMODE2 9
|
|
||||||
FLTMODE3 6
|
|
||||||
FLTMODE4 3
|
|
||||||
FLTMODE5 5
|
|
||||||
FLTMODE6 0
|
|
||||||
SIM_BARO_RND 0
|
SIM_BARO_RND 0
|
||||||
|
|
||||||
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
# we need small INS_ACC offsets so INS is recognised as being calibrated
|
||||||
INS_ACCOFFS_X 0.001
|
INS_ACCOFFS_X 0.001
|
||||||
INS_ACCOFFS_Y 0.001
|
INS_ACCOFFS_Y 0.001
|
||||||
@ -68,20 +71,6 @@ INS_ACC3OFFS_Z 0.000
|
|||||||
INS_ACC3SCAL_X 1.000
|
INS_ACC3SCAL_X 1.000
|
||||||
INS_ACC3SCAL_Y 1.000
|
INS_ACC3SCAL_Y 1.000
|
||||||
INS_ACC3SCAL_Z 1.000
|
INS_ACC3SCAL_Z 1.000
|
||||||
# flightmodes
|
|
||||||
# switch 1 Circle
|
ARMING_RUDDER 0
|
||||||
# switch 2 LAND
|
GCS_PID_MASK 255
|
||||||
# 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 !
|
|
||||||
|
@ -206,11 +206,9 @@ class VehicleInfo(object):
|
|||||||
},
|
},
|
||||||
},
|
},
|
||||||
"Blimp": {
|
"Blimp": {
|
||||||
"default_frame": "quad",
|
"default_frame": "Blimp",
|
||||||
"frames": {
|
"frames": {
|
||||||
# BLIMP
|
"Blimp": {
|
||||||
"quad": {
|
|
||||||
"model": "+",
|
|
||||||
"waf_target": "bin/blimp",
|
"waf_target": "bin/blimp",
|
||||||
"default_params_filename": "default_params/blimp.parm",
|
"default_params_filename": "default_params/blimp.parm",
|
||||||
},
|
},
|
||||||
|
Loading…
Reference in New Issue
Block a user