4 search a set of log files for signs of inconsistent IMU data     6 from __future__ 
import print_function
     7 from builtins 
import input
     8 from builtins 
import range
    13 from pymavlink 
import mavutil
    14 from math 
import degrees
    20 search_dirs = [
'c:\Program Files\APM Planner',
    21                'c:\Program Files\Mission Planner',
    22                'c:\Program Files (x86)\APM Planner',
    23                'c:\Program Files (x86)\Mission Planner']
    24 results = 
'SearchResults.zip'    25 email = 
'Craig Elder <craig@3drobotics.com>'    29         mlog = mavutil.mavlink_connection(filename)
    49             m = mlog.recv_match(type=[
'RAW_IMU',
'SCALED_IMU2',
'IMU',
'IMU2',
'PARM',
'PARAM_VALUE'])
    50         except Exception 
as e:
    51             print(
'Error: %s' % e)
    57         if mtype == 
'RAW_IMU':
    58             accel1 = [m.xacc*9.81*0.001, m.yacc*9.81*0.001, m.zacc*9.81*0.001]
    59             gyro1  = [degrees(m.xgyro*0.001), degrees(m.ygyro*0.001), degrees(m.zgyro*0.001)]
    62         elif mtype == 
'SCALED_IMU2':
    63             accel2 = [m.xacc*9.81*0.001, m.yacc*9.81*0.001, m.zacc*9.81*0.001]
    64             gyro2  = [degrees(m.xgyro*0.001), degrees(m.ygyro*0.001), degrees(m.zgyro*0.001)]
    69             accel1 = [m.AccX, m.AccY, m.AccZ]
    70             gyro1  = [m.GyrX, m.GyrY, m.GyrZ]
    74             accel2 = [m.AccX, m.AccY, m.AccZ]
    75             gyro2  = [m.GyrX, m.GyrY, m.GyrZ]
    80             if m.Name.startswith(
'INS_ACCOFFS_') 
or m.Name.startswith(
'INS_ACC2OFFS_'):
    82                     print(
'UNCALIBRATED: %s' % m)
    84         elif mtype == 
'PARAM_VALUE':
    85             if m.param_id.startswith(
'INS_ACCOFFS_') 
or m.param_id.startswith(
'INS_ACC2OFFS_'):
    86                 if m.param_value == 0.0:
    87                     print(
'UNCALIBRATED: %s' % m)
    91         if imu1_count > imu2_count + 100:
    94         if accel1 
is not None and accel2 
is not None and gotimu2 
and t2 >= t1:
    96                 adiff = accel1[i] - accel2[i]
    97                 if adiff > athreshold:
    98                     if ecount_accel[i] < 0:
   102                 elif adiff < -athreshold:
   103                     if ecount_accel[i] > 0:
   109                 gdiff = gyro1[i] - gyro2[i]
   110                 if gdiff > gthreshold:
   111                     if ecount_gyro[i] < 0:
   115                 elif gdiff < -gthreshold:
   116                     if ecount_gyro[i] > 0:
   122                 if abs(ecount_accel[i]) > count_threshold:
   123                     print(
"acceldiff[%u] %.1f" % (i, adiff))
   126                 if abs(ecount_gyro[i]) > count_threshold:
   127                     print(
"gyrodiff[i] %.1f" % (i, adiff))
   134 directories = sys.argv[1:]
   136     directories = search_dirs
   140 extensions = [
'.tlog',
'.bin']
   143     '''see if the path matches a extension'''   144     (root,ext) = os.path.splitext(f)
   145     return ext.lower() 
in extensions
   147 for d 
in directories:
   148     if not os.path.exists(d):
   151         print(
"Searching in %s" % d)
   152         for (root, dirs, files) 
in os.walk(d):
   156                 path = os.path.join(root, f)
   157                 filelist.append(path)
   161 for i 
in range(len(filelist)):
   163     print(
"Checking %s ... [found=%u i=%u/%u]" % (f, len(found), i, len(filelist)))
   167     except Exception 
as e:
   168         print(
"Failed - %s" % e)
   173     print(
"No matching files found - all OK!")
   174     input(
'Press enter to close')
   177 print(
"Creating zip file %s" % results)
   179     zip = zipfile.ZipFile(results, 
'w')
   181     print(
"Unable to create zip file %s" % results)
   182     print(
"Please send matching files manually")
   184         print(
'MATCHED: %s' % f)
   185     input(
'Press enter to close')
   189     arcname=os.path.basename(f)
   190     if not arcname.startswith(
'201'):
   191         mtime = os.path.getmtime(f)
   192         arcname = 
"%s-%s" % (time.strftime(
"%Y-%m-%d-%H-%M-%S", time.localtime(mtime)), arcname)
   193     zip.write(f, arcname=arcname)
   196 print(
'==============================================')
   197 print(
"Created %s with %u of %u matching logs" % (results, len(found), len(filelist)))
   198 print(
"Please send this file to %s" % email)
   199 print(
'==============================================')
   201 input(
'Press enter to close')