diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py
index f4835c670b..5f97d18798 100644
--- a/Tools/autotest/apmrover2.py
+++ b/Tools/autotest/apmrover2.py
@@ -5,7 +5,6 @@ from __future__ import print_function
 
 import os
 import pexpect
-import shutil
 import time
 
 from common import AutoTest
@@ -509,7 +508,8 @@ class AutoTestRover(AutoTest):
                           self.test_servorelayevents)
 
             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):
     #            self.progress("Failed left circuit")
     #            failed = True
@@ -519,7 +519,7 @@ class AutoTestRover(AutoTest):
 
         except pexpect.TIMEOUT as e:
             self.progress("Failed with timeout")
-            self.fail_list.append( ("*timeout*", None) )
+            self.fail_list.append(("*timeout*", None))
 
         self.close()
 
diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py
index 8a388be0e6..9d459d78cc 100644
--- a/Tools/autotest/arducopter.py
+++ b/Tools/autotest/arducopter.py
@@ -460,7 +460,7 @@ class AutoTestCopter(AutoTest):
         # restore motor 1 to 100% efficiency
         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
     def fly_fence_test(self, timeout=180):
@@ -576,7 +576,8 @@ class AutoTestCopter(AutoTest):
         self.mavproxy.send('arm check all\n')
 
     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.wait_mode('LOITER')
 
@@ -625,7 +626,6 @@ class AutoTestCopter(AutoTest):
         tstart = self.get_sim_time()
         tnow = tstart
         start_pos = self.sim_location()
-        success = True
 
         # initialise current glitch
         glitch_current = 0
@@ -1023,59 +1023,75 @@ class AutoTestCopter(AutoTest):
             self.run_test("Arm motors", self.arm_vehicle)
 
             # 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
-            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
             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:
                 self.fail_list.append("save_mission_to_file")
                 self.progress("save_mission_to_file failed")
 
             # 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
-            self.run_test("Test Failsafe", lambda: self.fly_throttle_failsafe)
+            self.run_test("Test Failsafe",
+                          lambda: self.fly_throttle_failsafe)
 
             # 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
-            self.run_test("Fly Battery Failsafe", lambda: self.fly_battery_failsafe)
+            self.run_test("Fly Battery Failsafe",
+                          lambda: self.fly_battery_failsafe)
 
             # 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
-            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
             self.run_test("RTL after stab patch", lambda: self.fly_RTL)
 
             # 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
-            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
-            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
-            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
-            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
             self.run_test("RTL after GPS Glitch Loiter test", self.fly_RTL)
 
             # 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
             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))
 
             # 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
             self.run_test("RTL after Loiter climb/descend", self.fly_RTL)
 
             # 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
             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)
 
             # 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
-            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
             self.run_test("RTL after SUPER SIMPLE mode", self.fly_RTL)
 
             # 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
             self.run_test("Fly CIRCLE mode", self.fly_circle)
@@ -1126,7 +1147,9 @@ class AutoTestCopter(AutoTest):
             self.mav.motors_disarmed_wait()
 
             # 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:
             self.progress("Failed with timeout")
@@ -1169,7 +1192,9 @@ class AutoTestCopter(AutoTest):
             self.set_rc(8, 1000)
 
             # 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:
             self.fail_list.append("Failed with timeout")
diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py
index 14a3a9912e..68de9fb9c7 100644
--- a/Tools/autotest/arduplane.py
+++ b/Tools/autotest/arduplane.py
@@ -132,8 +132,8 @@ class AutoTestPlane(AutoTest):
 
         # gain a bit of altitude
         self.wait_altitude(self.homeloc.alt+150,
-                                  self.homeloc.alt+180,
-                                  timeout=30)
+                           self.homeloc.alt+180,
+                           timeout=30)
 
         # level off
         self.set_rc(2, 1500)
