diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index c3baa6fd95..b7e0605544 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -6615,9 +6615,6 @@ class AutoTestCopter(AutoTest): 'heli-compound': "wrong binary, different takeoff regime", 'heli-dual': "wrong binary, different takeoff regime", 'heli': "wrong binary, different takeoff regime", - 'hexa-cwx': "does not take off", - 'hexa-dji': "does not take off", - 'octa-quad-cwx': "does not take off", 'tri': "does not take off", } for frame in sorted(copter_vinfo_options["frames"].keys()): diff --git a/Tools/autotest/default_params/copter-hexa-cwx.parm b/Tools/autotest/default_params/copter-hexa-cwx.parm new file mode 100644 index 0000000000..377111fbba --- /dev/null +++ b/Tools/autotest/default_params/copter-hexa-cwx.parm @@ -0,0 +1,2 @@ +FRAME_CLASS 2 +FRAME_TYPE 14 diff --git a/Tools/autotest/default_params/copter-hexa-dji.parm b/Tools/autotest/default_params/copter-hexa-dji.parm new file mode 100644 index 0000000000..7ab37d3243 --- /dev/null +++ b/Tools/autotest/default_params/copter-hexa-dji.parm @@ -0,0 +1,2 @@ +FRAME_CLASS 2 +FRAME_TYPE 13 diff --git a/Tools/autotest/default_params/copter-octaquad-cwx.parm b/Tools/autotest/default_params/copter-octaquad-cwx.parm new file mode 100644 index 0000000000..604c8e1e8e --- /dev/null +++ b/Tools/autotest/default_params/copter-octaquad-cwx.parm @@ -0,0 +1,2 @@ +FRAME_CLASS 4 +FRAME_TYPE 14 diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 0d727a3b07..10316bcd1f 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -50,11 +50,19 @@ class VehicleInfo(object): }, "hexa-cwx": { "waf_target": "bin/arducopter", - "default_params_filename": "default_params/copter.parm", + "default_params_filename": [ + "default_params/copter.parm", + "default_params/copter-hexa.parm", + "default_params/copter-hexa-cwx.parm" + ], }, "hexa-dji": { "waf_target": "bin/arducopter", - "default_params_filename": "default_params/copter.parm", + "default_params_filename": [ + "default_params/copter.parm", + "default_params/copter-hexa.parm", + "default_params/copter-hexa-dji.parm" + ], }, "octa-cwx": { "waf_target": "bin/arducopter", @@ -66,7 +74,11 @@ class VehicleInfo(object): }, "octa-quad-cwx": { "waf_target": "bin/arducopter", - "default_params_filename": "default_params/copter.parm", + "default_params_filename": [ + "default_params/copter.parm", + "default_params/copter-octaquad.parm", + "default_params/copter-octaquad-cwx.parm" + ], }, "octa-quad": { "waf_target": "bin/arducopter",