Tools:autotest, frsky passthrough fix for long status text message test

This commit is contained in:
yaapu 2021-02-28 12:12:56 +01:00 committed by Peter Barker
parent 694801254f
commit 3bfa07d35a
1 changed files with 8 additions and 17 deletions

View File

@ -9280,25 +9280,16 @@ switch value'''
tstart = self.get_sim_time_cached()
old_data = None
text = ""
sent_request = False
target_text = self.mav.recv_match(
type='STATUSTEXT',
blocking=True,
timeout=10
)
self.progress("Got STATUSTEXT: %s, waiting for same text from frsky" % target_text.text)
while True:
now = self.get_sim_time()
if now - tstart > 60: # it can take a *long* time to get these messages down!
raise NotAchievedException("Did not get statustext in time")
if now - tstart > 30 and not sent_request:
# have to wait this long or our message gets squelched....
sent_request = True
# self.mavproxy.send("param fetch\n")
self.run_cmd(
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
0, # p1
0, # p2
1, # p3, baro
0, # p4
0, # p5
0, # p6
0, # p7
)
frsky.update()
data = frsky.get_data(0x5000) # no timestamping on this data, so we can't catch legitimate repeats.
if data is None:
@ -9320,9 +9311,9 @@ switch value'''
if (x & 0x7f) == 0x00:
last = True
if last:
m = re.match("Updating barometer calibration", text)
m = re.match(target_text.text, text)
if m is not None:
want_sev = mavutil.mavlink.MAV_SEVERITY_INFO
want_sev = target_text.severity
if severity != want_sev:
raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity))
self.progress("Got statustext (%s)" % m.group(0))