mirror of https://github.com/ArduPilot/ardupilot
autotest: avoid leaving message hooks around
Can lead to some very weird and confusing output
This commit is contained in:
parent
32de8d78ab
commit
51b54d3740
|
@ -2570,7 +2570,7 @@ class AutoTestCopter(AutoTest):
|
|||
0, # compass learning
|
||||
0,
|
||||
timeout=timeout)
|
||||
# long timeouts here because they're a pause before we start motors
|
||||
# long timeouts here because there's a pause before we start motors
|
||||
self.wait_servo_channel_value(1, pwm_in, timeout=10)
|
||||
self.wait_servo_channel_value(4, pwm_in, timeout=10)
|
||||
self.wait_statustext("finished motor test")
|
||||
|
@ -2590,7 +2590,7 @@ class AutoTestCopter(AutoTest):
|
|||
# since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3
|
||||
# min/max are used.
|
||||
expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0
|
||||
self.progress("expected pwm=%f\n" % expected_pwm)
|
||||
self.progress("expected pwm=%f" % expected_pwm)
|
||||
self.wait_servo_channel_value(1, expected_pwm, timeout=10)
|
||||
self.wait_servo_channel_value(4, expected_pwm, timeout=10)
|
||||
self.wait_statustext("finished motor test")
|
||||
|
|
|
@ -1990,6 +1990,8 @@ class AutoTestPlane(AutoTest):
|
|||
self.progress("Caught exception: %s" % self.get_exception_stacktrace(e))
|
||||
ex = e
|
||||
|
||||
self.remove_message_hook(statustext_hook)
|
||||
|
||||
self.context_pop()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
|
|
@ -4076,14 +4076,17 @@ Also, ignores heartbeats not from our target system'''
|
|||
if text.lower() in m.text.lower():
|
||||
self.progress("Received expected text: %s" % m.text.lower())
|
||||
statustext_found = True
|
||||
self.install_message_hook_context(mh)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + timeout:
|
||||
if statustext_found:
|
||||
return
|
||||
if the_function is not None:
|
||||
the_function()
|
||||
m = self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=0.1)
|
||||
self.install_message_hook(mh)
|
||||
try:
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time_cached() < tstart + timeout:
|
||||
if statustext_found:
|
||||
return
|
||||
if the_function is not None:
|
||||
the_function()
|
||||
m = self.mav.recv_match(type='STATUSTEXT', blocking=True, timeout=0.1)
|
||||
finally:
|
||||
self.remove_message_hook(mh)
|
||||
raise AutoTestTimeoutException("Failed to receive text: %s" %
|
||||
text.lower())
|
||||
|
||||
|
|
Loading…
Reference in New Issue