예제 #1
0
def get_versions(fn):
    re_apmver = re.compile(r"^APM:Copter.+\(([0-9a-fA-F]{8})\)$")
    re_px4nuttxver = re.compile(r"^PX4: ([0-9a-fA-F]{8}) NuttX: ([0-9a-fA-F]{8})$")

    apmver = None
    px4ver = None
    nuttxver = None
    ftsver = None

    f = open(fn,'rb')
    parser = DFParser(f.read())
    f.close()

    while True:
        m = parser.parse_next()
        if m is None:
            break

        if m.get_type() == 'MSG':
            mobj = re_apmver.match(m['Message'])
            if mobj is not None:
                apmver = mobj.group(1)

            mobj = re_px4nuttxver.match(m['Message'])
            if mobj is not None:
                px4ver = mobj.group(1)
                nuttxver = mobj.group(2)

        if m.get_type() == 'FTSV':
            ftsver = m['Hash']

        if apmver is not None and px4ver is not None and nuttxver is not None and ftsver is not None:
            break

    return (('ardupilot',apmver), ('PX4',px4ver), ('NuttX',nuttxver), ('FTS',ftsver))
예제 #2
0
def get_time_series(fn, field_identifiers):
    f = open(fn,'rb')
    parser = DFParser(f.read())
    f.close()

    split_field_names = [split_field_identifier(x) for x in field_identifiers]
    msg_names = set([x[0] for x in split_field_names])

    field_names = {}
    for msg_name in msg_names:
        field_names[msg_name] = []
        for field_identifier in filter(lambda x: split_field_identifier(x)[0] == msg_name, field_identifiers):
            field_names[msg_name].append(split_field_identifier(field_identifier)[1])

    t = dict([(msg_name,[]) for msg_name in msg_names])

    ret = {}
    for field_identifier in field_identifiers:
        msg_name, field_name = split_field_identifier(field_identifier)
        ret[field_identifier] = (t[msg_name],[])

    while True:
        m = parser.parse_next()
        if m is None:
            break

        msg_name = m.get_type()

        if msg_name in msg_names:
            t[msg_name].append(m['TimeUS']*1e-6)
            for field_name in field_names[msg_name]:
                field_identifier = combine_field_identifier(msg_name,field_name)
                ret[field_identifier][1].append(m[field_name])

    return ret
예제 #3
0
def retrieve_timeseries(fname, field):
    f = open(fname, 'rb')
    data = f.read()
    f.close()

    parser = DFParser(data)

    msgname, fieldname = tuple(field.split('.', 1))

    ret = []

    while True:
        m = parser.parse_next()
        if m is None:
            break

        if m.get_type() == msgname:
            ret.append(m[fieldname])

    return ret
예제 #4
0
def get_time_series(fn, field_identifiers):
    f = open(fn,'rb')
    parser = DFParser(f)

    split_field_names = [split_field_identifier(x) for x in field_identifiers]
    msg_names = set([x[0] for x in split_field_names])

    field_names = {}
    for msg_name in msg_names:
        field_names[msg_name] = []
        for field_identifier in filter(lambda x: split_field_identifier(x)[0] == msg_name, field_identifiers):
            field_names[msg_name].append(split_field_identifier(field_identifier)[1])

    t = dict([(msg_name,[]) for msg_name in msg_names])

    ret = {}
    for field_identifier in field_identifiers:
        msg_name, field_name = split_field_identifier(field_identifier)
        ret[field_identifier] = (t[msg_name],[])

    while True:
        m = parser.parse_next()
        if m is None:
            break

        msg_name = m.get_type()

        if msg_name in msg_names:
            t[msg_name].append(m['TimeUS']*1e-6)
            for field_name in field_names[msg_name]:
                field_identifier = combine_field_identifier(msg_name,field_name)
                ret[field_identifier][1].append(m[field_name])

    f.close()

    return ret
