Tools: autotest: flake8 compliance

This commit is contained in:
Peter Barker 2018-05-09 13:32:23 +10:00
parent 40cd0cd17f
commit 513865ae4d
5 changed files with 90 additions and 42 deletions

View File

@ -5,7 +5,6 @@ from __future__ import print_function
import os import os
import pexpect import pexpect
import shutil
import time import time
from common import AutoTest from common import AutoTest
@ -509,7 +508,8 @@ class AutoTestRover(AutoTest):
self.test_servorelayevents) self.test_servorelayevents)
self.run_test("Download logs", lambda: self.run_test("Download logs", lambda:
self.log_download(self.buildlogs_path("APMrover2-log.bin"))) self.log_download(
self.buildlogs_path("APMrover2-log.bin")))
# if not drive_left_circuit(self): # if not drive_left_circuit(self):
# self.progress("Failed left circuit") # self.progress("Failed left circuit")
# failed = True # failed = True
@ -519,7 +519,7 @@ class AutoTestRover(AutoTest):
except pexpect.TIMEOUT as e: except pexpect.TIMEOUT as e:
self.progress("Failed with timeout") self.progress("Failed with timeout")
self.fail_list.append( ("*timeout*", None) ) self.fail_list.append(("*timeout*", None))
self.close() self.close()

View File

