Tools: autotest: improve test diagnostics

This commit is contained in:
Peter Barker 2019-08-07 14:58:25 +10:00 committed by Peter Barker
parent 2a3676003a
commit bf0a947317
4 changed files with 26 additions and 12 deletions

View File

@ -144,7 +144,8 @@ class AutoTestRover(AutoTest):
self.clear_wp(9) self.clear_wp(9)
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.disarm_vehicle() self.disarm_vehicle()
@ -291,7 +292,8 @@ class AutoTestRover(AutoTest):
self.progress("Sprayer OK") self.progress("Sprayer OK")
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.context_pop() self.context_pop()
self.disarm_vehicle(force=True) self.disarm_vehicle(force=True)
@ -507,7 +509,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_groundspeed(0, 0.2, timeout=120) self.wait_groundspeed(0, 0.2, timeout=120)
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.context_pop() self.context_pop()
self.mavproxy.send("fence clear\n") self.mavproxy.send("fence clear\n")

View File

@ -1597,7 +1597,8 @@ class AutoTestCopter(AutoTest):
blocking=True, blocking=True,
timeout=5) timeout=5)
except Exception as e: except Exception as e:
print("Caught exception %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
if m is not None: if m is not None:
raise NotAchievedException("Received unexpected RANGEFINDER msg") raise NotAchievedException("Received unexpected RANGEFINDER msg")
@ -3305,7 +3306,8 @@ class AutoTestCopter(AutoTest):
self.set_rc(10, 2000) self.set_rc(10, 2000)
self.check_avoidance_corners() self.check_avoidance_corners()
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.context_pop() self.context_pop()
self.mavproxy.send("fence clear\n") self.mavproxy.send("fence clear\n")
@ -3322,10 +3324,11 @@ class AutoTestCopter(AutoTest):
self.set_parameter("FENCE_ENABLE", 1) self.set_parameter("FENCE_ENABLE", 1)
self.check_avoidance_corners() self.check_avoidance_corners()
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.context_pop() self.context_pop()
self.mavproxy.send("fence clear\n") self.clear_fence()
self.disarm_vehicle(force=True) self.disarm_vehicle(force=True)
if ex is not None: if ex is not None:
raise ex raise ex
@ -3382,7 +3385,8 @@ class AutoTestCopter(AutoTest):
(pos_delta, max_delta)) (pos_delta, max_delta))
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.context_pop() self.context_pop()
self.disarm_vehicle(force=True) self.disarm_vehicle(force=True)
@ -3421,7 +3425,8 @@ class AutoTestCopter(AutoTest):
self.do_RTL() self.do_RTL()
except Exception as e: except Exception as e:
self.progress("Caught exception: %s" % str(e)) self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e))
ex = e ex = e
self.context_pop() self.context_pop()
self.mavproxy.send("fence clear\n") self.mavproxy.send("fence clear\n")

View File

@ -1246,8 +1246,8 @@ class AutoTestPlane(AutoTest):
blocking=True, blocking=True,
timeout=5) timeout=5)
except Exception as e: except Exception as e:
print("Caught exception:") self.progress("Caught exception: %s" %
self.progress(self.get_exception_stacktrace(e)) self.get_exception_stacktrace(e))
if m is not None: if m is not None:
raise NotAchievedException("Received unexpected RANGEFINDER msg") raise NotAchievedException("Received unexpected RANGEFINDER msg")

View File

@ -2768,7 +2768,7 @@ class AutoTest(ABC):
self.mavproxy.send("set streamrate %u\n" % sr) self.mavproxy.send("set streamrate %u\n" % sr)
except Exception as e: except Exception as e:
self.progress("Caught exception %s" % self.progress("Caught exception: %s" %
self.get_exception_stacktrace(e)) self.get_exception_stacktrace(e))
# tell MAVProxy to start stuffing around with the rates: # tell MAVProxy to start stuffing around with the rates:
sr = self.sitl_streamrate() sr = self.sitl_streamrate()
@ -2795,6 +2795,12 @@ class AutoTest(ABC):
if m is None: if m is None:
raise NotAchievedException("Requested CAMERA_FEEDBACK did not arrive") raise NotAchievedException("Requested CAMERA_FEEDBACK did not arrive")
def clear_fence_using_mavproxy(self):
self.mavproxy.send("fence clear\n")
def clear_fence(self):
self.clear_fence_using_mavproxy()
def clear_mission_using_mavproxy(self): def clear_mission_using_mavproxy(self):
self.mavproxy.send("wp clear\n") self.mavproxy.send("wp clear\n")
self.mavproxy.send('wp list\n') self.mavproxy.send('wp list\n')