예제 #5
0
def get_versions(fn):
    re_apmver = re.compile(r"^APM:Copter.+\(([0-9a-fA-F]{8})\)$")
    re_px4nuttxver = re.compile(r"^PX4: ([0-9a-fA-F]{8}) NuttX: ([0-9a-fA-F]{8})$")

    apmver = None
    px4ver = None
    nuttxver = None
    ftsver = None

    f = open(fn,'rb')
    parser = DFParser(f)

    while True:
        m = parser.parse_next()
        if m is None:
            break

        if m.get_type() == 'MSG':
            mobj = re_apmver.match(m['Message'])
            if mobj is not None:
                apmver = mobj.group(1)

            mobj = re_px4nuttxver.match(m['Message'])
            if mobj is not None:
                px4ver = mobj.group(1)
                nuttxver = mobj.group(2)

        if m.get_type() == 'FTSV':
            ftsver = m['Hash']

        if apmver is not None and px4ver is not None and nuttxver is not None and ftsver is not None:
            break

    f.close()

    return (('ardupilot',apmver), ('PX4',px4ver), ('NuttX',nuttxver), ('FTS',ftsver))
예제 #6
0
#!/usr/bin/env python
from DFParser import DFParser
from sys import argv

f = open(argv[1], 'rb')
data = f.read()
f.close()

parser = DFParser(data)
first_time = None
last_time = None

while True:
    m = parser.parse_next()
    if m is None:
        break

    time_field = 'T' if m.get_type() == 'GPS' else 'TimeMS'
    try:
        if first_time is None:
            first_time = m[time_field]
            print "log begins at time %f sec" % (first_time * 1.0e-3)

        if last_time is not None and m[time_field] - last_time > 50:
            print "%f sec of log data missing at time %f sec" % (
                (m[time_field] - last_time) * 1.0e-3, last_time * 1.0e-3)

        last_time = m[time_field]
    except:
        pass
예제 #7
0
파일: logcut.py 프로젝트: jschall/logtools
#!/usr/bin/env python
from DFParser import DFParser
import matplotlib.pyplot as plt
from scipy import signal
import argparse

parser = argparse.ArgumentParser()
parser.add_argument('in_log', nargs=1)
parser.add_argument('out_log', nargs=1)
parser.add_argument('begin_time', nargs=1)
parser.add_argument('end_time', nargs=1)
args = parser.parse_args()

in_f = open(args.in_log[0], 'rb')

parser = DFParser(in_f)

begin = float(args.begin_time[0])
end = float(args.end_time[0])

buf = ''

in_interval = False

while True:
    m = parser.parse_next()
    if m is None:
        break

    if 'TimeUS' in m._fieldnames:
        in_interval = m['TimeUS'] >= begin and m['TimeUS'] <= end
예제 #8
0
#!/usr/bin/env python
from DFParser import DFParser
from sys import argv

f = open(argv[1], 'rb')
data = f.read()
f.close()

parser = DFParser(data)

while True:
    if parser.parse_next() is None:
        break

tot = 0
gmbtot = 0
imutot = 0
ekftot = 0
magtot = 0

msg_usage = []
for key, qty in parser.msg_count.iteritems():
    if qty > 0:
        name = parser.formats[key].name
        msg_len = parser.formats[key].len
        msg_usage.append((name, msg_len * qty))

        tot += msg_len * qty
        if name.startswith('GMB'):
            gmbtot += msg_len * qty
        elif name.startswith('IMU'):
예제 #9
0
#!/usr/bin/env python
from DFParser import DFParser
from sys import argv

f = open(argv[1],'rb')
data = f.read()
f.close()

parser = DFParser(data)

while True:
    if parser.parse_next() is None:
        break

tot = 0
gmbtot = 0
imutot = 0
ekftot = 0
magtot = 0

msg_usage = []
for key,qty in parser.msg_count.iteritems():
    if qty > 0:
        name = parser.formats[key].name
        msg_len = parser.formats[key].len
        msg_usage.append((name,msg_len*qty))

        tot += msg_len*qty
        if name.startswith('GMB'):
            gmbtot += msg_len*qty
        elif name.startswith('IMU'):