@ -460,7 +460,7 @@ class AutoTestCopter(AutoTest):
# restore motor 1 to 100% efficiency # restore motor 1 to 100% efficiency
self.mavproxy.send('param set SIM_ENGINE_MUL 1.0\n') self.mavproxy.send('param set SIM_ENGINE_MUL 1.0\n')
self.progress("Stability patch and Loiter OK for %u seconds" % holdtime) self.progress("Stability patch and Loiter OK for %us" % holdtime)
# fly_fence_test - fly east until you hit the horizontal circular fence # fly_fence_test - fly east until you hit the horizontal circular fence
def fly_fence_test(self, timeout=180): def fly_fence_test(self, timeout=180):
@ -576,7 +576,8 @@ class AutoTestCopter(AutoTest):
self.mavproxy.send('arm check all\n') self.mavproxy.send('arm check all\n')
def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20): def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20):
"""fly_gps_glitch_loiter_test. Fly south east in loiter and test reaction to gps glitch.""" """fly_gps_glitch_loiter_test. Fly south east in loiter and test
reaction to gps glitch."""
self.mavproxy.send('switch 5\n') # loiter mode self.mavproxy.send('switch 5\n') # loiter mode
self.wait_mode('LOITER') self.wait_mode('LOITER')
@ -625,7 +626,6 @@ class AutoTestCopter(AutoTest):
tstart = self.get_sim_time() tstart = self.get_sim_time()
tnow = tstart tnow = tstart
start_pos = self.sim_location() start_pos = self.sim_location()
success = True
# initialise current glitch # initialise current glitch
glitch_current = 0 glitch_current = 0
@ -1023,59 +1023,75 @@ class AutoTestCopter(AutoTest):
self.run_test("Arm motors", self.arm_vehicle) self.run_test("Arm motors", self.arm_vehicle)
# Takeoff # Takeoff
self.run_test("Takeoff to test fly Square", lambda: self.takeoff(10)) self.run_test("Takeoff to test fly Square",
lambda: self.takeoff(10))
# Fly a square in Stabilize mode # Fly a square in Stabilize mode
self.run_test("Fly a square and save WPs with CH7", self.fly_square) self.run_test("Fly a square and save WPs with CH7",
self.fly_square)
# save the stored mission to file # save the stored mission to file
global num_wp global num_wp
num_wp = self.save_mission_to_file(os.path.join(testdir, "ch7_mission.txt")) num_wp = self.save_mission_to_file(os.path.join(testdir,
"ch7_mission.txt"))
if not num_wp: if not num_wp:
self.fail_list.append("save_mission_to_file") self.fail_list.append("save_mission_to_file")
self.progress("save_mission_to_file failed") self.progress("save_mission_to_file failed")
# fly the stored mission # fly the stored mission
self.run_test("Fly CH7 saved mission", lambda: self.fly_mission(height_accuracy=0.5, target_altitude=10)) self.run_test("Fly CH7 saved mission",
lambda: self.fly_mission(height_accuracy=0.5,
target_altitude=10))
# Throttle Failsafe # Throttle Failsafe
self.run_test("Test Failsafe", lambda: self.fly_throttle_failsafe) self.run_test("Test Failsafe",
lambda: self.fly_throttle_failsafe)
# Takeoff # Takeoff
self.run_test("Takeoff to test battery failsafe", lambda: self.takeoff(10)) self.run_test("Takeoff to test battery failsafe",
lambda: self.takeoff(10))
# Battery failsafe # Battery failsafe
self.run_test("Fly Battery Failsafe", lambda: self.fly_battery_failsafe) self.run_test("Fly Battery Failsafe",
lambda: self.fly_battery_failsafe)
# Takeoff # Takeoff
self.run_test("Takeoff to test stability patch", lambda: self.takeoff(10)) self.run_test("Takeoff to test stability patch",
lambda: self.takeoff(10))
# Stability patch # Stability patch
self.run_test("Fly stability patch", lambda: self.fly_stability_patch(30)) self.run_test("Fly stability patch",
lambda: self.fly_stability_patch(30))
# RTL # RTL
self.run_test("RTL after stab patch", lambda: self.fly_RTL) self.run_test("RTL after stab patch", lambda: self.fly_RTL)
# Takeoff # Takeoff
self.run_test("Takeoff to test horizontal fence", lambda: self.takeoff(10)) self.run_test("Takeoff to test horizontal fence",
lambda: self.takeoff(10))
# Fence test # Fence test
self.run_test("Test horizontal fence", lambda: self.fly_fence_test(180)) self.run_test("Test horizontal fence",
lambda: self.fly_fence_test(180))
# Fence test # Fence test
self.run_test("Test Max Alt Fence", lambda: self.fly_alt_max_fence_test(180)) self.run_test("Test Max Alt Fence",
lambda: self.fly_alt_max_fence_test(180))
# Takeoff # Takeoff
self.run_test("Takeoff to test GPS glitch loiter", lambda: self.takeoff(10)) self.run_test("Takeoff to test GPS glitch loiter",
lambda: self.takeoff(10))
# Fly GPS Glitch Loiter test # Fly GPS Glitch Loiter test
self.run_test("GPS Glitch Loiter Test", self.fly_gps_glitch_loiter_test) self.run_test("GPS Glitch Loiter Test",
self.fly_gps_glitch_loiter_test)
# RTL after GPS Glitch Loiter test # RTL after GPS Glitch Loiter test
self.run_test("RTL after GPS Glitch Loiter test", self.fly_RTL) self.run_test("RTL after GPS Glitch Loiter test", self.fly_RTL)
# Fly GPS Glitch test in auto mode # Fly GPS Glitch test in auto mode
self.run_test("GPS Glitch Auto Test", self.fly_gps_glitch_auto_test) self.run_test("GPS Glitch Auto Test",
self.fly_gps_glitch_auto_test)
# Takeoff # Takeoff
self.run_test("Takeoff to test loiter", lambda: self.takeoff(10)) self.run_test("Takeoff to test loiter", lambda: self.takeoff(10))
@ -1087,13 +1103,15 @@ class AutoTestCopter(AutoTest):
self.run_test("Loiter - climb to 30m", lambda: self.change_alt(30)) self.run_test("Loiter - climb to 30m", lambda: self.change_alt(30))
# Loiter Descend # Loiter Descend
self.run_test("Loiter - descend to 20m", lambda: self.change_alt(20)) self.run_test("Loiter - descend to 20m",
lambda: self.change_alt(20))
# RTL # RTL
self.run_test("RTL after Loiter climb/descend", self.fly_RTL) self.run_test("RTL after Loiter climb/descend", self.fly_RTL)
# Takeoff # Takeoff
self.run_test("Takeoff to test fly SIMPLE mode", lambda: self.takeoff(10)) self.run_test("Takeoff to test fly SIMPLE mode",
lambda: self.takeoff(10))
# Simple mode # Simple mode
self.run_test("Fly in SIMPLE mode", self.fly_simple) self.run_test("Fly in SIMPLE mode", self.fly_simple)
@ -1102,16 +1120,19 @@ class AutoTestCopter(AutoTest):
self.run_test("RTL after SIMPLE mode", self.fly_RTL) self.run_test("RTL after SIMPLE mode", self.fly_RTL)
# Takeoff # Takeoff
self.run_test("Takeoff to test circle in SUPER SIMPLE mode", lambda: self.takeoff(10)) self.run_test("Takeoff to test circle in SUPER SIMPLE mode",
lambda: self.takeoff(10))
# Fly a circle in super simple mode # Fly a circle in super simple mode
self.run_test("Fly a circle in SUPER SIMPLE mode", self.fly_super_simple) self.run_test("Fly a circle in SUPER SIMPLE mode",
self.fly_super_simple)
# RTL # RTL
self.run_test("RTL after SUPER SIMPLE mode", self.fly_RTL) self.run_test("RTL after SUPER SIMPLE mode", self.fly_RTL)
# Takeoff # Takeoff
self.run_test("Takeoff to test CIRCLE mode", lambda: self.takeoff(10)) self.run_test("Takeoff to test CIRCLE mode",
lambda: self.takeoff(10))
# Circle mode # Circle mode
self.run_test("Fly CIRCLE mode", self.fly_circle) self.run_test("Fly CIRCLE mode", self.fly_circle)
@ -1126,7 +1147,9 @@ class AutoTestCopter(AutoTest):
self.mav.motors_disarmed_wait() self.mav.motors_disarmed_wait()
# Download logs # Download logs
self.run_test("log download", lambda: self.log_download(self.buildlogs_path("ArduCopter-log.bin"))) self.run_test("log download",
lambda: self.log_download(
self.buildlogs_path("ArduCopter-log.bin")))
except pexpect.TIMEOUT as e: except pexpect.TIMEOUT as e:
self.progress("Failed with timeout") self.progress("Failed with timeout")
@ -1169,7 +1192,9 @@ class AutoTestCopter(AutoTest):
self.set_rc(8, 1000) self.set_rc(8, 1000)
# mission ends with disarm so should be ok to download logs now # mission ends with disarm so should be ok to download logs now
self.run_test("log download", lambda: self.log_download(self.buildlogs_path("Helicopter-log.bin"))) self.run_test("log download",
lambda: self.log_download(
self.buildlogs_path("Helicopter-log.bin")))
except pexpect.TIMEOUT as e: except pexpect.TIMEOUT as e:
self.fail_list.append("Failed with timeout") self.fail_list.append("Failed with timeout")

