diff --git a/Tools/autotest/default_params/plane-ice.parm b/Tools/autotest/default_params/plane-ice.parm new file mode 100644 index 0000000000..28b135b98e --- /dev/null +++ b/Tools/autotest/default_params/plane-ice.parm @@ -0,0 +1,7 @@ +ICE_ENABLE 1 +ICE_RPM_CHAN 1 +SERVO13_FUNCTION 67 +SERVO14_FUNCTION 69 +ICE_START_CHAN 7 +RPM1_TYPE 10 +SERVO3_REVERSED 1 diff --git a/Tools/autotest/default_params/quadplane-ice.parm b/Tools/autotest/default_params/quadplane-ice.parm new file mode 100644 index 0000000000..9b645e2e46 --- /dev/null +++ b/Tools/autotest/default_params/quadplane-ice.parm @@ -0,0 +1 @@ +Q_OPTIONS 64 diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index db8715b1cf..e44482ddfe 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -246,6 +246,10 @@ class VehicleInfo(object): "waf_target": "bin/arduplane", "default_params_filename": "default_params/quadplane.parm", }, + "quadplane-ice": { + "waf_target": "bin/arduplane", + "default_params_filename": ["default_params/quadplane.parm", "default_params/plane-ice.parm", "default_params/quadplane-ice.parm"], + }, "firefly": { "waf_target": "bin/arduplane", "default_params_filename": "default_params/firefly.parm", @@ -266,6 +270,10 @@ class VehicleInfo(object): "waf_target": "bin/arduplane", "default_params_filename": ["default_params/plane.parm", "default_params/plane-jet.parm"], }, + "plane-ice": { + "waf_target": "bin/arduplane", + "default_params_filename": ["default_params/plane.parm", "default_params/plane-ice.parm"], + }, "quadplane-copter_tailsitter": { "waf_target": "bin/arduplane", "default_params_filename": ["default_params/quadplane.parm","default_params/quadplane-copter_tailsitter.parm"],