From a8ea84a729dac062373cedc46941c12513b54762 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 31 Jul 2018 11:47:49 +0200 Subject: [PATCH] Tools: autotest: clean function arguments --- Tools/autotest/arducopter.py | 25 ++++++++++++------------- Tools/autotest/arduplane.py | 10 +++------- 2 files changed, 15 insertions(+), 20 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index bf4780007f..a52801b8d4 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -151,7 +151,7 @@ class AutoTestCopter(AutoTest): self.set_rc(3, 1000) self.arm_vehicle() self.set_rc(3, takeoff_throttle) - self.wait_for_alt(alt_min=30) + self.wait_for_alt(alt_min=alt_min) self.hover() self.progress("TAKEOFF COMPLETE") @@ -168,9 +168,9 @@ class AutoTestCopter(AutoTest): """Land the quad.""" self.progress("STARTING LANDING") self.mavproxy.send('switch 2\n') # land mode - self.wait_mode('LAND') + self.wait_mode('LAND', timeout=timeout) self.progress("Entered Landing Mode") - self.wait_altitude(-5, 1, relative=True) + self.wait_altitude(-5, 1, relative=True, timeout=timeout) self.progress("LANDING: ok!") def hover(self, hover_throttle=1500): @@ -321,7 +321,7 @@ class AutoTestCopter(AutoTest): self.save_wp() # enter RTL mode and wait for the vehicle to disarm - def fly_RTL(self, side=60, timeout=250): + def fly_RTL(self, timeout=250): """Return, land.""" self.progress("# Enter RTL") self.mavproxy.send('switch 3\n') @@ -406,7 +406,7 @@ class AutoTestCopter(AutoTest): self.wait_mode('STABILIZE') raise AutoTestTimeoutException() - def fly_battery_failsafe(self, timeout=30): + def fly_battery_failsafe(self, timeout=300): # switch to loiter mode so that we hold position self.mavproxy.send('switch 5\n') self.wait_mode('LOITER') @@ -419,7 +419,7 @@ class AutoTestCopter(AutoTest): self.set_parameter('SIM_BATT_VOLTAGE', 10) # wait for LAND mode. If unsuccessful an exception will be raised - self.wait_mode('LAND', 300) + self.wait_mode('LAND', timeout=timeout) # disable battery failsafe self.set_parameter('BATT_FS_LOW_ACT', 0) @@ -553,7 +553,7 @@ class AutoTestCopter(AutoTest): raise AutoTestTimeoutException() # fly_alt_fence_test - fly up until you hit the fence - def fly_alt_max_fence_test(self, timeout=180): + def fly_alt_max_fence_test(self): """Hold loiter position.""" self.mavproxy.send('switch 5\n') # loiter mode self.wait_mode('LOITER') @@ -809,7 +809,7 @@ class AutoTestCopter(AutoTest): # fly_simple - assumes the simple bearing is initialised to be # directly north flies a box with 100m west, 15 seconds north, # 50 seconds east, 15 seconds south - def fly_simple(self, side=50, timeout=120): + def fly_simple(self, side=50): # hold position in loiter self.mavproxy.send('switch 5\n') # loiter mode @@ -900,7 +900,7 @@ class AutoTestCopter(AutoTest): self.hover() # fly_circle - flies a circle with 20m radius - def fly_circle(self, maxaltchange=10, holdtime=36): + def fly_circle(self, holdtime=36): # hold position in loiter self.mavproxy.send('switch 5\n') # loiter mode self.wait_mode('LOITER') @@ -1143,7 +1143,7 @@ class AutoTestCopter(AutoTest): return True - def fly_mission(self, height_accuracy=-1.0, target_altitude=None): + def fly_mission(self,): """Fly a mission from a file.""" global num_wp self.progress("test: Fly a mission from 1 to %u" % num_wp) @@ -1685,8 +1685,7 @@ class AutoTestCopter(AutoTest): # fly the stored mission self.run_test("Fly CH7 saved mission", - lambda: self.fly_mission(height_accuracy=0.5, - target_altitude=10)) + lambda: self.fly_mission) # Throttle Failsafe self.run_test("Test Failsafe", @@ -1721,7 +1720,7 @@ class AutoTestCopter(AutoTest): # Fence test self.run_test("Test Max Alt Fence", - lambda: self.fly_alt_max_fence_test(180)) + lambda: self.fly_alt_max_fence_test) # Takeoff self.run_test("Takeoff to test GPS glitch loiter", diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index ff65839621..b6397d206c 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -312,7 +312,6 @@ class AutoTestPlane(AutoTest): self.mavproxy.send("mode STABILIZE\n") self.wait_mode('STABILIZE') - count = 1 while count > 0: self.progress("Starting roll") self.set_rc(1, 2000) @@ -341,7 +340,6 @@ class AutoTestPlane(AutoTest): self.mavproxy.send("mode ACRO\n") self.wait_mode('ACRO') - count = 1 while count > 0: self.progress("Starting roll") self.set_rc(1, 1000) @@ -376,7 +374,7 @@ class AutoTestPlane(AutoTest): self.set_rc(3, 1700) return self.wait_level_flight() - def test_FBWB(self, count=1, mode='FBWB'): + def test_FBWB(self, mode='FBWB'): """Fly FBWB or CRUISE mode.""" self.mavproxy.send("mode %s\n" % mode) self.wait_mode(mode) @@ -440,7 +438,7 @@ class AutoTestPlane(AutoTest): return self.wait_level_flight() - def fly_mission(self, filename, height_accuracy=-1, target_altitude=None): + def fly_mission(self, filename): """Fly a mission from a file.""" self.progress("Flying mission %s" % filename) self.mavproxy.send('wp load %s\n' % filename) @@ -500,9 +498,7 @@ class AutoTestPlane(AutoTest): self.run_test("Mission test", lambda: self.fly_mission( - os.path.join(testdir, "ap1.txt"), - height_accuracy=10, - target_altitude=self.homeloc.alt+100)) + os.path.join(testdir, "ap1.txt"))) self.run_test("Log download", lambda: self.log_download(