Tools: Add SITL tilthvec frame and default parameters
This commit is contained in:
parent
93b3970141
commit
6bc4ab638a
14
Tools/autotest/default_params/quadplane-tilthvec.parm
Normal file
14
Tools/autotest/default_params/quadplane-tilthvec.parm
Normal file
@ -0,0 +1,14 @@
|
|||||||
|
LIM_PITCH_MAX 3000
|
||||||
|
LIM_PITCH_MIN -3000
|
||||||
|
Q_ENABLE 1
|
||||||
|
Q_FRAME_CLASS 1
|
||||||
|
Q_FRAME_TYPE 3
|
||||||
|
Q_RTL_MODE 1
|
||||||
|
Q_TILT_TYPE 2
|
||||||
|
Q_TILT_YAW_ANGLE 10
|
||||||
|
Q_TILT_MASK 15
|
||||||
|
Q_VFWD_GAIN 0.1
|
||||||
|
Q_ANGLE_MAX 4500
|
||||||
|
Q_ASSIST_SPEED 6
|
||||||
|
SERVO12_FUNCTION 76
|
||||||
|
SERVO13_FUNCTION 75
|
@ -120,6 +120,11 @@ class VehicleInfo(object):
|
|||||||
"waf_target": "bin/arduplane",
|
"waf_target": "bin/arduplane",
|
||||||
"default_params_filename": "default_params/quadplane-tilttrivec.parm",
|
"default_params_filename": "default_params/quadplane-tilttrivec.parm",
|
||||||
},
|
},
|
||||||
|
"quadplane-tilthvec": {
|
||||||
|
"make_target": "sitl",
|
||||||
|
"waf_target": "bin/arduplane",
|
||||||
|
"default_params_filename": ["default_params/plane.parm", "default_params/quadplane-tilthvec.parm"],
|
||||||
|
},
|
||||||
"quadplane-tri": {
|
"quadplane-tri": {
|
||||||
"make_target": "sitl",
|
"make_target": "sitl",
|
||||||
"waf_target": "bin/arduplane",
|
"waf_target": "bin/arduplane",
|
||||||
|
Loading…
Reference in New Issue
Block a user