4 search a set of log files for bad accel values 6 from __future__
import print_function
7 from builtins
import input
8 from builtins
import range
13 from pymavlink
import mavutil
19 search_dirs = [
'c:\Program Files\APM Planner',
20 'c:\Program Files\Mission Planner',
21 'c:\Program Files (x86)\APM Planner',
22 'c:\Program Files (x86)\Mission Planner']
23 results =
'SearchResults.zip' 24 email =
'Craig Elder <craig@3drobotics.com>' 26 from argparse
import ArgumentParser
27 parser = ArgumentParser(description=__doc__)
28 parser.add_argument(
"--directory", action=
'append', default=search_dirs, help=
"directories to search")
29 parser.add_argument(
"--post-boot", action=
'store_true', help=
"post boot only")
30 parser.add_argument(
"--init-only", action=
'store_true', help=
"init only")
31 parser.add_argument(
"--single-axis", action=
'store_true', help=
"single axis only")
33 args = parser.parse_args()
39 mlog = mavutil.mavlink_connection(filename)
45 m = mlog.recv_match(type=[
'PARAM_VALUE',
'RAW_IMU'])
50 if m.get_type() ==
'PARAM_VALUE':
51 if m.param_id.startswith(
'INS_PRODUCT_ID'):
52 if m.param_value
not in [0.0, 5.0]:
54 if m.get_type() ==
'RAW_IMU':
55 if m.time_usec < last_t:
58 if abs(m.xacc) >= 3000
and abs(m.yacc) > 3000
and abs(m.zacc) > 3000
and not args.single_axis:
59 if args.post_boot
and not have_ok:
61 if args.init_only
and have_ok:
63 print(have_ok, last_t, m)
66 for axes
in [
'xacc',
'yacc',
'zacc']:
67 value1 = getattr(m, axes)
68 if abs(value1) > 2000:
73 value2 = getattr(badval, axes)
74 if abs(value1 - value2) < 30:
79 if args.init_only
and have_ok:
81 print(have_ok, badcount, badval, m)
93 directories = args.directory
97 directories = sys.argv[1:]
101 for d
in directories:
102 if not os.path.exists(d):
105 print(
"Searching in %s" % d)
106 for (root, dirs, files)
in os.walk(d):
108 if not f.endswith(
'.tlog'):
110 path = os.path.join(root, f)
111 filelist.append(path)
112 elif d.endswith(
'.tlog'):
115 for i
in range(len(filelist)):
117 print(
"Checking %s ... [found=%u logcount=%u i=%u/%u]" % (f, len(found), logcount, i, len(filelist)))
123 print(
"No matching files found - all OK!")
124 input(
'Press enter to close')
127 print(
"Creating zip file %s" % results)
129 zip = zipfile.ZipFile(results,
'w')
131 print(
"Unable to create zip file %s" % results)
132 print(
"Please send matching files manually")
134 print(
'MATCHED: %s' % f)
135 input(
'Press enter to close')
139 zip.write(f, arcname=os.path.basename(f))
142 print(
'==============================================')
143 print(
"Created %s with %u of %u matching logs" % (results, len(found), logcount))
144 print(
"Please send this file to %s" % email)
145 print(
'==============================================')
147 input(
'Press enter to close')