mirror of https://github.com/ArduPilot/ardupilot
autotest: added plane-jet parameters
This commit is contained in:
parent
e52d447c08
commit
f8c5f7ca9c
|
@ -0,0 +1,32 @@
|
||||||
|
ALT_HOLD_RTL 20000.0000
|
||||||
|
ARSPD_FBW_MAX 80.0000
|
||||||
|
ARSPD_FBW_MIN 25.0000
|
||||||
|
FBWB_CLIMB_RATE 5.0000
|
||||||
|
LAND_FLARE_SEC 2.0000
|
||||||
|
LIM_PITCH_MAX 2000.0000
|
||||||
|
LIM_PITCH_MIN -2500.0000
|
||||||
|
LIM_ROLL_CD 7000.0000
|
||||||
|
NAVL1_PERIOD 17.0000
|
||||||
|
PTCH2SRV_D 0.0900
|
||||||
|
PTCH2SRV_FF 0.1800
|
||||||
|
PTCH2SRV_I 1.0000
|
||||||
|
PTCH2SRV_P 1.7000
|
||||||
|
PTCH2SRV_RLL 1.0400
|
||||||
|
RLL2SRV_D 0.1300
|
||||||
|
RLL2SRV_FF 0.3000
|
||||||
|
RLL2SRV_I 1.0000
|
||||||
|
RLL2SRV_P 1.3000
|
||||||
|
RLL2SRV_RMAX 70.0000
|
||||||
|
SCALING_SPEED 40.0000
|
||||||
|
TECS_CLMB_MAX 15.0000
|
||||||
|
TECS_LAND_ARSPD 30.0000
|
||||||
|
TECS_RLL2THR 5.0000
|
||||||
|
TECS_SINK_MAX 8.5000
|
||||||
|
TECS_SINK_MIN 10.0000
|
||||||
|
THR_SLEWRATE 30.0000
|
||||||
|
TKOFF_ROTATE_SPD 20.0000
|
||||||
|
TKOFF_THR_MAX 100.0000
|
||||||
|
TRIM_ARSPD_CM 4000.0000
|
||||||
|
TRIM_THROTTLE 36.0000
|
||||||
|
WP_LOITER_RAD 180.0000
|
||||||
|
WP_RADIUS 140.0000
|
|
@ -155,6 +155,10 @@ class VehicleInfo(object):
|
||||||
"waf_target": "bin/arduplane",
|
"waf_target": "bin/arduplane",
|
||||||
"default_params_filename": "default_params/plane-tailsitter.parm",
|
"default_params_filename": "default_params/plane-tailsitter.parm",
|
||||||
},
|
},
|
||||||
|
"plane-jet": {
|
||||||
|
"waf_target": "bin/arduplane",
|
||||||
|
"default_params_filename": ["default_params/plane.parm", "default_params/plane-jet.parm"],
|
||||||
|
},
|
||||||
"plane": {
|
"plane": {
|
||||||
"waf_target": "bin/arduplane",
|
"waf_target": "bin/arduplane",
|
||||||
"default_params_filename": "default_params/plane.parm",
|
"default_params_filename": "default_params/plane.parm",
|
||||||
|
|
Loading…
Reference in New Issue