autotest: fly each working Helicopter frame
This commit is contained in:
parent
757fc1d679
commit
6944ef6af1
@ -96,7 +96,7 @@ class AutoTestCopter(AutoTest):
|
||||
pass
|
||||
|
||||
def defaults_filepath(self):
|
||||
return self.model_defaults_filepath(self.vehicleinfo_key(), self.frame)
|
||||
return self.model_defaults_filepath(self.frame)
|
||||
|
||||
def wait_disarmed_default_wait_time(self):
|
||||
return 120
|
||||
@ -5646,7 +5646,7 @@ class AutoTestCopter(AutoTest):
|
||||
ex = None
|
||||
try:
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(self.model_defaults_filepath('ArduCopter', 'Callisto'))],
|
||||
["--defaults", ','.join(self.model_defaults_filepath('Callisto'))],
|
||||
model="octa-quad:@ROMFS/models/Callisto.json",
|
||||
wipe=True,
|
||||
)
|
||||
@ -6598,7 +6598,7 @@ class AutoTestCopter(AutoTest):
|
||||
|
||||
def test_callisto(self):
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(self.model_defaults_filepath('ArduCopter', 'Callisto')), ],
|
||||
["--defaults", ','.join(self.model_defaults_filepath('Callisto')), ],
|
||||
model="octa-quad:@ROMFS/models/Callisto.json",
|
||||
wipe=True,
|
||||
)
|
||||
@ -6632,7 +6632,7 @@ class AutoTestCopter(AutoTest):
|
||||
# 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)
|
||||
defaults = self.model_defaults_filepath(actual_model)
|
||||
if type(defaults) != list:
|
||||
defaults = [defaults]
|
||||
self.customise_SITL_commandline(
|
||||
@ -7313,6 +7313,9 @@ class AutoTestCopter(AutoTest):
|
||||
|
||||
class AutoTestHeli(AutoTestCopter):
|
||||
|
||||
def vehicleinfo_key(self):
|
||||
return 'Helicopter'
|
||||
|
||||
def log_name(self):
|
||||
return "HeliCopter"
|
||||
|
||||
@ -7425,6 +7428,70 @@ class AutoTestHeli(AutoTestCopter):
|
||||
|
||||
self.progress("AVC mission completed: passed!")
|
||||
|
||||
def takeoff(self,
|
||||
alt_min=30,
|
||||
takeoff_throttle=1700,
|
||||
require_absolute=True,
|
||||
mode="STABILIZE",
|
||||
timeout=120):
|
||||
"""Takeoff get to 30m altitude."""
|
||||
self.progress("TAKEOFF")
|
||||
self.change_mode(mode)
|
||||
if not self.armed():
|
||||
self.wait_ready_to_arm(require_absolute=require_absolute, timeout=timeout)
|
||||
self.zero_throttle()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.progress("Raising rotor speed")
|
||||
self.set_rc(8, 2000)
|
||||
self.progress("wait for rotor runup to complete")
|
||||
self.wait_servo_channel_value(8, 1660, timeout=10)
|
||||
|
||||
if mode == 'GUIDED':
|
||||
self.user_takeoff(alt_min=alt_min)
|
||||
else:
|
||||
self.set_rc(3, takeoff_throttle)
|
||||
self.wait_for_alt(alt_min=alt_min, timeout=timeout)
|
||||
self.hover()
|
||||
self.progress("TAKEOFF COMPLETE")
|
||||
|
||||
def fly_each_frame(self):
|
||||
vinfo = vehicleinfo.VehicleInfo()
|
||||
vinfo_options = vinfo.options[self.vehicleinfo_key()]
|
||||
known_broken_frames = {
|
||||
}
|
||||
for frame in sorted(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 = 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(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()
|
||||
self.set_rc(8, 1000)
|
||||
|
||||
def hover(self):
|
||||
self.progress("Setting hover collective")
|
||||
self.set_rc(3, 1500)
|
||||
|
||||
def fly_heli_poshold_takeoff(self):
|
||||
"""ensure vehicle stays put until it is ready to fly"""
|
||||
self.context_push()
|
||||
@ -7453,8 +7520,7 @@ class AutoTestHeli(AutoTestCopter):
|
||||
self.progress("Pushing collective past half-way")
|
||||
self.set_rc(3, 1600)
|
||||
self.delay_sim_time(0.5)
|
||||
self.progress("Bringing back to hover collective")
|
||||
self.set_rc(3, 1500)
|
||||
self.hover()
|
||||
|
||||
# make sure we haven't already reached alt:
|
||||
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
@ -7609,6 +7675,10 @@ class AutoTestHeli(AutoTestCopter):
|
||||
"Fly AutoRotation",
|
||||
self.fly_autorotation),
|
||||
|
||||
("FlyEachFrame",
|
||||
"Fly each supported internal frame",
|
||||
self.fly_each_frame),
|
||||
|
||||
("LogUpload",
|
||||
"Log upload",
|
||||
self.log_upload),
|
||||
|
@ -2067,7 +2067,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.customise_SITL_commandline(
|
||||
[],
|
||||
model=model,
|
||||
defaults_filepath=self.model_defaults_filepath("ArduPlane", model),
|
||||
defaults_filepath=self.model_defaults_filepath(model),
|
||||
wipe=True)
|
||||
|
||||
self.load_mission('CMAC-soar.txt', strict=False)
|
||||
|
@ -1390,8 +1390,7 @@ class AutoTest(ABC):
|
||||
self.progress("Applying default parameters file")
|
||||
# setup test parameters
|
||||
if self.params is None:
|
||||
self.params = self.model_defaults_filepath(self.vehicleinfo_key(),
|
||||
self.frame)
|
||||
self.params = self.model_defaults_filepath(self.frame)
|
||||
for x in self.params:
|
||||
self.repeatedly_apply_parameter_file(os.path.join(testdir, x))
|
||||
|
||||
@ -10487,8 +10486,8 @@ switch value'''
|
||||
|
||||
return psd
|
||||
|
||||
def model_defaults_filepath(self, vehicle, model):
|
||||
|
||||
def model_defaults_filepath(self, model):
|
||||
vehicle = self.vehicleinfo_key()
|
||||
vinfo = vehicleinfo.VehicleInfo()
|
||||
defaults_filepath = vinfo.options[vehicle]["frames"][model]["default_params_filename"]
|
||||
if isinstance(defaults_filepath, str):
|
||||
|
@ -150,9 +150,6 @@ class VehicleInfo(object):
|
||||
"default_params_filename": ["default_params/copter-heli.parm",
|
||||
"default_params/copter-heli-dual.parm"],
|
||||
},
|
||||
"heli-compound": {
|
||||
"waf_target": "bin/arducopter-heli",
|
||||
},
|
||||
"singlecopter": {
|
||||
"waf_target": "bin/arducopter",
|
||||
"default_params_filename": "default_params/copter-single.parm",
|
||||
@ -179,6 +176,25 @@ class VehicleInfo(object):
|
||||
},
|
||||
},
|
||||
},
|
||||
"Helicopter": {
|
||||
"default_frame": "heli",
|
||||
"frames": {
|
||||
"heli": {
|
||||
"waf_target": "bin/arducopter-heli",
|
||||
"default_params_filename": "default_params/copter-heli.parm",
|
||||
},
|
||||
"heli-dual": {
|
||||
"waf_target": "bin/arducopter-heli",
|
||||
"default_params_filename": ["default_params/copter-heli.parm",
|
||||
"default_params/copter-heli-dual.parm"],
|
||||
},
|
||||
# "heli-compound": {
|
||||
# "waf_target": "bin/arducopter-heli",
|
||||
# "default_params_filename": ["default_params/copter-heli.parm",
|
||||
# "default_params/copter-heli-compound.parm"],
|
||||
# },
|
||||
},
|
||||
},
|
||||
"Blimp": {
|
||||
"default_frame": "quad",
|
||||
"frames": {
|
||||
|
@ -46,6 +46,9 @@ class AutoTestQuadPlane(AutoTest):
|
||||
def get_normal_armable_modes_list():
|
||||
return []
|
||||
|
||||
def vehicleinfo_key(self):
|
||||
return 'ArduPlane'
|
||||
|
||||
def default_frame(self):
|
||||
return "quadplane"
|
||||
|
||||
@ -71,7 +74,7 @@ class AutoTestQuadPlane(AutoTest):
|
||||
pass
|
||||
|
||||
def defaults_filepath(self):
|
||||
return self.model_defaults_filepath("ArduPlane", self.frame)
|
||||
return self.model_defaults_filepath(self.frame)
|
||||
|
||||
def is_plane(self):
|
||||
return True
|
||||
|
@ -5345,7 +5345,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
|
||||
self.customise_SITL_commandline([],
|
||||
model=model,
|
||||
defaults_filepath=self.model_defaults_filepath("Rover", model))
|
||||
defaults_filepath=self.model_defaults_filepath(model))
|
||||
|
||||
self.change_mode("MANUAL")
|
||||
self.wait_ready_to_arm()
|
||||
|
Loading…
Reference in New Issue
Block a user