mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: add test which flies each frame we can
This commit is contained in:
parent
6f5626d04f
commit
63ba484087
@ -19,6 +19,7 @@ from pymavlink import mavextra
|
||||
from pymavlink import rotmat
|
||||
|
||||
from pysim import util
|
||||
from pysim import vehicleinfo
|
||||
|
||||
from common import AutoTest
|
||||
from common import NotAchievedException, AutoTestTimeoutException, PreconditionFailedException
|
||||
@ -6480,6 +6481,50 @@ class AutoTestCopter(AutoTest):
|
||||
self.takeoff(10)
|
||||
self.do_RTL()
|
||||
|
||||
def fly_each_frame(self):
|
||||
vinfo = vehicleinfo.VehicleInfo()
|
||||
copter_vinfo_options = vinfo.options[self.vehicleinfo_key()]
|
||||
known_broken_frames = {
|
||||
'cwx': "missing defaults file",
|
||||
'deca-cwx': "doesn't take off",
|
||||
'djix': "missing defaults file",
|
||||
'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-cwx': "does not take off",
|
||||
'octa-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()):
|
||||
self.start_subtest("Testing frame (%s)" % str(frame))
|
||||
if frame in known_broken_frames:
|
||||
self.progress("Actually, no I'm not - it is known-broken (%s)" %
|
||||
(known_broken_frames[frame]))
|
||||
continue
|
||||
frame_bits = copter_vinfo_options["frames"][frame]
|
||||
print("frame_bits: %s" % str(frame_bits))
|
||||
if frame_bits.get("external", False):
|
||||
self.progress("Actually, no I'm not - it is an external simulation")
|
||||
continue
|
||||
model = frame_bits.get("model", frame)
|
||||
# the model string for Callisto has crap in it.... we
|
||||
# should really have another entry in the vehicleinfo data
|
||||
# to carry the path to the JSON.
|
||||
actual_model = model.split(":")[0]
|
||||
defaults = self.model_defaults_filepath("ArduCopter", actual_model)
|
||||
if type(defaults) != list:
|
||||
defaults = [defaults]
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(defaults), ],
|
||||
model=model,
|
||||
wipe=True,
|
||||
)
|
||||
self.takeoff(10)
|
||||
self.do_RTL()
|
||||
|
||||
def test_replay(self):
|
||||
'''test replay correctness'''
|
||||
self.progress("Building Replay")
|
||||
@ -6939,6 +6984,10 @@ class AutoTestCopter(AutoTest):
|
||||
"Check GSF",
|
||||
self.test_gsf),
|
||||
|
||||
Test("FlyEachFrame",
|
||||
"Fly each supported internal frame",
|
||||
self.fly_each_frame),
|
||||
|
||||
Test("GPSBlending",
|
||||
"Test GPS Blending",
|
||||
self.test_gps_blending),
|
||||
|
@ -106,16 +106,19 @@ class VehicleInfo(object):
|
||||
"IrisRos": {
|
||||
"waf_target": "bin/arducopter",
|
||||
"default_params_filename": "default_params/copter.parm",
|
||||
"external": True,
|
||||
},
|
||||
"gazebo-iris": {
|
||||
"waf_target": "bin/arducopter",
|
||||
"default_params_filename": ["default_params/copter.parm",
|
||||
"default_params/gazebo-iris.parm"],
|
||||
"external": True,
|
||||
},
|
||||
"airsim-copter": {
|
||||
"waf_target": "bin/arducopter",
|
||||
"default_params_filename": ["default_params/copter.parm",
|
||||
"default_params/airsim-quadX.parm"],
|
||||
"external": True,
|
||||
},
|
||||
# HELICOPTER
|
||||
"heli": {
|
||||
@ -142,9 +145,11 @@ class VehicleInfo(object):
|
||||
"scrimmage-copter" : {
|
||||
"waf_target": "bin/arducopter",
|
||||
"default_params_filename": "default_params/copter.parm",
|
||||
"external": True,
|
||||
},
|
||||
"calibration": {
|
||||
"extra_mavlink_cmds": "module load sitl_calibration;",
|
||||
"external": True, # lies! OTOH, hard to take off with this
|
||||
},
|
||||
"Callisto": {
|
||||
"model": "octa-quad:@ROMFS/models/Callisto.json",
|
||||
|
Loading…
Reference in New Issue
Block a user