View File

@ -282,7 +282,7 @@ class AutoTestPlane(AutoTest):
self.wait_roll(150, accuracy=90) self.wait_roll(150, accuracy=90)
self.wait_roll(0, accuracy=90) self.wait_roll(0, accuracy=90)
except Exception as e: except Exception as e:
self.set_rc(1,1500) self.set_rc(1, 1500)
raise e raise e
count -= 1 count -= 1
@ -513,11 +513,15 @@ class AutoTestPlane(AutoTest):
self.run_test("CIRCLE test", self.fly_CIRCLE) self.run_test("CIRCLE test", self.fly_CIRCLE)
self.run_test("Mission test", lambda: self.fly_mission(os.path.join(testdir, "ap1.txt"), self.run_test("Mission test",
lambda: self.fly_mission(
os.path.join(testdir, "ap1.txt"),
height_accuracy=10, height_accuracy=10,
target_altitude=self.homeloc.alt+100)) target_altitude=self.homeloc.alt+100))
self.run_test("Log download", lambda: self.log_download(self.buildlogs_path("ArduPlane-log.bin"))) self.run_test("Log download",
lambda: self.log_download(
self.buildlogs_path("ArduPlane-log.bin")))
except pexpect.TIMEOUT as e: except pexpect.TIMEOUT as e:
self.progress("Failed with timeout") self.progress("Failed with timeout")

View File

@ -167,9 +167,13 @@ class AutoTestSub(AutoTest):
self.run_test("Dive manual", self.dive_manual) self.run_test("Dive manual", self.dive_manual)
self.run_test("Dive mission", lambda: self.dive_mission(os.path.join(testdir, "sub_mission.txt"))) self.run_test("Dive mission",
lambda: self.dive_mission(
os.path.join(testdir, "sub_mission.txt")))
self.run_test("Log download", lambda: self.log_download(self.buildlogs_path("ArduSub-log.bin"))) self.run_test("Log download",
lambda: self.log_download(
self.buildlogs_path("ArduSub-log.bin")))
except pexpect.TIMEOUT as e: except pexpect.TIMEOUT as e:
self.progress("Failed with timeout") self.progress("Failed with timeout")