@@ -165,10 +165,10 @@ class AutoTestPlane(AutoTest):
         self.mavproxy.send('switch 2\n')
         self.wait_mode('RTL')
         self.wait_location(self.homeloc,
-                                  accuracy=120,
-                                  target_altitude=self.homeloc.alt+100,
-                                  height_accuracy=20,
-                                  timeout=180)
+                           accuracy=120,
+                           target_altitude=self.homeloc.alt+100,
+                           height_accuracy=20,
+                           timeout=180)
         self.progress("RTL Complete")
 
     def fly_LOITER(self, num_circles=4):
@@ -282,7 +282,7 @@ class AutoTestPlane(AutoTest):
                 self.wait_roll(150, accuracy=90)
                 self.wait_roll(0, accuracy=90)
             except Exception as e:
-                self.set_rc(1,1500)
+                self.set_rc(1, 1500)
                 raise e
             count -= 1
 
@@ -513,11 +513,15 @@ class AutoTestPlane(AutoTest):
 
             self.run_test("CIRCLE test", self.fly_CIRCLE)
 
-            self.run_test("Mission test", lambda: self.fly_mission(os.path.join(testdir, "ap1.txt"),
-                                    height_accuracy=10,
-                                    target_altitude=self.homeloc.alt+100))
+            self.run_test("Mission test",
+                          lambda: self.fly_mission(
+                              os.path.join(testdir, "ap1.txt"),
+                              height_accuracy=10,
+                              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:
             self.progress("Failed with timeout")
diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py
index 0299e59ef3..cf8afcb6b8 100644
--- a/Tools/autotest/ardusub.py
+++ b/Tools/autotest/ardusub.py
@@ -167,9 +167,13 @@ class AutoTestSub(AutoTest):
 
             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:
             self.progress("Failed with timeout")
diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py
index 56ff3101e8..0f6d6ecbd3 100644
--- a/Tools/autotest/common.py
+++ b/Tools/autotest/common.py
@@ -28,61 +28,76 @@ class ErrorException(Exception):
     """Base class for other exceptions"""
     pass
 
+
 class AutoTestTimeoutException(ErrorException):
     pass
 
+
 class WaitModeTimeout(AutoTestTimeoutException):
     """Thrown when fails to achieve given mode change."""
     pass
 
+
 class WaitAltitudeTimout(AutoTestTimeoutException):
     """Thrown when fails to achieve given altitude range."""
     pass
 
+
 class WaitGroundSpeedTimeout(AutoTestTimeoutException):
     """Thrown when fails to achieve given ground speed range."""
     pass
 
+
 class WaitRollTimeout(AutoTestTimeoutException):
     """Thrown when fails to achieve given roll in degrees."""
     pass
 
+
 class WaitPitchTimeout(AutoTestTimeoutException):
     """Thrown when fails to achieve given pitch in degrees."""
     pass
 
+
 class WaitHeadingTimeout(AutoTestTimeoutException):
     """Thrown when fails to achieve given heading."""
     pass
 
+
 class WaitDistanceTimeout(AutoTestTimeoutException):
     """Thrown when fails to attain distance"""
     pass
 
+
 class WaitLocationTimeout(AutoTestTimeoutException):
     """Thrown when fails to attain location"""
     pass
 
+
 class WaitWaypointTimeout(AutoTestTimeoutException):
     """Thrown when fails to attain waypoint ranges"""
     pass
 
+
 class SetRCTimeout(AutoTestTimeoutException):
     """Thrown when fails to send RC commands"""
     pass
 
+
 class MsgRcvTimeoutException(AutoTestTimeoutException):
     """Thrown when fails to receive an expected message"""
     pass
 
+
 class NotAchievedException(ErrorException):
     """Thrown when fails to achieve a goal"""
     pass
 
+
 class PreconditionFailedException(ErrorException):
     """Thrown when a precondition for a test is not met"""
     pass
 
+
 class AutoTest(ABC):
     """Base abstract class.
     It implements the common function for all vehicle types.
@@ -677,7 +692,7 @@ class AutoTest(ABC):
             function()
         except Exception as e:
             self.progress('FAILED: "%s": %s' % (desc, type(e).__name__))
-            self.fail_list.append( (desc, e) )
+            self.fail_list.append((desc, e))
             return
         self.progress('PASSED: "%s"' % desc)