mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
autotest: use wait_statustext in place of mavproxy.expect for autorotate test
This commit is contained in:
parent
6e2339d2d6
commit
34a52e9cfe
@ -7014,11 +7014,14 @@ class AutoTestHeli(AutoTestCopter):
|
||||
(start_alt + 5),
|
||||
relative=True,
|
||||
timeout=timeout)
|
||||
self.context_collect('STATUSTEXT')
|
||||
self.progress("Triggering autorotate by raising interlock")
|
||||
self.set_rc(8, 1000)
|
||||
self.mavproxy.expect("SS Glide Phase")
|
||||
self.mavproxy.expect("Hit ground at ([0-9.]+) m/s")
|
||||
speed = float(self.mavproxy.match.group(1))
|
||||
self.wait_statustext("SS Glide Phase", check_context=True)
|
||||
self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s",
|
||||
check_context=True,
|
||||
regex=True)
|
||||
speed = float(self.re_match.group(1))
|
||||
if speed > 30:
|
||||
raise NotAchievedException("Hit too hard")
|
||||
self.wait_disarmed()
|
||||
|
@ -5188,7 +5188,8 @@ Also, ignores heartbeats not from our target system'''
|
||||
if m.get_type() != "STATUSTEXT":
|
||||
return
|
||||
if regex:
|
||||
if re.match(text, m.text):
|
||||
self.re_match = re.match(text, m.text)
|
||||
if self.re_match:
|
||||
statustext_found = True
|
||||
if text.lower() in m.text.lower():
|
||||
self.progress("Received expected text: %s" % m.text.lower())
|
||||
|
Loading…
Reference in New Issue
Block a user