diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py
index f6205f1488..5909c6db81 100644
--- a/Tools/autotest/arducopter.py
+++ b/Tools/autotest/arducopter.py
@@ -487,8 +487,7 @@ class AutoTestCopter(AutoTest):
 
             self.wait_disarmed()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -875,8 +874,7 @@ class AutoTestCopter(AutoTest):
         try:
             self.test_battery_failsafe(timeout=timeout)
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.set_parameter('BATT_LOW_VOLT', 0)
@@ -1748,8 +1746,7 @@ class AutoTestCopter(AutoTest):
             self.set_parameter('SIM_SPEEDUP', old_speedup)
             self.do_RTL()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 0)
         sr = self.sitl_streamrate()
@@ -1819,8 +1816,7 @@ class AutoTestCopter(AutoTest):
                     raise NotAchievedException("Alt should be limited by EKF optical flow limits")
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.set_rc(2, 1500)
@@ -1879,8 +1875,7 @@ class AutoTestCopter(AutoTest):
         try:
             self.fly_autotune_switch_body()
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -2186,8 +2181,7 @@ class AutoTestCopter(AutoTest):
             else:
                 raise NotAchievedException("Detected peak %.1f Hz %.2f dB" % (freq, peakdB))
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
             self.disarm_vehicle(force=True)
 
@@ -2282,8 +2276,7 @@ class AutoTestCopter(AutoTest):
                     break
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -2364,8 +2357,7 @@ class AutoTestCopter(AutoTest):
             self.do_RTL()
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle(force=True)
@@ -2524,8 +2516,7 @@ class AutoTestCopter(AutoTest):
                 raise NotAchievedException("Did not see expected RFND message")
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -2580,8 +2571,7 @@ class AutoTestCopter(AutoTest):
             self.do_RTL()
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             self.disarm_vehicle(force=True)
             ex = e
         self.context_pop()
@@ -2630,8 +2620,7 @@ class AutoTestCopter(AutoTest):
             self.wait_rtl_complete()
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             self.disarm_vehicle(force=True)
             ex = e
         self.context_pop()
@@ -2800,7 +2789,7 @@ class AutoTestCopter(AutoTest):
                 raise NotAchievedException("Did not see expected PL message")
 
         except Exception as e:
