Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/Replay/check_replay.py
Views: 1798
#!/usr/bin/env python12'''3check that replay produced identical results4'''56from __future__ import print_function78def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose=False, accuracy=0.0, ignores=set()):9'''check replay log for matching output'''10from pymavlink import mavutil11progress("Processing log %s" % logfile)12failure = 013errors = 014count = 015base_count = 016counts = {}17base_counts = {}1819mlog = mavutil.mavlink_connection(logfile)2021ek2_list = ['NKF1','NKF2','NKF3','NKF4','NKF5','NKF0','NKQ', 'NKY0', 'NKY1']22ek3_list = ['XKF1','XKF2','XKF3','XKF4','XKF0','XKFS','XKQ','XKFD','XKV1','XKV2','XKY0','XKY1']2324if ekf2_only:25mlist = ek2_list26elif ekf3_only:27mlist = ek3_list28else:29mlist = ek2_list + ek3_list3031base = {}32for m in mlist:33base[m] = {}3435while True:36m = mlog.recv_match(type=mlist)37if m is None:38break39if not hasattr(m,'C'):40continue41mtype = m.get_type()42if mtype not in counts:43counts[mtype] = 044base_counts[mtype] = 045core = m.C46if core < 100:47base[mtype][core] = m48base_count += 149base_counts[mtype] += 150continue51mb = base[mtype][core-100]52count += 153counts[mtype] += 154mismatch = False55for f in m._fieldnames:56if f == 'C':57continue58if "%s.%s" % (mtype, f) in ignores:59continue60v1 = getattr(m,f)61v2 = getattr(mb,f)62ok = v1 == v263if not ok and accuracy > 0:64avg = (v1+v2)*0.565margin = accuracy*0.01*avg66if abs(v1-v2) <= abs(margin):67ok = True68if not ok:69mismatch = True70errors += 171progress("Mismatch in field %s.%s: %s %s" % (mtype, f, str(v1), str(v2)))72if mismatch:73progress(mb)74progress(m)75progress("Processed %u/%u messages, %u errors" % (count, base_count, errors))76if verbose:77for mtype in counts.keys():78progress("%s %u/%u %d" % (mtype, counts[mtype], base_counts[mtype], base_counts[mtype]-counts[mtype]))79count_delta = abs(count - base_count)80if count == 0 or count_delta > 100:81progress("count=%u count_delta=%u" % (count, count_delta))82failure += 183if failure != 0 or errors != 0:84return False85return True8687if __name__ == '__main__':88import sys89from argparse import ArgumentParser90parser = ArgumentParser(description=__doc__)91parser.add_argument("--ekf2-only", action='store_true', help="only check EKF2")92parser.add_argument("--ekf3-only", action='store_true', help="only check EKF3")93parser.add_argument("--verbose", action='store_true', help="verbose output")94parser.add_argument("--accuracy", type=float, default=0.0, help="accuracy percentage for match")95parser.add_argument("--ignore-field", action='append', default=[], help="ignore message field when comparing")96parser.add_argument("logs", metavar="LOG", nargs="+")9798args = parser.parse_args()99100failed = False101for filename in args.logs:102if not check_log(filename, print, args.ekf2_only, args.ekf3_only, args.verbose, accuracy=args.accuracy, ignores=args.ignore_field):103failed = True104105if failed:106print("FAILED")107sys.exit(1)108print("Passed")109sys.exit(0)110111112