View File

@ -28,61 +28,76 @@ class ErrorException(Exception):
"""Base class for other exceptions""" """Base class for other exceptions"""
pass pass
class AutoTestTimeoutException(ErrorException): class AutoTestTimeoutException(ErrorException):
pass pass
class WaitModeTimeout(AutoTestTimeoutException): class WaitModeTimeout(AutoTestTimeoutException):
"""Thrown when fails to achieve given mode change.""" """Thrown when fails to achieve given mode change."""
pass pass
class WaitAltitudeTimout(AutoTestTimeoutException): class WaitAltitudeTimout(AutoTestTimeoutException):
"""Thrown when fails to achieve given altitude range.""" """Thrown when fails to achieve given altitude range."""
pass pass
class WaitGroundSpeedTimeout(AutoTestTimeoutException): class WaitGroundSpeedTimeout(AutoTestTimeoutException):
"""Thrown when fails to achieve given ground speed range.""" """Thrown when fails to achieve given ground speed range."""
pass pass
class WaitRollTimeout(AutoTestTimeoutException): class WaitRollTimeout(AutoTestTimeoutException):
"""Thrown when fails to achieve given roll in degrees.""" """Thrown when fails to achieve given roll in degrees."""
pass pass
class WaitPitchTimeout(AutoTestTimeoutException): class WaitPitchTimeout(AutoTestTimeoutException):
"""Thrown when fails to achieve given pitch in degrees.""" """Thrown when fails to achieve given pitch in degrees."""
pass pass
class WaitHeadingTimeout(AutoTestTimeoutException): class WaitHeadingTimeout(AutoTestTimeoutException):
"""Thrown when fails to achieve given heading.""" """Thrown when fails to achieve given heading."""
pass pass
class WaitDistanceTimeout(AutoTestTimeoutException): class WaitDistanceTimeout(AutoTestTimeoutException):
"""Thrown when fails to attain distance""" """Thrown when fails to attain distance"""
pass pass
class WaitLocationTimeout(AutoTestTimeoutException): class WaitLocationTimeout(AutoTestTimeoutException):
"""Thrown when fails to attain location""" """Thrown when fails to attain location"""
pass pass
class WaitWaypointTimeout(AutoTestTimeoutException): class WaitWaypointTimeout(AutoTestTimeoutException):
"""Thrown when fails to attain waypoint ranges""" """Thrown when fails to attain waypoint ranges"""
pass pass
class SetRCTimeout(AutoTestTimeoutException): class SetRCTimeout(AutoTestTimeoutException):
"""Thrown when fails to send RC commands""" """Thrown when fails to send RC commands"""
pass pass
class MsgRcvTimeoutException(AutoTestTimeoutException): class MsgRcvTimeoutException(AutoTestTimeoutException):
"""Thrown when fails to receive an expected message""" """Thrown when fails to receive an expected message"""
pass pass
class NotAchievedException(ErrorException): class NotAchievedException(ErrorException):
"""Thrown when fails to achieve a goal""" """Thrown when fails to achieve a goal"""
pass pass
class PreconditionFailedException(ErrorException): class PreconditionFailedException(ErrorException):
"""Thrown when a precondition for a test is not met""" """Thrown when a precondition for a test is not met"""
pass pass
class AutoTest(ABC): class AutoTest(ABC):
"""Base abstract class. """Base abstract class.
It implements the common function for all vehicle types. It implements the common function for all vehicle types.
@ -677,7 +692,7 @@ class AutoTest(ABC):
function() function()
except Exception as e: except Exception as e:
self.progress('FAILED: "%s": %s' % (desc, type(e).__name__)) self.progress('FAILED: "%s": %s' % (desc, type(e).__name__))
self.fail_list.append( (desc, e) ) self.fail_list.append((desc, e))
return return
self.progress('PASSED: "%s"' % desc) self.progress('PASSED: "%s"' % desc)