-            self.progress("Exception caught (%s)" % str(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.zero_throttle()
@@ -3161,8 +3150,7 @@ class AutoTestCopter(AutoTest):
                 self.wait_mode(name)
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -3188,8 +3176,7 @@ class AutoTestCopter(AutoTest):
             self.set_rc(10, 1000) # this re-polls the mode switch
             self.wait_mode("CIRCLE")
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -3506,8 +3493,7 @@ class AutoTestCopter(AutoTest):
             self.wait_disarmed()
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -3565,8 +3551,7 @@ class AutoTestCopter(AutoTest):
             self.wait_statustext("Gripper Grabbed", timeout=60)
             self.wait_statustext("Gripper Released", timeout=60)
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             self.change_mode('LAND')
             ex = e
         self.context_pop()
@@ -3586,8 +3571,7 @@ class AutoTestCopter(AutoTest):
             self.set_rc(3, 1500)
             self.wait_altitude(10, 3000, relative=True)
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.do_RTL()
@@ -3903,8 +3887,7 @@ class AutoTestCopter(AutoTest):
                 self.context_pop()
 
             except Exception as e:
-                self.progress("Exception caught: %s" % (
-                    self.get_exception_stacktrace(e)))
+                self.print_exception_caught(e)
                 self.context_pop()
                 raise e
 
@@ -4088,8 +4071,7 @@ class AutoTestCopter(AutoTest):
                 raise
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
 
@@ -4210,7 +4192,8 @@ class AutoTestCopter(AutoTest):
                     raise NotAchievedException("Double-notch peak was higher than single-notch peak %fdB > %fdB" % (peakdb2, peakdb1))
 
             except Exception as e:
-                self.progress("Exception caught in %s loop: %s" % (loop, self.get_exception_stacktrace(e)))
+                self.print_exception_caught(e)
+                self.progress("Exception caught in %s loop" % (loop,))
                 if loop != "second":
                     continue
                 ex = e
@@ -4397,7 +4380,8 @@ class AutoTestCopter(AutoTest):
                 self.reboot_sitl()
 
             except Exception as e:
-                self.progress("Exception caught in %s loop: %s" % (loop, self.get_exception_stacktrace(e)))
+                self.print_exception_caught(e)
+                self.progress("Exception caught in %s loop" % (loop, ))
                 if loop != "second":
                     continue
                 ex = e
@@ -4550,7 +4534,7 @@ class AutoTestCopter(AutoTest):
                 self.reboot_sitl()
 
             except Exception as e:
-                self.progress("Exception caught in %s loop: %s" % (loop, self.get_exception_stacktrace(e)))
+                self.progress("Exception caught in %s loop" % (loop, ))
                 if loop != "second":
                     continue
                 ex = e
@@ -4733,8 +4717,7 @@ class AutoTestCopter(AutoTest):
             self.loiter_to_ne(start.x + 5, start.y - 10, start.z + 10)
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -4828,8 +4811,7 @@ class AutoTestCopter(AutoTest):
                     raise NotAchievedException("Failed to maintain takeoff alt")
             self.progress("takeoff OK")
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.land_and_disarm()
@@ -4984,8 +4966,7 @@ class AutoTestCopter(AutoTest):
                 self.OBSTACLE_DISTANCE_3D_test_angle(angle)
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle(force=True)
@@ -5007,8 +4988,7 @@ class AutoTestCopter(AutoTest):
             self.set_rc(10, 2000)
             self.check_avoidance_corners()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.mavproxy.send("fence clear\n")
@@ -5105,8 +5085,7 @@ class AutoTestCopter(AutoTest):
             self.set_parameter("FENCE_ENABLE", 1)
             self.check_avoidance_corners()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.clear_fence()
@@ -5261,8 +5240,7 @@ class AutoTestCopter(AutoTest):
             self.land_and_disarm()
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.disarm_vehicle(force=True)
         self.reboot_sitl()
@@ -5302,8 +5280,7 @@ class AutoTestCopter(AutoTest):
             self.do_RTL()
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.mavproxy.send("fence clear\n")
@@ -5382,8 +5359,7 @@ class AutoTestCopter(AutoTest):
             self.land_and_disarm()
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.disarm_vehicle(force=True)
         self.reboot_sitl()
@@ -5518,8 +5494,7 @@ class AutoTestCopter(AutoTest):
             self.set_parameter("DISARM_DELAY", 10)
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -5689,8 +5664,7 @@ class AutoTestCopter(AutoTest):
                 if len(wanted_distances.keys()) == 0:
                     break
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -5811,8 +5785,7 @@ class AutoTestCopter(AutoTest):
             self.disarm_vehicle()
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -5926,8 +5899,7 @@ class AutoTestCopter(AutoTest):
 
             self.context_pop()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.reboot_sitl()
@@ -6059,8 +6031,7 @@ class AutoTestCopter(AutoTest):
                 raise NotAchievedException("Changed to ALT_HOLD with no altitude estimate")
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle(force=True)
@@ -6090,8 +6061,7 @@ class AutoTestCopter(AutoTest):
 
         except Exception as e:
             self.disarm_vehicle(force=True)
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         if ex is not None:
@@ -6853,8 +6823,7 @@ class AutoTestHeli(AutoTestCopter):
                     raise NotAchievedException("Failed to maintain takeoff alt")
             self.progress("takeoff OK")
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.land_and_disarm()
@@ -6892,8 +6861,7 @@ class AutoTestHeli(AutoTestCopter):
 
             self.progress("takeoff OK")
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.land_and_disarm()
diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py
index 6541b2977f..c1ec0481a8 100644
--- a/Tools/autotest/arduplane.py
+++ b/Tools/autotest/arduplane.py
@@ -780,8 +780,7 @@ class AutoTestPlane(AutoTest):
 
             self.progress("Flaps OK")
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         if ex:
@@ -948,8 +947,7 @@ class AutoTestPlane(AutoTest):
             self.wait_statustext("Long event on", check_context=True)
             self.wait_mode("RTL")
         except Exception as e:
-            self.progress("Exception caught:")
-            self.progress(self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         if ex is not None:
@@ -1016,8 +1014,7 @@ class AutoTestPlane(AutoTest):
             self.wait_statustext("Gripper Released", timeout=60)
             self.wait_statustext("Auto disarmed", timeout=60)
         except Exception as e:
-            self.progress("Exception caught:")
-            self.progress(self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         if ex is not None:
@@ -1157,8 +1154,7 @@ class AutoTestPlane(AutoTest):
                 raise NotAchievedException("Expected zero points remaining")
 
         except Exception as e:
-            self.progress("Exception caught:")
-            self.progress(self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.mavproxy.send('fence clear\n')
         if ex is not None:
@@ -1210,8 +1206,7 @@ class AutoTestPlane(AutoTest):
             self.reboot_sitl()
 
         except Exception as e:
-            self.progress("Exception caught:")
-            self.progress(self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.mavproxy.send('fence clear\n')
         if ex is not None:
@@ -1250,8 +1245,7 @@ class AutoTestPlane(AutoTest):
             self.mavproxy.send("rally list\n")
             self.test_fence_breach_circle_at(loc)
         except Exception as e:
-            self.progress("Exception caught:")
-            self.progress(self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.mavproxy.send('rally clear\n')
         if ex is not None:
@@ -1483,8 +1477,7 @@ class AutoTestPlane(AutoTest):
                                     blocking=True,
                                     timeout=5)
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
 
         if m is not None:
             raise NotAchievedException("Received unexpected RANGEFINDER msg")
@@ -1518,8 +1511,7 @@ class AutoTestPlane(AutoTest):
                 raise NotAchievedException("No RFND messages in log")
 
         except Exception as e:
-            self.progress("Exception caught:")
-            self.progress(self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -1659,8 +1651,7 @@ class AutoTestPlane(AutoTest):
                 raise NotAchievedException("Got collision message when I shouldn't have")
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -2292,7 +2283,7 @@ class AutoTestPlane(AutoTest):
             self.disarm_vehicle()
 
         except Exception as e:
-            self.progress("Caught exception: %s" % self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.remove_message_hook(statustext_hook)
diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py
index 0e10adeba2..ffe7fcff0b 100644
--- a/Tools/autotest/ardusub.py
+++ b/Tools/autotest/ardusub.py
@@ -283,8 +283,7 @@ class AutoTestSub(AutoTest):
             self.wait_statustext("Gripper Grabbed", timeout=60)
             self.wait_statustext("Gripper Released", timeout=60)
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
         if ex is not None:
             raise ex
diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py
index 8996d8695a..b97072444a 100644
--- a/Tools/autotest/common.py
+++ b/Tools/autotest/common.py
@@ -5309,6 +5309,16 @@ Also, ignores heartbeats not from our target system'''
             self.progress("Run attempt failed.  Retrying")
         self.run_one_test_attempt(test, interact=interact, attempt=1)
 
+    def print_exception_caught(self, e):
+        self.progress("Exception caught: %s" %
+                      self.get_exception_stacktrace(e))
+        path = None
+        try:
+            path = self.current_onboard_log_filepath()
+        except IndexError:
+            pass
+        self.progress("Most recent logfile: %s" % (path, ))
+
     def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=True):
         '''called by run_one_test to actually run the test in a retry loop'''
         name = test.name
@@ -5341,8 +5351,7 @@ Also, ignores heartbeats not from our target system'''
 
             test_function()
         except Exception as e:
-            self.progress("Exception caught: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.test_timings[desc] = time.time() - start_time
         reset_needed = self.contexts[-1].sitl_commandline_customised
@@ -6579,8 +6588,7 @@ Also, ignores heartbeats not from our target system'''
                         raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Exception caught: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             self.disarm_vehicle()
             ex = e
         self.context_pop()
@@ -6643,7 +6651,7 @@ Also, ignores heartbeats not from our target system'''
             self.mavproxy.expect("Chip erase complete")
 
         except Exception as e:
-            self.progress("Exception (%s) caught" % str(e))
+            self.print_exception_caught(e)
             ex = e
         self.mavproxy.send("module unload log\n")
         self.context_pop()
@@ -6751,7 +6759,7 @@ Also, ignores heartbeats not from our target system'''
             self.mavproxy.expect("Chip erase complete")
 
         except Exception as e:
-            self.progress("Exception (%s) caught" % str(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.mavproxy.send("module unload log\n")
@@ -7146,8 +7154,7 @@ Also, ignores heartbeats not from our target system'''
                 raise NotAchievedException("Getting rate of unsupported message is a failure")
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.progress("Resetting CAMERA_FEEDBACK rate to zero")
@@ -8587,8 +8594,7 @@ switch value'''
                     else:
                         self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct))
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.mavproxy_unload_module("relay")
         self.mavproxy_unload_module("calibration")
@@ -9693,8 +9699,7 @@ switch value'''
             crsf.write_data_id(crsf.dataid_vtx_unknown)
             self.delay_sim_time(5)
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle(force=True)
diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py
index e924666601..e2f03371d7 100644
--- a/Tools/autotest/rover.py
+++ b/Tools/autotest/rover.py
@@ -154,8 +154,7 @@ class AutoTestRover(AutoTest):
 
             self.clear_wp(9)
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.disarm_vehicle()
@@ -344,8 +343,7 @@ class AutoTestRover(AutoTest):
 
             self.progress("Sprayer OK")
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle(force=True)
@@ -379,8 +377,7 @@ class AutoTestRover(AutoTest):
             self.set_rc(1, 1500)
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.disarm_vehicle()
@@ -598,8 +595,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.wait_groundspeed(0, 0.2, timeout=120)
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.mavproxy.send("fence clear\n")
@@ -669,8 +665,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.set_rc(8, 1700) # PWM for mode5
             self.wait_mode("ACRO")
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -711,8 +706,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.wait_mode("ACRO")
             self.set_rc(9, 1000)
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -1028,8 +1022,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.end_subtest("Checking higher-channel semantics")
 
         except Exception as e:
-            self.progress("Exception caught: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -1118,8 +1111,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10)
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
 
         self.context_pop()
@@ -1169,8 +1161,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
 
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         if ex is not None:
@@ -1235,8 +1226,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
                 raise comp_arm_exception
 
         except Exception as e:
-            self.progress("Exception caught: %s" % (
-                self.get_exception_stacktrace(e)))
+            self.print_exception_caught(e)
             ex = e
         self.mav.mav.srcSystem = old_srcSystem
         self.set_parameter("SYSID_ENFORCE", 0, add_to_context=False)
@@ -4692,8 +4682,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.wait_distance_to_home(3, 7, timeout=300)
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -4740,8 +4729,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.do_RTL(timeout=300)
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -4779,8 +4767,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
                     raise NotAchievedException("wheel distance incorrect")
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             self.disarm_vehicle()
             ex = e
         self.reboot_sitl()
@@ -4828,8 +4815,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.do_RTL()
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -4914,8 +4900,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.do_RTL(timeout=300)
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle()
@@ -4961,8 +4946,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.do_RTL(timeout=300)
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle()
@@ -5000,8 +4984,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.wait_distance_to_home(3, 7, timeout=300)
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.disarm_vehicle()
@@ -5081,8 +5064,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.reboot_sitl()
             self.delay_sim_time(10)
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.remove_example_script(example_script)
         self.reboot_sitl()
@@ -5126,8 +5108,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
                 self.remove_example_script(script)
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.reboot_sitl()
 
@@ -5162,8 +5143,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.reboot_sitl()
             self.wait_statustext('hello, world', check_context=True, timeout=30)
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
 
         self.remove_example_script(example_script)
@@ -5196,8 +5176,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.disarm_vehicle()
             self.reboot_sitl()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             self.disarm_vehicle()
             ex = e
         self.remove_example_script(example_script)
@@ -5388,8 +5367,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
                 ])
 
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()
@@ -5679,8 +5657,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
             self.wait_mode("MANUAL")
             self.disarm_vehicle()
         except Exception as e:
-            self.progress("Caught exception: %s" %
-                          self.get_exception_stacktrace(e))
+            self.print_exception_caught(e)
             ex = e
         self.context_pop()
         self.reboot_sitl()