Tools: autotest: add some tests for Copter parachute functions

This commit is contained in:
Peter Barker 2019-01-09 12:40:49 +11:00 committed by Peter Barker
parent 9253e9b381
commit 55f751a8f4
3 changed files with 57 additions and 5 deletions

View File

@ -1504,6 +1504,54 @@ class AutoTestCopter(AutoTest):
if ex is not None: if ex is not None:
raise ex raise ex
def test_parachute(self):
self.set_rc(9, 1000)
self.set_parameter("CHUTE_ENABLED", 1)
self.set_parameter("CHUTE_TYPE", 10)
self.set_parameter("SERVO9_FUNCTION", 27)
self.set_parameter("SIM_PARA_ENABLE", 1)
self.set_parameter("SIM_PARA_PIN", 9)
self.progress("Testing three-position switch")
self.set_parameter("RC9_OPTION", 23) # parachute 3pos
self.progress("Test manual triggering")
self.takeoff(20)
self.set_rc(9, 2000)
self.mavproxy.expect('BANG')
self.set_rc(9, 1000)
self.reboot_sitl()
self.context_push()
self.progress("Crashing with 3pos switch in enable position")
self.takeoff(40)
self.set_rc(9, 1500)
self.set_parameter("SIM_ENGINE_MUL", 0)
self.set_parameter("SIM_ENGINE_FAIL", 1)
self.mavproxy.expect('BANG')
self.set_rc(9, 1000)
self.reboot_sitl()
self.context_pop();
self.progress("Crashing with 3pos switch in disable position")
loiter_alt = 10
self.takeoff(loiter_alt, mode='LOITER')
self.set_rc(9, 1100)
self.set_parameter("SIM_ENGINE_MUL", 0)
self.set_parameter("SIM_ENGINE_FAIL", 1)
tstart = self.get_sim_time()
while self.get_sim_time_cached() < tstart + 5:
m = self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=1)
if m is None:
continue
if "BANG" in m.text:
self.set_rc(9, 1000)
self.reboot_sitl()
raise NotAchievedException("Parachute deployed when disabled")
self.set_rc(9, 1000)
self.reboot_sitl()
def fly_precision_sitl(self): def fly_precision_sitl(self):
"""Use SITL PrecLand backend precision messages to land aircraft.""" """Use SITL PrecLand backend precision messages to land aircraft."""
@ -2612,6 +2660,10 @@ class AutoTestCopter(AutoTest):
"Test RangeFinder Basic Functionality", "Test RangeFinder Basic Functionality",
self.test_rangefinder), self.test_rangefinder),
("Parachute",
"Test Parachute Functionality",
self.test_parachute),
("LogDownLoad", ("LogDownLoad",
"Log download", "Log download",
lambda: self.log_download( lambda: self.log_download(

View File

@ -690,11 +690,6 @@ class AutoTestPlane(AutoTest):
if ex is not None: if ex is not None:
raise ex raise ex
def start_subtest(self, description):
self.progress("-")
self.progress("---------- %s ----------" % description)
self.progress("-")
def run_subtest(self, desc, func): def run_subtest(self, desc, func):
self.start_subtest(desc) self.start_subtest(desc)
func() func()

View File

@ -2003,6 +2003,11 @@ switch value'''
self.progress("Waiting for mode-switch mode %s" % want) self.progress("Waiting for mode-switch mode %s" % want)
self.wait_mode(want) self.wait_mode(want)
def start_subtest(self, description):
self.progress("-")
self.progress("---------- %s ----------" % description)
self.progress("-")
def run_tests(self, tests): def run_tests(self, tests):
"""Autotest vehicle in SITL.""" """Autotest vehicle in SITL."""
self.check_test_syntax(test_file=os.path.realpath(__file__)) self.check_test_syntax(test_file=os.path.realpath(__file__))