From 36e480483ffc47b5f2ee2257c17d1cb339a776ac Mon Sep 17 00:00:00 2001 From: Andrew Chapman Date: Sun, 26 Jan 2014 22:38:57 -0800 Subject: [PATCH] LogAnalyzer: Initial commit for discussion A lot of this is still stub code, but far enough along for discussion and feedback. Some good example tests are TestVibration and TestBrownout datatypes handled correctly now (previsouly all read as floats), added flag to skip bad input lines, now prints some general log info (size, duration, etc), added some basic performance timing, --- Tools/LogAnalyzer/DataflashLog.py | 287 + Tools/LogAnalyzer/LogAnalyzer.py | 183 + Tools/LogAnalyzer/UnitTest.py | 7 + Tools/LogAnalyzer/logs/mechanical_fail.log | 7777 +++++++++++++ Tools/LogAnalyzer/logs/nan.log | 2738 +++++ Tools/LogAnalyzer/logs/tradheli_brownout.log | 4197 +++++++ Tools/LogAnalyzer/logs/underpowered.log | 9888 +++++++++++++++++ Tools/LogAnalyzer/tests/TestBalanceTwist.py | 18 + Tools/LogAnalyzer/tests/TestBrownout.py | 34 + Tools/LogAnalyzer/tests/TestCompass.py | 54 + Tools/LogAnalyzer/tests/TestEmpty.py | 19 + Tools/LogAnalyzer/tests/TestEvents.py | 54 + Tools/LogAnalyzer/tests/TestGPSGlitch.py | 32 + Tools/LogAnalyzer/tests/TestParams.py | 52 + Tools/LogAnalyzer/tests/TestPerformance.py | 16 + .../tests/TestPitchRollCoupling.py | 18 + Tools/LogAnalyzer/tests/TestUnderpowered.py | 18 + Tools/LogAnalyzer/tests/TestVCC.py | 34 + Tools/LogAnalyzer/tests/TestVibration.py | 63 + 19 files changed, 25489 insertions(+) create mode 100644 Tools/LogAnalyzer/DataflashLog.py create mode 100755 Tools/LogAnalyzer/LogAnalyzer.py create mode 100644 Tools/LogAnalyzer/UnitTest.py create mode 100644 Tools/LogAnalyzer/logs/mechanical_fail.log create mode 100644 Tools/LogAnalyzer/logs/nan.log create mode 100644 Tools/LogAnalyzer/logs/tradheli_brownout.log create mode 100644 Tools/LogAnalyzer/logs/underpowered.log create mode 100644 Tools/LogAnalyzer/tests/TestBalanceTwist.py create mode 100644 Tools/LogAnalyzer/tests/TestBrownout.py create mode 100644 Tools/LogAnalyzer/tests/TestCompass.py create mode 100644 Tools/LogAnalyzer/tests/TestEmpty.py create mode 100644 Tools/LogAnalyzer/tests/TestEvents.py create mode 100644 Tools/LogAnalyzer/tests/TestGPSGlitch.py create mode 100644 Tools/LogAnalyzer/tests/TestParams.py create mode 100644 Tools/LogAnalyzer/tests/TestPerformance.py create mode 100644 Tools/LogAnalyzer/tests/TestPitchRollCoupling.py create mode 100644 Tools/LogAnalyzer/tests/TestUnderpowered.py create mode 100644 Tools/LogAnalyzer/tests/TestVCC.py create mode 100644 Tools/LogAnalyzer/tests/TestVibration.py diff --git a/Tools/LogAnalyzer/DataflashLog.py b/Tools/LogAnalyzer/DataflashLog.py new file mode 100644 index 0000000000..bee0a09ad7 --- /dev/null +++ b/Tools/LogAnalyzer/DataflashLog.py @@ -0,0 +1,287 @@ +# +# Code to abstract the parsing of APM Dataflash log files, currently only used by the LogAnalyzer +# +# Initial code by Andrew Chapman (chapman@skymount.com), 16th Jan 2014 +# + +# TODO: log reading needs to be much more robust, only compatible with AC3.0.1-AC3.1 logs at this point, try to be compatible at least back to AC2.9.1, and APM:Plane too (skipping copter-only tests) +# TODO: rethink data storage, dictionaries are good for specific line lookups, but we don't end up doing a lot of that + +import pprint # temp +import collections +import os + +class Format: + '''Channel format as specified by the FMT lines in the log file''' + msgType = 0 + msgLen = 0 + name = "" + types = "" + labels = [] + def __init__(self,msgType,msgLen,name,types,labels): + self.msgType = msgType + self.msgLen = msgLen + self.name = name + self.types = types + self.labels = labels.split(',') + def __str__(self): + return "%8s %s" % (self.name, `self.labels`) + + +class Channel: + '''storage for a single stream of data, i.e. all GPS.RelAlt values''' + dictData = None # dict of linenum->value # store dupe data in dict and list for now, until we decide which is the better way to go + listData = None # list of (linenum,value) + def __init__(self): + self.dictData = {} + self.listData = [] + def getSegment(self, startLine, endLine): + '''returns a segment of this data (from startLine to endLine, inclusive) as a new Channel instance''' + segment = Channel() + segment.dictData = {k:v for k,v in self.dictData.iteritems() if k >= startLine and k <= endLine} + return segment + def min(self): + return min(self.dictData.values()) + def max(self): + return max(self.dictData.values()) + def avg(self): + return avg(self.dictData.values()) + def getNearestValue(self, lineNumber, lookForwards=True): + '''return the nearest data value to the given lineNumber''' + if lineNumber in self.dictData: + return self.dictData[lineNumber] + offset = 1 + if not lookForwards: + offset = -1 + minLine = min(self.dictData.keys()) + maxLine = max(self.dictData.keys()) + line = max(minLine,lineNumber) + line = min(maxLine,line) + while line >= minLine and line <= maxLine: + if line in self.dictData: + return self.dictData[line] + line = line + offset + raise Exception("Error finding nearest value for line %d" % lineNumber) + + +class DataflashLogHelper: + @staticmethod + def getTimeAtLine(logdata, lineNumber): + '''returns the nearest GPS timestamp in milliseconds after the given line number''' + if not "GPS" in logdata.channels: + raise Exception("no GPS log data found") + # older logs use 'TIme', newer logs use 'TimeMS' + timeLabel = "TimeMS" + if "Time" in logdata.channels["GPS"]: + timeLabel = "Time" + while lineNumber <= logdata.lineCount: + if lineNumber in logdata.channels["GPS"][timeLabel].dictData: + return logdata.channels["GPS"][timeLabel].dictData[lineNumber] + lineNumber = lineNumber + 1 + + @staticmethod + def findLoiterChunks(logdata, minLengthSeconds=0, noRCInputs=True): + '''returns a list of (to,from) pairs defining sections of the log which are in loiter mode. Ordered from longest to shortest in time. If noRCInputs == True it only returns chunks with no control inputs''' + # TODO: implement noRCInputs handling when identifying stable loiter chunks, for now we're ignoring it + + def chunkSizeCompare(chunk1, chunk2): + chunk1Len = chunk1[1]-chunk1[0] + chunk2Len = chunk2[1]-chunk2[0] + if chunk1Len == chunk2Len: + return 0 + elif chunk1Len > chunk2Len: + return -1 + else: + return 1 + + od = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0])) + chunks = [] + for i in range(len(od.keys())): + if od.values()[i][0] == "LOITER": + startLine = od.keys()[i] + endLine = None + if i == len(od.keys())-1: + endLine = logdata.lineCount + else: + endLine = od.keys()[i+1]-1 + chunkTimeSeconds = (DataflashLogHelper.getTimeAtLine(logdata,endLine)-DataflashLogHelper.getTimeAtLine(logdata,startLine)+1) / 1000.0 + if chunkTimeSeconds > minLengthSeconds: + chunks.append((startLine,endLine)) + #print "LOITER chunk: %d to %d, %d lines" % (startLine,endLine,endLine-startLine+1) + #print " (time %d to %d, %d seconds)" % (DataflashLogHelper.getTimeAtLine(logdata,startLine), DataflashLogHelper.getTimeAtLine(logdata,endLine), chunkTimeSeconds) + chunks.sort(chunkSizeCompare) + return chunks + + @staticmethod + def isLogEmpty(logdata): + '''returns an human readable error string if the log is essentially empty, otherwise returns None''' + # naive check for now, see if the throttle output was ever above 20% + throttleThreshold = 200 + if "CTUN" in logdata.channels: + maxThrottle = logdata.channels["CTUN"]["ThrOut"].max() + if maxThrottle < throttleThreshold: + return "Throttle never above 20%" + return None + + +class DataflashLog: + '''APM Dataflash log file reader and container class. Keep this simple, add more advanced or specific functions to DataflashLogHelper class''' + filename = None + + vehicleType = None # ArduCopter, ArduPlane, ArduRover, etc, verbatim as given by header + firmwareVersion = None + firmwareHash = None + freeRAM = None + hardwareType = None # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing + + formats = {} # name -> Format + parameters = {} # token -> value + messages = {} # lineNum -> message + modeChanges = {} # lineNum -> (mode,value) + channels = {} # lineLabel -> {dataLabel:Channel} + + filesizeKB = None + durationSecs = None + lineCount = None + + def getCopterType(self): + if self.vehicleType != "ArduCopter": + return None + motLabels = [] + if "MOT" in self.formats: # not listed in PX4 log header for some reason? + motLabels = self.formats["MOT"].labels + if "GGain" in motLabels: + return "tradheli" + elif len(motLabels) == 4: + return "quad" + elif len(motLabels) == 6: + return "hex" + elif len(motLabels) == 8: + return "octo" + else: + return "" + + def __castToFormatType(self,value,valueType): + '''using format characters from libraries/DataFlash/DataFlash.h to cast to basic python int/float/string types''' + intTypes = "bBhHiIM" + floatTypes = "fcCeEL" + charTypes = "nNZ" + if valueType in floatTypes: + return float(value) + elif valueType in intTypes: + return int(value) + elif valueType in charTypes: + return str(value) + else: + raise Exception("Unknown value type of '%s' specified to __castToFormatType()" % valueType) + + def __init__(self, logfile, ignoreBadlines=False): + self.read(logfile, ignoreBadlines) + + def read(self, logfile, ignoreBadlines=False): + # TODO: dataflash log parsing code is *SUPER* hacky, should re-write more methodically + self.filename = logfile + f = open(self.filename, 'r') + lineNumber = 0 + copterLogPre3Header = False + copterLogPre3Params = False + knownHardwareTypes = ["APM", "PX4", "MPNG"] + for line in f: + lineNumber = lineNumber + 1 + try: + #print "Reading line: %d" % lineNumber + line = line.strip('\n\r') + tokens = line.split(', ') + # first handle the log header lines + if copterLogPre3Header and line[0:15] == "SYSID_SW_MREV: ": + copterLogPre3Header = False + copterLogPre3Params = True + if len(tokens) == 1: + tokens2 = line.split(' ') + if line == "": + pass + elif len(tokens2) == 1 and tokens2[0].isdigit(): # log index + pass + elif len(tokens2) == 3 and tokens2[0] == "Free" and tokens2[1] == "RAM:": + self.freeRAM = int(tokens2[2]) + elif tokens2[0] in knownHardwareTypes: + self.hardwareType = line # not sure if we can parse this more usefully, for now only need to report it back verbatim + elif line[0:8] == "FW Ver: ": + copterLogPre3Header = True + elif copterLogPre3Header: + pass # just skip over all that until we hit the PARM lines + elif (len(tokens2) == 2 or len(tokens2) == 3) and tokens2[1][0] == "V": # e.g. ArduCopter V3.1 (5c6503e2) + self.vehicleType = tokens2[0] + self.firmwareVersion = tokens2[1] + if len(tokens2) == 3: + self.firmwareHash = tokens2[2][1:-1] + elif len(tokens2) == 2 and copterLogPre3Params: + pName = tokens2[0] + self.parameters[pName] = float(tokens2[1]) + else: + errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename) + if ignoreBadlines: + print errorMsg + " (skipping line)" + else: + raise Exception(errorMsg) + # now handle the non-log data stuff, format descriptions, params, etc + elif tokens[0] == "FMT": + format = None + if len(tokens) == 6: + format = Format(tokens[1],tokens[2],tokens[3],tokens[4],tokens[5]) + elif len(tokens) == 5: # some logs have FMT STRT with no labels + format = Format(tokens[1],tokens[2],tokens[3],tokens[4],"") + else: + raise Exception("FMT error on line %d, nTokens: %d" % (lineNumber, len(tokens))) + #print format # TEMP + self.formats[tokens[3]] = format + elif tokens[0] == "PARM": + pName = tokens[1] + self.parameters[pName] = float(tokens[2]) + elif tokens[0] == "MSG": + self.messages[lineNumber] = tokens[1] + elif tokens[0] == "MODE": + self.modeChanges[lineNumber] = (tokens[1],int(tokens[2])) + # anything else must be the log data + elif not copterLogPre3Header: + groupName = tokens[0] + tokens2 = line.split(', ') + # first time seeing this type of log line, create the channel storage + if not groupName in self.channels: + self.channels[groupName] = {} + for label in self.formats[groupName].labels: + self.channels[groupName][label] = Channel() + #print "Channel definition for group %s, data at address %s" % (groupName, hex(id(self.channels[groupName][label].dictData))) + #pprint.pprint(self.channels[groupName]) # TEMP!!! + # check the number of tokens matches between the line and what we're expecting from the FMT definition + if len(tokens2) != (len(self.formats[groupName].labels) + 1): + errorMsg = "Error on line %d of log file: %s, %s line's value count (%d) not matching FMT specification (%d)" % (lineNumber, self.filename, groupName, len(tokens2), len(self.formats[groupName].labels)) + if ignoreBadlines: + print errorMsg + " (skipping line)" + continue + else: + raise Exception(errorMsg) + # store each token in its relevant channel + for (index,label) in enumerate(self.formats[groupName].labels): + #value = float(tokens2[index+1]) # simple read without handling datatype + value = self.__castToFormatType(tokens2[index+1], self.formats[groupName].types[index]) # handling datatype via this call slows down ready by about 50% + channel = self.channels[groupName][label] + #print "Set data {%s,%s} for line %d to value %s, of type %c, stored at address %s" % (groupName, label, lineNumber, `value`, self.formats[groupName].types[index], hex(id(channel.dictData))) + channel.dictData[lineNumber] = value + channel.listData.append((lineNumber,value)) + except: + print "Error parsing line %d of log file %s" % (lineNumber,self.filename) + raise + + # gather some general stats about the log + self.lineCount = lineNumber + self.filesizeKB = os.path.getsize(self.filename) / 1024.0 + if "GPS" in self.channels: + # the GPS time label changed at some point, need to handle both + timeLabel = "TimeMS" + if timeLabel not in self.channels["GPS"]: + timeLabel = "Time" + firstTimeGPS = self.channels["GPS"][timeLabel].listData[0][1] + lastTimeGPS = self.channels["GPS"][timeLabel].listData[-1][1] + self.durationSecs = (lastTimeGPS-firstTimeGPS) / 1000 + diff --git a/Tools/LogAnalyzer/LogAnalyzer.py b/Tools/LogAnalyzer/LogAnalyzer.py new file mode 100755 index 0000000000..fb21c045e9 --- /dev/null +++ b/Tools/LogAnalyzer/LogAnalyzer.py @@ -0,0 +1,183 @@ +#!/usr/bin/env python +# +# A module to analyze and identify any common problems which can be determined from log files +# +# Initial code by Andrew Chapman (chapman@skymount.com), 16th Jan 2014 +# + + +# some logging oddities noticed while doing this, to be followed up on: +# - tradheli MOT labels Mot1,Mot2,Mot3,Mot4,GGain +# - Pixhawk doesn't output one of the FMT labels... forget which one +# - MAG offsets seem to be constant (only seen data on Pixhawk) +# - MAG offsets seem to be cast to int before being output? (param is -84.67, logged as -84) + +# TODO - unify result statusMessage and extraOutput. simple tests set statusMessage, complex ones append to it with newlines + + +import DataflashLog + +import pprint # temp +import imp +import glob +import inspect +import os, sys +import argparse +import datetime +import time + + +class TestResult: + '''all tests pass back a standardized result''' + class StatusType: + # NA means not applicable for this log (e.g. copter tests against a plane log), UNKNOWN means it is missing data required for the test + PASS, FAIL, WARN, UNKNOWN, NA = range(5) + status = None + statusMessage = "" + extraFeedback = "" + + +class Test: + '''base class to be inherited by each specific log test. Each test should be quite granular so we have lots of small tests with clear results''' + name = "" + result = None # will be an instance of TestResult after being run + execTime = None + enable = True + def run(self, logdata): + pass + + +class TestSuite: + '''registers test classes''' + tests = [] + logfile = None + logdata = None + + def __init__(self): + # dynamically load in Test subclasses from the 'tests' folder + dirName = os.path.dirname(os.path.abspath(__file__)) + testScripts = glob.glob(dirName + '/tests/*.py') + testClasses = [] + for script in testScripts: + m = imp.load_source("m",script) + for name, obj in inspect.getmembers(m, inspect.isclass): + if name not in testClasses and inspect.getsourcefile(obj) == script: + testClasses.append(name) + self.tests.append(obj()) + + # and here's an example of explicitly loading a Test class if you wanted to do that + # m = imp.load_source("m", dirName + '/tests/TestBadParams.py') + # self.tests.append(m.TestBadParams()) + + + def run(self, logdata): + '''run all registered tests in a single call''' + self.logdata = logdata + self.logfile = logdata.filename + for test in self.tests: + # run each test in turn, gathering timing info + if test.enable: + startTime = time.time() + test.run(self.logdata) # RUN THE TEST + endTime = time.time() + test.execTime = endTime-startTime + + def outputPlainText(self, outputStats): + print 'Dataflash log analysis report for file: ' + self.logfile + print 'Log size: %.2fmb (%d lines)' % (self.logdata.filesizeKB / 1024.0, self.logdata.lineCount) + print 'Log duration: %s' % str(datetime.timedelta(seconds=self.logdata.durationSecs)) + '\n' + + if self.logdata.vehicleType == "ArduCopter" and self.logdata.getCopterType(): + print 'Vehicle Type: %s (%s)' % (self.logdata.vehicleType, self.logdata.getCopterType()) + else: + print 'Vehicle Type: %s' % self.logdata.vehicleType + print 'Firmware Version: %s (%s)' % (self.logdata.firmwareVersion, self.logdata.firmwareHash) + print 'Hardware: %s' % self.logdata.hardwareType + print 'Free RAM: %s' % self.logdata.freeRAM + print '\n' + + print "Test Results:" + for test in self.tests: + if not test.enable: + continue + execTime = "" + if outputStats: + execTime = " (%.2fms)" % (test.execTime) + if test.result.status == TestResult.StatusType.PASS: + print " %20s: PASS %-50s%s" % (test.name, test.result.statusMessage,execTime) + elif test.result.status == TestResult.StatusType.FAIL: + print " %20s: FAIL %-50s%s [GRAPH]" % (test.name, test.result.statusMessage,execTime) + elif test.result.status == TestResult.StatusType.WARN: + print " %20s: WARN %-50s%s [GRAPH]" % (test.name, test.result.statusMessage,execTime) + elif test.result.status == TestResult.StatusType.NA: + # skip any that aren't relevant for this vehicle/hardware/etc + continue + else: + print " %20s: UNKNOWN %-50s%s" % (test.name, test.result.statusMessage,execTime) + if test.result.extraFeedback: + for line in test.result.extraFeedback.strip().split('\n'): + print " %20s %s" % ("",line) + print '\n' + + + # temp - test some spot values + #print "GPS abs alt on line 24126 is " + `self.logdata.channels["GPS"]["Alt"].dictData[24126]` # 52.03 + #print "ATT pitch on line 22153 is " + `self.logdata.channels["ATT"]["Pitch"].dictData[22153]` # -7.03 + #gpsAlt = self.logdata.channels["GPS"]["Alt"] + #print "All GPS Alt data: %s\n\n" % gpsAlt.dictData + #gpsAltSeg = gpsAlt.getSegment(426,711) + #print "Segment of GPS Alt data from %d to %d: %s\n\n" % (426,711,gpsAltSeg.dictData) + + def outputXML(self, xmlFile): + # TODO: implement XML output + # ... + raise Exception("outputXML() not implemented yet") + + +def main(): + dirName = os.path.dirname(os.path.abspath(__file__)) + + # deal with command line arguments + parser = argparse.ArgumentParser(description='Analyze an APM Dataflash log for known issues') + parser.add_argument('logfile', type=argparse.FileType('r'), help='path to Dataflash log file') + parser.add_argument('-q', '--quiet', metavar='', action='store_const', const=True, help='quiet mode, do not print results') + parser.add_argument('-s', '--stats', metavar='', action='store_const', const=True, help='output performance stats') + parser.add_argument('-i', '--ignore', metavar='', action='store_const', const=True, help='ignore bad data lines') + parser.add_argument('-e', '--empty', metavar='', action='store_const', const=True, help='run an initial check for an empty log') + parser.add_argument('-x', '--xml', type=str, metavar='XML file', nargs='?', const='', default='', help='write output to specified XML file') + args = parser.parse_args() + + # load the log + startTime = time.time() + logdata = DataflashLog.DataflashLog(args.logfile.name, ignoreBadlines=args.ignore) # read log + endTime = time.time() + if args.stats: + print "Log file read time: %.2f seconds" % (endTime-startTime) + + # check for empty log if requested + if args.empty: + emptyErr = DataflashLog.DataflashLogHelper.isLogEmpty(logdata) + if emptyErr: + sys.stderr.write("Empty log file: %s, %s" % (logdata.filename, emptyErr)) + sys.exit(1) + + #run the tests, and gather timings + testSuite = TestSuite() + startTime = time.time() + testSuite.run(logdata) # run tests + endTime = time.time() + if args.stats: + print "Test suite run time: %.2f seconds" % (endTime-startTime) + + # deal with output + if not args.quiet: + testSuite.outputPlainText(args.stats) + if args.xml: + testSuite.outputXML(args.xml) + if not args.quiet: + print "XML output written to file: %s\n" % args.xml + + +if __name__ == "__main__": + main() + diff --git a/Tools/LogAnalyzer/UnitTest.py b/Tools/LogAnalyzer/UnitTest.py new file mode 100644 index 0000000000..6f8b30e7a7 --- /dev/null +++ b/Tools/LogAnalyzer/UnitTest.py @@ -0,0 +1,7 @@ +# +# +# Unit and regression tests for the LogAnalyzer code +# +# + +# TODO: implement unit+regression tests diff --git a/Tools/LogAnalyzer/logs/mechanical_fail.log b/Tools/LogAnalyzer/logs/mechanical_fail.log new file mode 100644 index 0000000000..f0ba451d87 --- /dev/null +++ b/Tools/LogAnalyzer/logs/mechanical_fail.log @@ -0,0 +1,7777 @@ +9 + +ArduCopter V3.1 (5c6503e2) +Free RAM: 1044 +APM 2 +FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format +FMT, 129, 23, PARM, Nf, Name,Value +FMT, 130, 45, GPS, BIHBcLLeeEefI, Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T +FMT, 131, 31, IMU, Iffffff, TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ +FMT, 132, 67, MSG, Z, Message +FMT, 25, 25, ATUN, BBfffff, Axis,TuneStep,RateMin,RateMax,RPGain,RDGain,SPGain +FMT, 26, 9, ATDE, cf, Angle,Rate +FMT, 9, 19, CURR, hIhhhf, ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot +FMT, 11, 11, MOT, hhhh, Mot1,Mot2,Mot3,Mot4 +FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch +FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit +FMT, 4, 25, CTUN, hcefchhhh, ThrIn,SonAlt,BarAlt,WPAlt,DesSonAlt,AngBst,CRate,ThrOut,DCRate +FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ +FMT, 6, 19, PM, BBHHIhBHB, RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr +FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng +FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw +FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng +FMT, 3, 6, MODE, Mh, Mode,ThrCrs +FMT, 10, 3, STRT, , +FMT, 13, 4, EV, B, Id +FMT, 20, 6, D16, Bh, Id,Value +FMT, 21, 6, DU16, BH, Id,Value +FMT, 22, 8, D32, Bi, Id,Value +FMT, 23, 8, DU32, BI, Id,Value +FMT, 24, 8, DFLT, Bf, Id,Value +FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain +FMT, 18, 27, CAM, IHLLeccC, GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw +FMT, 19, 5, ERR, BB, Subsys,ECode +PARM, SYSID_SW_MREV, 120.0000 +PARM, SYSID_SW_TYPE, 10.00000 +PARM, SYSID_THISMAV, 1.000000 +PARM, SYSID_MYGCS, 253.0000 +PARM, SERIAL3_BAUD, 57.00000 +PARM, TELEM_DELAY, 0.000000 +PARM, RTL_ALT, 7000.000 +PARM, SONAR_ENABLE, 0.000000 +PARM, SONAR_TYPE, 0.000000 +PARM, SONAR_GAIN, 0.800000 +PARM, FS_BATT_ENABLE, 1.000000 +PARM, FS_BATT_VOLTAGE, 14.00000 +PARM, FS_BATT_MAH, 0.000000 +PARM, FS_GPS_ENABLE, 1.000000 +PARM, FS_GCS_ENABLE, 0.000000 +PARM, GPS_HDOP_GOOD, 200.0000 +PARM, MAG_ENABLE, 1.000000 +PARM, FLOW_ENABLE, 0.000000 +PARM, SUPER_SIMPLE, 0.000000 +PARM, RTL_ALT_FINAL, 0.000000 +PARM, RSSI_PIN, -1.000000 +PARM, WP_YAW_BEHAVIOR, 2.000000 +PARM, WP_TOTAL, 4.000000 +PARM, WP_INDEX, 0.000000 +PARM, CIRCLE_RADIUS, 10.00000 +PARM, CIRCLE_RATE, 20.00000 +PARM, RTL_LOIT_TIME, 5000.000 +PARM, LAND_SPEED, 50.00000 +PARM, PILOT_VELZ_MAX, 250.0000 +PARM, THR_MIN, 130.0000 +PARM, THR_MAX, 1000.000 +PARM, FS_THR_ENABLE, 1.000000 +PARM, FS_THR_VALUE, 975.0000 +PARM, TRIM_THROTTLE, 352.0000 +PARM, THR_MID, 380.0000 +PARM, FLTMODE1, 0.000000 +PARM, FLTMODE2, 5.000000 +PARM, FLTMODE3, 11.00000 +PARM, FLTMODE4, 0.000000 +PARM, FLTMODE5, 2.000000 +PARM, FLTMODE6, 6.000000 +PARM, SIMPLE, 0.000000 +PARM, LOG_BITMASK, 1854.000 +PARM, ESC, 0.000000 +PARM, TUNE, 0.000000 +PARM, TUNE_LOW, 65.00000 +PARM, TUNE_HIGH, 225.0000 +PARM, FRAME, 1.000000 +PARM, CH7_OPT, 17.00000 +PARM, CH8_OPT, 0.000000 +PARM, ARMING_CHECK, 1.000000 +PARM, ANGLE_MAX, 3500.000 +PARM, ANGLE_RATE_MAX, 18000.00 +PARM, RC1_MIN, 994.0000 +PARM, RC1_TRIM, 1507.000 +PARM, RC1_MAX, 2022.000 +PARM, RC1_REV, 1.000000 +PARM, RC1_DZ, 30.00000 +PARM, RC2_MIN, 991.0000 +PARM, RC2_TRIM, 1504.000 +PARM, RC2_MAX, 2022.000 +PARM, RC2_REV, 1.000000 +PARM, RC2_DZ, 30.00000 +PARM, RC3_MIN, 994.0000 +PARM, RC3_TRIM, 1000.000 +PARM, RC3_MAX, 2022.000 +PARM, RC3_REV, 1.000000 +PARM, RC3_DZ, 30.00000 +PARM, RC4_MIN, 1070.000 +PARM, RC4_TRIM, 1495.000 +PARM, RC4_MAX, 1938.000 +PARM, RC4_REV, 1.000000 +PARM, RC4_DZ, 10.00000 +PARM, RC5_MIN, 1175.000 +PARM, RC5_TRIM, 1178.000 +PARM, RC5_MAX, 1850.000 +PARM, RC5_REV, 1.000000 +PARM, RC5_DZ, 0.000000 +PARM, RC5_FUNCTION, 0.000000 +PARM, RC6_MIN, 991.0000 +PARM, RC6_TRIM, 1498.000 +PARM, RC6_MAX, 2022.000 +PARM, RC6_REV, 1.000000 +PARM, RC6_DZ, 0.000000 +PARM, RC6_FUNCTION, 0.000000 +PARM, RC7_MIN, 991.0000 +PARM, RC7_TRIM, 991.0000 +PARM, RC7_MAX, 994.0000 +PARM, RC7_REV, 1.000000 +PARM, RC7_DZ, 0.000000 +PARM, RC7_FUNCTION, 0.000000 +PARM, RC8_MIN, 1506.000 +PARM, RC8_TRIM, 1507.000 +PARM, RC8_MAX, 1507.000 +PARM, RC8_REV, 1.000000 +PARM, RC8_DZ, 0.000000 +PARM, RC8_FUNCTION, 0.000000 +PARM, RC10_MIN, 1100.000 +PARM, RC10_TRIM, 1500.000 +PARM, RC10_MAX, 1900.000 +PARM, RC10_REV, 1.000000 +PARM, RC10_DZ, 0.000000 +PARM, RC10_FUNCTION, 0.000000 +PARM, RC11_MIN, 1100.000 +PARM, RC11_TRIM, 1500.000 +PARM, RC11_MAX, 1900.000 +PARM, RC11_REV, 1.000000 +PARM, RC11_DZ, 0.000000 +PARM, RC11_FUNCTION, 0.000000 +PARM, RC_SPEED, 490.0000 +PARM, ACRO_RP_P, 4.500000 +PARM, ACRO_YAW_P, 3.000000 +PARM, ACRO_BAL_ROLL, 1.000000 +PARM, ACRO_BAL_PITCH, 1.000000 +PARM, ACRO_TRAINER, 2.000000 +PARM, LED_MODE, 9.000000 +PARM, RATE_RLL_P, 0.105000 +PARM, RATE_RLL_I, 0.105000 +PARM, RATE_RLL_D, 0.015000 +PARM, RATE_RLL_IMAX, 500.0000 +PARM, RATE_PIT_P, 0.075000 +PARM, RATE_PIT_I, 0.075000 +PARM, RATE_PIT_D, 0.013500 +PARM, RATE_PIT_IMAX, 500.0000 +PARM, RATE_YAW_P, 0.200000 +PARM, RATE_YAW_I, 0.020000 +PARM, RATE_YAW_D, 0.000000 +PARM, RATE_YAW_IMAX, 800.0000 +PARM, LOITER_LAT_P, 1.000000 +PARM, LOITER_LAT_I, 0.500000 +PARM, LOITER_LAT_D, 0.000000 +PARM, LOITER_LAT_IMAX, 400.0000 +PARM, LOITER_LON_P, 1.000000 +PARM, LOITER_LON_I, 0.500000 +PARM, LOITER_LON_D, 0.000000 +PARM, LOITER_LON_IMAX, 400.0000 +PARM, THR_RATE_P, 6.000000 +PARM, THR_RATE_I, 0.000000 +PARM, THR_RATE_D, 0.000000 +PARM, THR_RATE_IMAX, 300.0000 +PARM, THR_ACCEL_P, 0.750000 +PARM, THR_ACCEL_I, 1.500000 +PARM, THR_ACCEL_D, 0.000000 +PARM, THR_ACCEL_IMAX, 500.0000 +PARM, OF_RLL_P, 2.500000 +PARM, OF_RLL_I, 0.500000 +PARM, OF_RLL_D, 0.120000 +PARM, OF_RLL_IMAX, 100.0000 +PARM, OF_PIT_P, 2.500000 +PARM, OF_PIT_I, 0.500000 +PARM, OF_PIT_D, 0.120000 +PARM, OF_PIT_IMAX, 100.0000 +PARM, STB_RLL_P, 4.500000 +PARM, STB_RLL_I, 0.100000 +PARM, STB_RLL_IMAX, 800.0000 +PARM, STB_PIT_P, 4.500000 +PARM, STB_PIT_I, 0.100000 +PARM, STB_PIT_IMAX, 800.0000 +PARM, STB_YAW_P, 4.500000 +PARM, STB_YAW_I, 0.000000 +PARM, STB_YAW_IMAX, 800.0000 +PARM, THR_ALT_P, 1.000000 +PARM, THR_ALT_I, 0.000000 +PARM, THR_ALT_IMAX, 300.0000 +PARM, HLD_LAT_P, 1.000000 +PARM, HLD_LAT_I, 0.000000 +PARM, HLD_LAT_IMAX, 0.000000 +PARM, HLD_LON_P, 1.000000 +PARM, HLD_LON_I, 0.000000 +PARM, HLD_LON_IMAX, 0.000000 +PARM, CAM_TRIGG_TYPE, 0.000000 +PARM, CAM_DURATION, 10.00000 +PARM, CAM_SERVO_ON, 1300.000 +PARM, CAM_SERVO_OFF, 1100.000 +PARM, CAM_TRIGG_DIST, 0.000000 +PARM, RELAY_PIN, 13.00000 +PARM, COMPASS_OFS_X, -68.20219 +PARM, COMPASS_OFS_Y, 22.18370 +PARM, COMPASS_OFS_Z, 73.09023 +PARM, COMPASS_DEC, 0.361231 +PARM, COMPASS_LEARN, 0.000000 +PARM, COMPASS_USE, 1.000000 +PARM, COMPASS_AUTODEC, 1.000000 +PARM, COMPASS_MOTCT, 0.000000 +PARM, COMPASS_MOT_X, 0.000000 +PARM, COMPASS_MOT_Y, 0.000000 +PARM, COMPASS_MOT_Z, 0.000000 +PARM, COMPASS_ORIENT, 8.000000 +PARM, COMPASS_EXTERNAL, 1.000000 +PARM, INS_PRODUCT_ID, 88.00000 +PARM, INS_ACCSCAL_X, 0.996883 +PARM, INS_ACCSCAL_Y, 1.002162 +PARM, INS_ACCSCAL_Z, 0.987875 +PARM, INS_ACCOFFS_X, -0.064104 +PARM, INS_ACCOFFS_Y, 0.211506 +PARM, INS_ACCOFFS_Z, 1.198524 +PARM, INS_GYROFFS_X, -0.028185 +PARM, INS_GYROFFS_Y, 0.015048 +PARM, INS_GYROFFS_Z, 0.001241 +PARM, INS_MPU6K_FILTER, 0.000000 +PARM, INAV_TC_XY, 2.500000 +PARM, INAV_TC_Z, 5.000000 +PARM, WPNAV_SPEED, 500.0000 +PARM, WPNAV_RADIUS, 200.0000 +PARM, WPNAV_SPEED_UP, 250.0000 +PARM, WPNAV_SPEED_DN, 150.0000 +PARM, WPNAV_LOIT_SPEED, 500.0000 +PARM, WPNAV_ACCEL, 100.0000 +PARM, SR0_RAW_SENS, 2.000000 +PARM, SR0_EXT_STAT, 2.000000 +PARM, SR0_RC_CHAN, 2.000000 +PARM, SR0_RAW_CTRL, 2.000000 +PARM, SR0_POSITION, 2.000000 +PARM, SR0_EXTRA1, 2.000000 +PARM, SR0_EXTRA2, 2.000000 +PARM, SR0_EXTRA3, 2.000000 +PARM, SR0_PARAMS, 0.000000 +PARM, SR3_RAW_SENS, 2.000000 +PARM, SR3_EXT_STAT, 2.000000 +PARM, SR3_RC_CHAN, 2.000000 +PARM, SR3_RAW_CTRL, 2.000000 +PARM, SR3_POSITION, 2.000000 +PARM, SR3_EXTRA1, 2.000000 +PARM, SR3_EXTRA2, 2.000000 +PARM, SR3_EXTRA3, 2.000000 +PARM, SR3_PARAMS, 0.000000 +PARM, AHRS_GPS_GAIN, 1.000000 +PARM, AHRS_GPS_USE, 1.000000 +PARM, AHRS_YAW_P, 0.100000 +PARM, AHRS_RP_P, 0.100000 +PARM, AHRS_WIND_MAX, 0.000000 +PARM, AHRS_TRIM_X, 0.006394 +PARM, AHRS_TRIM_Y, 0.007151 +PARM, AHRS_TRIM_Z, 0.000000 +PARM, AHRS_ORIENTATION, 0.000000 +PARM, AHRS_COMP_BETA, 0.100000 +PARM, AHRS_GPS_MINSATS, 6.000000 +PARM, AHRS_GPS_DELAY, 2.000000 +PARM, MNT_MODE, 0.000000 +PARM, MNT_RETRACT_X, 0.000000 +PARM, MNT_RETRACT_Y, 0.000000 +PARM, MNT_RETRACT_Z, 0.000000 +PARM, MNT_NEUTRAL_X, 0.000000 +PARM, MNT_NEUTRAL_Y, 0.000000 +PARM, MNT_NEUTRAL_Z, 0.000000 +PARM, MNT_CONTROL_X, 0.000000 +PARM, MNT_CONTROL_Y, 0.000000 +PARM, MNT_CONTROL_Z, 0.000000 +PARM, MNT_STAB_ROLL, 0.000000 +PARM, MNT_STAB_TILT, 0.000000 +PARM, MNT_STAB_PAN, 0.000000 +PARM, MNT_RC_IN_ROLL, 0.000000 +PARM, MNT_ANGMIN_ROL, -4500.000 +PARM, MNT_ANGMAX_ROL, 4500.000 +PARM, MNT_RC_IN_TILT, 0.000000 +PARM, MNT_ANGMIN_TIL, -4500.000 +PARM, MNT_ANGMAX_TIL, 4500.000 +PARM, MNT_RC_IN_PAN, 0.000000 +PARM, MNT_ANGMIN_PAN, -4500.000 +PARM, MNT_ANGMAX_PAN, 4500.000 +PARM, MNT_JSTICK_SPD, 0.000000 +PARM, BATT_MONITOR, 4.000000 +PARM, BATT_VOLT_PIN, 13.00000 +PARM, BATT_CURR_PIN, 12.00000 +PARM, BATT_VOLT_MULT, 10.39689 +PARM, BATT_AMP_PERVOLT, 18.00180 +PARM, BATT_AMP_OFFSET, 0.000000 +PARM, BATT_CAPACITY, 4200.000 +PARM, GND_ABS_PRESS, 100422.4 +PARM, GND_TEMP, 24.71102 +PARM, GND_ALT_OFFSET, 0.000000 +PARM, SCHED_DEBUG, 0.000000 +PARM, FENCE_ENABLE, 1.000000 +PARM, FENCE_TYPE, 1.000000 +PARM, FENCE_ACTION, 0.000000 +PARM, FENCE_ALT_MAX, 100.0000 +PARM, FENCE_RADIUS, 150.0000 +PARM, FENCE_MARGIN, 2.000000 +PARM, GPSGLITCH_ENABLE, 1.000000 +PARM, GPSGLITCH_RADIUS, 200.0000 +PARM, GPSGLITCH_ACCEL, 1000.000 +PARM, MOT_TCRV_ENABLE, 1.000000 +PARM, MOT_TCRV_MIDPCT, 52.00000 +PARM, MOT_TCRV_MAXPCT, 93.00000 +PARM, MOT_SPIN_ARMED, 0.000000 +PARM, RCMAP_ROLL, 1.000000 +PARM, RCMAP_PITCH, 2.000000 +PARM, RCMAP_THROTTLE, 3.000000 +PARM, RCMAP_YAW, 4.000000 +MSG, ArduCopter V3.1 (5c6503e2) +MODE, STABILIZE, 352 +D32, 9, 35888 +CMD, 4, 0, 16, 0, 0, 0.00, -39.4950300, 176.7483511 +EV, 10 +GPS, 3, 109206800, 1774, 9, 2.42, -39.4950300, 176.7483511, 0.05, 46.82, 0.03, 202.77, 0.080000, 66937 +CTUN, 0, 0.00, -0.06, 0.000000, 0.00, 0, -2, 0, 0 +ATT, 0.00, -0.30, 0.00, -4.66, 0.00, 358.89, 358.89 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.10, 0.000000, 0.00, 0, -2, 0, 0 +ATT, 0.00, -0.39, 0.00, -4.71, 0.00, 358.90, 358.90 +MOT, 994, 994, 994, 994 +GPS, 3, 109214200, 1774, 9, 2.42, -39.4950310, 176.7483504, 0.04, 46.82, 0.06, 202.77, 0.140000, 67138 +CTUN, 0, 0.00, 0.08, 0.000000, 0.00, 0, -2, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.76, 0.00, 358.92, 358.92 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -2, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.75, 0.00, 358.93, 358.93 +MOT, 994, 994, 994, 994 +GPS, 3, 109214400, 1774, 9, 2.42, -39.4950310, 176.7483505, 0.04, 46.83, 0.04, 202.77, 0.120000, 67338 +CTUN, 0, 0.00, -0.05, 0.000000, 0.00, 0, -2, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.74, 0.10, 358.94, 358.94 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.08, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.75, 0.00, 358.95, 358.95 +MOT, 994, 994, 994, 994 +GPS, 3, 109214600, 1774, 9, 2.42, -39.4950310, 176.7483505, 0.03, 46.84, 0.04, 202.77, 0.090000, 67538 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 358.96, 358.96 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.03, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.76, 0.10, 358.97, 358.97 +MOT, 994, 994, 994, 994 +GPS, 3, 109214800, 1774, 9, 2.42, -39.4950310, 176.7483504, 0.02, 46.83, 0.03, 202.77, 0.120000, 67740 +CTUN, 0, 0.00, -0.08, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 0.20, 358.98, 358.98 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.04, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 0.10, 358.99, 358.99 +MOT, 994, 994, 994, 994 +DU32, 7, 270937 +CURR, 0, 0, 1691, 0, 4962, 0.000000 +GPS, 3, 109215000, 1774, 9, 2.42, -39.4950311, 176.7483504, 0.00, 46.83, 0.05, 202.77, 0.120000, 67940 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.77, 6.13, 359.00, 359.00 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.05, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 23.59, 359.01, 359.01 +MOT, 994, 994, 994, 994 +GPS, 3, 109215200, 1774, 9, 2.42, -39.4950311, 176.7483503, 0.00, 46.83, 0.02, 202.77, 0.110000, 68140 +CTUN, 0, 0.00, 0.03, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.76, 41.15, 359.02, 359.02 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.02, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 45.31, 359.02, 359.02 +MOT, 994, 994, 994, 994 +GPS, 3, 109215400, 1774, 9, 2.42, -39.4950311, 176.7483503, 0.00, 46.84, 0.03, 202.77, 0.099999, 68340 +CTUN, 0, 0.00, 0.04, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.04, 359.04 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.11, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.04, 359.04 +MOT, 994, 994, 994, 994 +GPS, 3, 109215600, 1774, 9, 2.42, -39.4950311, 176.7483503, -0.01, 46.86, 0.01, 202.77, 0.080000, 68541 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 45.20, 359.05, 359.05 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.11, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.06, 359.06 +MOT, 994, 994, 994, 994 +GPS, 3, 109215800, 1774, 9, 2.42, -39.4950311, 176.7483503, -0.01, 46.85, 0.03, 202.77, 0.130000, 68741 +CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.79, 45.31, 359.07, 359.07 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.78, 45.20, 359.07, 359.07 +MOT, 994, 994, 994, 994 +DU32, 7, 270937 +CURR, 0, 0, 1695, 0, 4962, 0.000000 +GPS, 3, 109216000, 1774, 9, 2.42, -39.4950310, 176.7483503, -0.02, 46.87, 0.02, 202.77, 0.090000, 68941 +CTUN, 0, 0.00, 0.02, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.78, 45.20, 359.08, 359.08 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.07, 0.000000, 0.00, 0, -3, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.78, 45.31, 359.09, 359.09 +MOT, 994, 994, 994, 994 +GPS, 3, 109216200, 1774, 9, 2.42, -39.4950311, 176.7483503, -0.03, 46.87, 0.05, 202.77, 0.110000, 69141 +CTUN, 0, 0.00, 0.08, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.79, 32.73, 359.10, 359.10 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.10, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.78, 18.29, 359.11, 359.11 +MOT, 994, 994, 994, 994 +GPS, 3, 109216400, 1774, 9, 2.42, -39.4950310, 176.7483503, -0.02, 46.89, 0.02, 202.77, 0.110000, 69341 +CTUN, 0, 0.00, -0.03, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.77, 6.75, 359.12, 359.12 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.06, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.78, 1.76, 359.13, 359.13 +MOT, 994, 994, 994, 994 +GPS, 3, 109216600, 1774, 9, 2.42, -39.4950310, 176.7483503, -0.03, 46.89, 0.03, 202.77, 0.090000, 69541 +CTUN, 0, 0.00, 0.09, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.79, 0.00, 359.14, 359.14 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.79, 0.00, 359.14, 359.14 +MOT, 994, 994, 994, 994 +GPS, 3, 109216800, 1774, 9, 2.42, -39.4950310, 176.7483504, -0.03, 46.89, 0.05, 202.77, 0.110000, 69742 +CTUN, 0, 0.00, -0.04, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.50, 0.00, -4.78, 0.00, 359.15, 359.15 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.09, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.78, 0.00, 359.16, 359.16 +MOT, 994, 994, 994, 994 +DU32, 7, 270937 +CURR, 0, 0, 1686, 0, 4940, 0.000000 +GPS, 3, 109217000, 1774, 9, 2.42, -39.4950311, 176.7483504, -0.03, 46.89, 0.05, 202.77, 0.110000, 69942 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 0.00, 359.16, 359.16 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 0.10, 359.17, 359.17 +MOT, 994, 994, 994, 994 +GPS, 3, 109217200, 1774, 9, 2.42, -39.4950311, 176.7483505, -0.04, 46.89, 0.06, 202.77, 0.090000, 70143 +CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.77, 0.00, 359.18, 359.18 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, 0.02, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.76, 0.10, 359.19, 359.19 +MOT, 994, 994, 994, 994 +GPS, 3, 109217400, 1774, 9, 2.42, -39.4950312, 176.7483505, -0.04, 46.89, 0.05, 202.77, 0.130000, 70343 +CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 359.19, 359.19 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.02, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 359.20, 359.20 +MOT, 994, 994, 994, 994 +GPS, 3, 109217600, 1774, 9, 2.42, -39.4950312, 176.7483506, -0.04, 46.89, 0.08, 202.77, 0.110000, 70543 +CTUN, 0, 0.00, -0.03, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.76, 0.10, 359.21, 359.21 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.07, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.75, 0.10, 359.22, 359.22 +MOT, 994, 994, 994, 994 +GPS, 3, 109217800, 1774, 9, 2.42, -39.4950312, 176.7483506, -0.05, 46.90, 0.05, 202.77, 0.130000, 70744 +CTUN, 0, 0.00, -0.05, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.49, 0.00, -4.75, 0.10, 359.22, 359.22 +MOT, 994, 994, 994, 994 +CTUN, 0, 0.00, -0.05, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.76, 0.20, 359.23, 359.23 +MOT, 994, 994, 994, 994 +DU32, 7, 270937 +CURR, 0, 0, 1690, 0, 4962, 0.000000 +CTUN, 0, 0.00, 0.01, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.48, 0.00, -4.77, 0.20, 359.23, 359.23 +MOT, 994, 994, 994, 994 +GPS, 3, 109218000, 1774, 9, 2.42, -39.4950312, 176.7483506, -0.06, 46.90, 0.07, 202.77, 0.140000, 70963 +CTUN, 0, 0.00, 0.00, 0.000000, 0.00, 0, -4, 0, 0 +ATT, 0.00, -0.47, 0.00, -4.76, 0.10, 359.24, 359.24 +MOT, 994, 994, 994, 994 +EV, 15 +GPS, 3, 109218200, 1774, 9, 2.42, -39.4950313, 176.7483506, -0.07, 46.90, 0.08, 202.77, 0.160000, 71145 +CTUN, 135, 0.00, -0.10, 0.000000, 0.00, 0, -4, 133, 0 +ATT, 0.00, -0.47, 0.00, -4.76, 0.10, 359.24, 359.24 +MOT, 1149, 1130, 1152, 1127 +CTUN, 137, 0.00, -0.04, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.46, 0.00, -4.76, 0.10, 359.25, 359.25 +MOT, 1163, 1130, 1162, 1127 +GPS, 3, 109218400, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.08, 46.89, 0.07, 202.77, 0.140000, 71345 +CTUN, 137, 0.00, -0.04, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.46, 0.00, -4.75, 0.10, 359.27, 359.27 +MOT, 1162, 1129, 1160, 1127 +CTUN, 135, 0.00, -0.07, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.47, 0.00, -4.73, 0.20, 359.28, 359.28 +MOT, 1166, 1140, 1171, 1127 +GPS, 3, 109218600, 1774, 9, 2.42, -39.4950313, 176.7483506, -0.09, 46.90, 0.05, 202.77, 0.099999, 71545 +CTUN, 135, 0.00, 0.00, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.47, 0.00, -4.71, 0.00, 359.31, 359.31 +MOT, 1156, 1127, 1160, 1127 +CTUN, 137, 0.00, -0.02, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.49, 0.00, -4.71, 0.10, 359.32, 359.32 +MOT, 1159, 1149, 1181, 1127 +GPS, 3, 109218800, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.09, 46.90, 0.06, 202.77, 0.140000, 71746 +CTUN, 135, 0.00, -0.04, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.48, 0.00, -4.71, 0.00, 359.33, 359.33 +MOT, 1169, 1129, 1167, 1127 +CTUN, 135, 0.00, -0.04, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.48, 0.00, -4.71, 0.00, 359.34, 359.34 +MOT, 1166, 1145, 1183, 1127 +DU32, 7, 270969 +CURR, 133, 1069, 1688, 340, 4962, 1.545313 +GPS, 3, 109219000, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.09, 46.90, 0.08, 202.77, 0.120000, 71946 +CTUN, 137, 0.00, -0.05, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.47, 0.00, -4.70, 0.00, 359.35, 359.35 +MOT, 1178, 1128, 1179, 1127 +CTUN, 137, 0.00, -0.12, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.47, 0.00, -4.68, 0.00, 359.36, 359.36 +MOT, 1175, 1143, 1192, 1127 +GPS, 3, 109219200, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.11, 46.90, 0.04, 202.77, 0.099999, 72146 +CTUN, 137, 0.00, -0.12, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.47, 0.00, -4.68, 0.10, 359.37, 359.37 +MOT, 1176, 1130, 1179, 1127 +CTUN, 135, 0.00, -0.08, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.47, 0.00, -4.69, 0.10, 359.38, 359.38 +MOT, 1198, 1127, 1185, 1140 +GPS, 3, 109219400, 1774, 9, 2.42, -39.4950314, 176.7483506, -0.12, 46.91, 0.03, 202.77, 0.110000, 72347 +CTUN, 135, 0.00, -0.14, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.48, 0.00, -4.69, 0.10, 359.38, 359.38 +MOT, 1181, 1141, 1192, 1127 +CTUN, 135, 0.00, -0.09, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.47, 0.00, -4.68, 0.00, 359.40, 359.40 +MOT, 1176, 1151, 1200, 1127 +GPS, 3, 109219600, 1774, 9, 2.42, -39.4950314, 176.7483505, -0.13, 46.92, 0.04, 202.77, 0.099999, 72547 +CTUN, 135, 0.00, -0.05, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.46, 0.00, -4.68, 0.00, 359.41, 359.41 +MOT, 1181, 1127, 1179, 1129 +CTUN, 135, 0.00, -0.15, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.48, 0.00, -4.67, 0.00, 359.42, 359.42 +MOT, 1191, 1136, 1200, 1127 +GPS, 3, 109219800, 1774, 9, 2.42, -39.4950314, 176.7483505, -0.14, 46.91, 0.03, 202.77, 0.099999, 72747 +CTUN, 135, 0.00, -0.12, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.48, 0.00, -4.66, 0.00, 359.42, 359.42 +MOT, 1190, 1129, 1192, 1127 +CTUN, 135, 0.00, -0.12, 0.000000, 0.00, 0, -5, 133, 0 +ATT, 0.00, -0.47, 0.00, -4.65, 0.00, 359.43, 359.43 +MOT, 1187, 1147, 1207, 1127 +DU32, 7, 270969 +CURR, 134, 2401, 1674, 335, 4940, 2.455562 +GPS, 3, 109220000, 1774, 9, 2.42, -39.4950315, 176.7483504, -0.15, 46.90, 0.03, 202.77, 0.090000, 72948 +CTUN, 137, 0.00, -0.14, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.47, 0.00, -4.66, 0.00, 359.44, 359.44 +MOT, 1183, 1139, 1196, 1127 +CTUN, 137, 0.00, -0.10, 0.000000, 0.00, 0, -5, 134, 0 +ATT, 0.00, -0.47, 0.00, -4.65, 0.00, 359.45, 359.45 +MOT, 1199, 1149, 1221, 1127 +GPS, 3, 109220200, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.16, 46.90, 0.03, 202.77, 0.090000, 73148 +CTUN, 138, 0.00, 0.04, 0.000000, 0.00, 0, -6, 135, 0 +ATT, 0.00, -0.47, 0.00, -4.64, 0.00, 359.46, 359.46 +MOT, 1202, 1129, 1200, 1127 +CTUN, 137, 0.00, -0.13, 0.000000, 0.00, 0, -6, 134, 0 +ATT, 0.00, -0.48, 0.00, -4.62, 0.20, 359.47, 359.47 +MOT, 1198, 1129, 1196, 1127 +GPS, 3, 109220400, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.16, 46.91, 0.04, 202.77, 0.099999, 73348 +CTUN, 140, 0.00, -0.04, 0.000000, 0.00, 0, -6, 136, 0 +ATT, 0.00, -0.48, 0.00, -4.61, 0.10, 359.48, 359.48 +MOT, 1210, 1140, 1219, 1127 +CTUN, 141, 0.00, -0.04, 0.000000, 0.00, 0, -5, 137, 0 +ATT, 0.00, -0.48, 0.00, -4.59, 0.20, 359.49, 359.49 +MOT, 1200, 1143, 1213, 1127 +GPS, 3, 109220600, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.15, 46.91, 0.03, 202.77, 0.110000, 73549 +CTUN, 164, 0.00, -0.09, 0.000000, 0.00, 0, -6, 152, 0 +ATT, 0.00, -0.47, 0.00, -4.57, 0.10, 359.49, 359.49 +MOT, 1200, 1137, 1211, 1127 +CTUN, 166, 0.00, -0.24, 0.000000, 0.00, 0, -6, 154, 0 +ATT, 0.00, -0.47, 0.00, -4.58, 0.20, 359.50, 359.50 +MOT, 1208, 1138, 1211, 1127 +GPS, 3, 109220800, 1774, 9, 2.42, -39.4950316, 176.7483504, -0.17, 46.91, 0.03, 202.77, 0.110000, 73749 +CTUN, 169, 0.00, 0.00, 0.000000, 0.00, 0, -6, 156, 0 +ATT, 0.00, -0.47, 0.00, -4.56, 0.10, 359.52, 359.52 +MOT, 1214, 1145, 1228, 1127 +CTUN, 177, 0.00, -0.02, 0.000000, 0.00, 0, -6, 161, 0 +ATT, 0.00, -0.48, 0.00, -4.54, 0.10, 359.52, 359.52 +MOT, 1217, 1152, 1238, 1127 +DU32, 7, 270969 +CURR, 167, 3831, 1683, 411, 4962, 3.494093 +PM, 0, 0, 1, 1000, 7381955, 0, 0, 0, 0 +GPS, 3, 109221000, 1774, 9, 2.42, -39.4950317, 176.7483504, -0.16, 46.91, 0.06, 202.77, 0.130000, 73949 +CTUN, 188, 0.00, -0.01, 0.000000, 0.00, 0, -6, 169, 0 +ATT, 0.00, -0.48, 0.00, -4.52, 0.10, 359.53, 359.53 +MOT, 1228, 1148, 1244, 1127 +CTUN, 201, 0.00, -0.15, 0.000000, 0.00, 0, -5, 177, 0 +ATT, 0.00, -0.48, 0.00, -4.51, 0.20, 359.54, 359.54 +MOT, 1221, 1146, 1236, 1127 +EV, 28 +GPS, 3, 109221200, 1774, 9, 2.42, -39.4950318, 176.7483503, -0.17, 46.91, 0.03, 202.77, 0.110000, 74149 +CTUN, 214, 0.00, 0.05, 0.000000, 0.00, 0, -5, 186, 0 +ATT, 0.00, -0.48, 0.00, -4.48, 0.10, 359.55, 359.54 +MOT, 1222, 1153, 1240, 1135 +EV, 16 +CTUN, 230, 0.00, -0.23, 0.000000, 0.00, 0, -4, 197, 0 +ATT, 0.00, -0.49, 0.00, -4.45, 0.10, 359.56, 359.54 +MOT, 1242, 1158, 1258, 1138 +GPS, 3, 109221400, 1774, 9, 2.42, -39.4950318, 176.7483503, -0.17, 46.92, 0.02, 202.77, 0.110000, 74350 +CTUN, 243, 0.00, -0.06, 0.000000, 0.00, 0, -4, 206, 0 +ATT, 0.00, -0.49, 0.00, -4.40, 0.10, 359.58, 359.54 +MOT, 1255, 1162, 1255, 1162 +CTUN, 259, 0.00, -0.08, 0.000000, 0.00, 0, -5, 217, 0 +ATT, 0.00, -0.50, 0.00, -4.34, 0.10, 359.59, 359.54 +MOT, 1254, 1189, 1280, 1162 +GPS, 3, 109221600, 1774, 9, 2.42, -39.4950319, 176.7483503, -0.17, 46.91, 0.03, 202.77, 0.099999, 74550 +CTUN, 263, 0.00, 0.00, 0.000000, 0.00, 0, -4, 219, 0 +ATT, 0.00, -0.52, 0.00, -4.25, 0.10, 359.60, 359.54 +MOT, 1261, 1186, 1275, 1172 +CTUN, 282, 0.00, 0.00, 0.000000, 0.00, 0, -4, 232, 0 +ATT, 0.00, -0.53, 0.00, -4.15, 0.10, 359.62, 359.54 +MOT, 1270, 1205, 1296, 1178 +GPS, 3, 109221800, 1774, 9, 2.42, -39.4950319, 176.7483503, -0.16, 46.92, 0.02, 202.77, 0.080000, 74750 +CTUN, 293, 0.00, 0.00, 0.000000, 0.00, 0, -4, 238, 0 +ATT, 0.00, -0.54, 0.00, -4.06, 0.10, 359.64, 359.54 +MOT, 1275, 1212, 1300, 1187 +CTUN, 295, 0.00, -0.18, 0.000000, 0.00, 0, -3, 241, 0 +ATT, 0.00, -0.55, 0.00, -4.06, 0.20, 359.65, 359.54 +MOT, 1294, 1199, 1292, 1201 +DU32, 7, 270713 +CURR, 246, 5903, 1642, 795, 4940, 5.161857 +GPS, 3, 109222000, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.16, 46.92, 0.03, 202.77, 0.090000, 74950 +CTUN, 306, 0.00, -0.28, 0.000000, 0.00, 0, -4, 248, 0 +ATT, 0.00, -0.55, 0.00, -3.94, 0.51, 359.67, 359.57 +MOT, 1308, 1205, 1299, 1205 +CTUN, 321, 0.00, -0.06, 0.000000, 0.00, 0, -4, 257, 0 +ATT, 0.00, -0.57, 0.00, -3.88, 0.72, 359.70, 359.75 +MOT, 1313, 1227, 1312, 1207 +GPS, 3, 109222200, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.17, 46.93, 0.03, 202.77, 0.099999, 75151 +CTUN, 321, 0.00, -0.10, 0.000000, 0.00, 0, -5, 259, 0 +ATT, 0.00, -0.56, 0.00, -3.79, 1.66, 359.72, 0.08 +MOT, 1304, 1254, 1307, 1201 +CTUN, 332, 0.00, -0.19, 0.000000, 0.00, 0, -5, 264, 0 +ATT, 0.00, -0.59, 0.00, -3.65, 1.97, 359.76, 0.60 +MOT, 1307, 1275, 1316, 1190 +GPS, 3, 109222400, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.18, 46.93, 0.04, 202.77, 0.110000, 75351 +CTUN, 337, 0.00, -0.17, 0.000000, 0.00, 0, -6, 269, 0 +ATT, 0.00, -0.63, 0.00, -3.58, 2.70, 359.80, 1.29 +MOT, 1335, 1276, 1302, 1195 +CTUN, 355, 0.00, -0.12, 0.000000, 0.00, 0, -5, 278, 0 +ATT, 0.00, -0.65, 0.00, -3.44, 2.70, 359.83, 2.06 +MOT, 1376, 1275, 1292, 1203 +GPS, 3, 109222600, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.18, 46.94, 0.04, 202.77, 0.110000, 75551 +CTUN, 366, 0.00, -0.18, 0.000000, 0.00, 0, -5, 289, 0 +ATT, 0.00, -0.70, 0.00, -3.30, 2.70, 359.88, 2.79 +MOT, 1393, 1298, 1303, 1202 +CTUN, 371, 0.00, -0.03, 0.000000, 0.00, 0, -4, 290, 0 +ATT, 0.00, -0.77, 0.00, -2.97, 4.57, 359.94, 4.05 +MOT, 1387, 1349, 1286, 1180 +GPS, 3, 109222800, 1774, 9, 2.42, -39.4950320, 176.7483503, -0.19, 46.96, 0.02, 202.77, 0.090000, 75752 +CTUN, 387, 0.00, -0.12, 0.000000, 0.00, 0, -4, 303, 0 +ATT, 0.00, -0.85, 0.00, -2.54, 4.46, 0.01, 5.42 +MOT, 1397, 1389, 1298, 1172 +CTUN, 398, 0.00, -0.09, 0.000000, 0.00, 0, -4, 309, 0 +ATT, 0.00, -0.95, 0.00, -2.03, 4.88, 0.12, 6.77 +MOT, 1418, 1408, 1287, 1169 +DU32, 7, 270713 +CURR, 316, 8656, 1641, 1523, 4940, 8.217794 +GPS, 3, 109223000, 1774, 9, 2.42, -39.4950321, 176.7483503, -0.19, 46.97, 0.06, 202.77, 0.090000, 75952 +CTUN, 408, 0.00, -0.18, 0.000000, 0.00, 0, -3, 316, 0 +ATT, 0.00, -1.09, 0.00, -1.41, 5.50, 0.26, 8.26 +MOT, 1441, 1429, 1277, 1163 +CTUN, 429, 0.00, -0.17, 0.000000, 0.00, 0, -3, 332, 0 +ATT, 0.00, -1.10, 0.00, -0.32, 5.40, 0.44, 9.86 +MOT, 1485, 1454, 1243, 1199 +GPS, 3, 109223200, 1774, 9, 2.42, -39.4950321, 176.7483502, -0.19, 46.98, 0.04, 202.77, 0.099999, 76152 +CTUN, 442, 0.00, -0.43, 0.000000, 0.00, 0, 0, 339, 0 +ATT, 0.00, -1.04, 0.00, 1.68, 5.50, 0.82, 10.82 +MOT, 1477, 1477, 1227, 1231 +CTUN, 458, 0.00, -0.28, 0.000000, 0.00, 0, 3, 351, 0 +ATT, 0.00, -0.75, 0.00, 4.65, 5.71, 1.36, 11.36 +MOT, 1469, 1509, 1222, 1262 +GPS, 3, 109223400, 1774, 9, 2.42, -39.4950323, 176.7483502, -0.20, 47.00, 0.11, 202.77, 0.060000, 76353 +CTUN, 476, 0.00, -0.40, 0.000000, 0.00, 2, 7, 365, 0 +ATT, 0.00, -0.13, -0.50, 8.25, 6.02, 2.34, 12.34 +MOT, 1453, 1538, 1226, 1306 +CTUN, 476, 0.00, -0.29, 0.000000, 0.00, 4, 12, 367, 0 +ATT, 0.00, 0.47, -4.20, 11.64, 6.13, 3.80, 13.80 +MOT, 1489, 1489, 1257, 1299 +GPS, 3, 109223600, 1774, 9, 2.42, -39.4950327, 176.7483503, -0.19, 47.03, 0.23, 202.77, 0.000000, 76553 +CTUN, 476, 0.00, -0.15, 0.000000, 0.00, 5, 17, 368, 0 +ATT, 0.00, 0.75, -5.07, 12.38, 5.81, 6.07, 15.58 +MOT, 1430, 1505, 1336, 1267 +CTUN, 476, 0.00, 0.11, 0.000000, 0.00, 4, 17, 367, 0 +ATT, 0.00, 0.11, -5.93, 11.30, 4.46, 8.96, 17.13 +MOT, 1383, 1499, 1372, 1279 +GPS, 3, 109223800, 1774, 9, 2.42, -39.4950337, 176.7483505, -0.14, 47.07, 0.56, 179.17, -0.080000, 76753 +CTUN, 476, 0.00, 0.16, 0.000000, 0.00, 3, 19, 365, 0 +ATT, 0.00, -0.31, -6.15, 9.21, 2.39, 11.72, 18.03 +MOT, 1390, 1438, 1391, 1307 +CTUN, 476, 0.00, 0.31, 0.000000, 0.00, 1, 21, 364, 0 +ATT, 0.00, -0.33, -6.37, 6.23, 1.66, 14.06, 18.55 +MOT, 1364, 1440, 1413, 1303 +DU32, 7, 270713 +CURR, 363, 12184, 1622, 2053, 4897, 13.83383 +GPS, 3, 109224000, 1774, 9, 2.42, -39.4950352, 176.7483507, -0.05, 47.11, 0.81, 176.44, -0.110000, 76954 +CTUN, 476, 0.00, 0.17, 0.000000, 0.00, 0, 22, 363, 0 +ATT, 0.00, -0.61, -7.02, 3.43, 0.83, 15.98, 18.83 +MOT, 1356, 1423, 1399, 1338 +CTUN, 476, 0.00, 0.01, 0.000000, 0.00, 0, 22, 363, 0 +ATT, 0.00, -0.96, -7.45, 1.47, 0.10, 17.30, 18.83 +MOT, 1348, 1417, 1410, 1342 +GPS, 3, 109224200, 1774, 9, 2.42, -39.4950373, 176.7483507, 0.01, 47.16, 1.14, 177.70, -0.120000, 77153 +CTUN, 474, 0.00, 0.28, 0.000000, 0.00, 0, 20, 362, 0 +ATT, 0.00, -1.68, -9.20, -0.10, 0.10, 18.20, 18.83 +MOT, 1360, 1400, 1392, 1360 +CTUN, 474, 0.00, 0.19, 0.000000, 0.00, 0, 19, 362, 0 +ATT, 0.00, -1.81, -11.66, -2.54, 0.00, 18.80, 18.83 +MOT, 1367, 1392, 1396, 1358 +GPS, 3, 109224400, 1774, 9, 2.42, -39.4950396, 176.7483506, 0.07, 47.21, 1.28, 179.83, -0.170000, 77354 +CTUN, 474, 0.00, 0.14, 0.000000, 0.00, 0, 15, 362, 0 +ATT, 1.87, -1.93, -17.09, -5.55, 0.00, 19.22, 18.83 +MOT, 1362, 1394, 1385, 1371 +CTUN, 474, 0.00, 0.33, 0.000000, 0.00, 2, 11, 364, 0 +ATT, 2.38, -0.95, -19.05, -9.25, 0.10, 19.47, 18.83 +MOT, 1360, 1402, 1382, 1376 +GPS, 3, 109224600, 1774, 9, 2.42, -39.4950419, 176.7483504, 0.12, 47.23, 1.24, 182.10, -0.099999, 77554 +CTUN, 474, 0.00, 0.36, 0.000000, 0.00, 5, 7, 367, 0 +ATT, 1.72, 0.00, -19.49, -12.80, 0.20, 19.61, 18.83 +MOT, 1387, 1387, 1397, 1363 +CTUN, 476, 0.00, 0.39, 0.000000, 0.00, 7, 3, 369, 0 +ATT, 0.00, 0.40, -17.31, -15.07, 0.20, 19.68, 18.83 +MOT, 1431, 1347, 1422, 1342 +GPS, 3, 109224800, 1774, 9, 2.42, -39.4950437, 176.7483502, 0.16, 47.26, 1.06, 182.40, 0.000000, 77755 +CTUN, 513, 0.00, 0.60, 0.000000, 0.00, 10, 2, 406, 0 +ATT, 0.00, 0.31, -12.09, -15.19, 0.20, 19.74, 18.83 +MOT, 1385, 1472, 1403, 1441 +CTUN, 524, 0.00, 0.74, 0.000000, 0.00, 7, 7, 413, 0 +ATT, 0.00, 0.24, -10.57, -13.00, 0.10, 19.61, 18.83 +MOT, 1438, 1446, 1428, 1419 +DU32, 7, 270713 +CURR, 417, 15902, 1593, 2783, 4897, 19.21214 +GPS, 3, 109225000, 1774, 9, 2.42, -39.4950449, 176.7483505, 0.23, 47.26, 0.68, 179.00, 0.099999, 77955 +CTUN, 526, 0.00, 0.57, 0.000000, 0.00, 5, 23, 417, 0 +ATT, 0.00, -0.04, -11.37, -10.70, 0.00, 19.28, 18.83 +MOT, 1418, 1485, 1430, 1415 +CTUN, 524, 0.00, 0.39, 0.000000, 0.00, 3, 39, 412, 0 +ATT, 0.00, -0.23, -12.46, -9.43, 0.00, 18.86, 18.83 +MOT, 1404, 1499, 1420, 1403 +GPS, 3, 109225200, 1774, 9, 2.42, -39.4950454, 176.7483510, 0.34, 47.31, 0.36, 173.65, 0.010000, 78155 +CTUN, 524, 0.00, 0.42, 0.000000, 0.00, 3, 53, 412, 0 +ATT, 0.00, -0.81, -13.33, -8.64, 0.00, 18.51, 18.83 +MOT, 1425, 1476, 1415, 1411 +CTUN, 524, 0.00, 0.56, 0.000000, 0.00, 2, 69, 411, 0 +ATT, 0.00, -1.30, -13.18, -7.87, 0.00, 18.29, 18.83 +MOT, 1421, 1476, 1423, 1402 +GPS, 3, 109225400, 1774, 9, 2.42, -39.4950451, 176.7483520, 0.50, 47.44, 0.45, 118.53, -0.210000, 78355 +CTUN, 524, 0.00, 0.79, 0.000000, 0.00, 2, 87, 411, 0 +ATT, 0.00, -1.38, -13.18, -7.60, 0.00, 18.27, 18.83 +MOT, 1399, 1492, 1414, 1418 +CTUN, 526, 0.00, 0.67, 0.000000, 0.00, 2, 105, 414, 0 +ATT, 0.00, -1.24, -12.96, -7.22, 0.10, 18.34, 18.83 +MOT, 1428, 1470, 1398, 1440 +GPS, 3, 109225600, 1774, 9, 2.42, -39.4950444, 176.7483530, 0.75, 47.60, 0.52, 71.44, -0.440000, 78555 +CTUN, 524, 0.00, 0.90, 0.000000, 0.00, 2, 123, 411, 0 +ATT, 0.00, -1.08, -13.11, -7.11, 1.66, 18.40, 19.10 +MOT, 1422, 1488, 1414, 1399 +CTUN, 524, 0.00, 1.16, 0.000000, 0.00, 2, 141, 411, 0 +ATT, 0.00, -0.93, -13.40, -7.60, 3.22, 18.77, 19.85 +MOT, 1413, 1505, 1402, 1402 +GPS, 3, 109225800, 1774, 9, 2.42, -39.4950432, 176.7483540, 1.07, 47.84, 0.74, 48.24, -0.760000, 78756 +CTUN, 524, 0.00, 1.30, 0.000000, 0.00, 2, 159, 411, 0 +ATT, 0.00, -0.93, -13.98, -8.22, 2.70, 19.63, 20.77 +MOT, 1430, 1465, 1396, 1432 +CTUN, 524, 0.00, 1.40, 0.000000, 0.00, 3, 173, 412, 0 +ATT, 0.00, -0.74, -14.92, -8.89, 0.10, 20.61, 21.11 +MOT, 1392, 1470, 1429, 1437 +DU32, 7, 270713 +CURR, 402, 20022, 1589, 2437, 4940, 26.21315 +GPS, 3, 109226000, 1774, 9, 2.42, -39.4950418, 176.7483550, 1.47, 48.11, 0.86, 37.28, -1.030000, 78956 +CTUN, 516, 0.00, 1.59, 0.000000, 0.00, 3, 188, 402, 0 +ATT, 0.00, -0.47, -15.36, -9.77, 0.10, 21.26, 21.11 +MOT, 1413, 1434, 1409, 1430 +CTUN, 510, 0.00, 1.90, 0.000000, 0.00, 4, 195, 400, 0 +ATT, 0.00, -0.19, -15.36, -10.45, 0.10, 21.62, 21.11 +MOT, 1387, 1456, 1399, 1435 +GPS, 3, 109226200, 1774, 9, 2.42, -39.4950400, 176.7483562, 1.91, 48.43, 1.10, 32.72, -1.270000, 79156 +CTUN, 508, 0.00, 2.19, 0.000000, 0.00, 4, 198, 393, 0 +ATT, 0.00, 0.00, -15.36, -10.50, 0.00, 21.80, 21.11 +MOT, 1390, 1442, 1405, 1410 +CTUN, 509, 0.00, 2.33, 0.000000, 0.00, 4, 197, 395, 0 +ATT, 0.00, 0.45, -15.36, -10.52, 0.10, 21.79, 21.11 +MOT, 1382, 1460, 1381, 1432 +GPS, 3, 109226400, 1774, 9, 2.42, -39.4950380, 176.7483577, 2.36, 48.77, 1.26, 30.97, -1.420000, 79356 +CTUN, 497, 0.00, 2.47, 0.000000, 0.00, 4, 194, 381, 0 +ATT, 0.00, 0.93, -15.79, -10.36, 0.00, 21.68, 21.11 +MOT, 1379, 1438, 1373, 1402 +CTUN, 500, 0.00, 2.66, 0.000000, 0.00, 4, 190, 384, 0 +ATT, 0.00, 1.19, -15.57, -10.34, 0.00, 21.48, 21.11 +MOT, 1388, 1438, 1354, 1425 +GPS, 3, 109226600, 1774, 9, 2.42, -39.4950356, 176.7483592, 2.79, 49.14, 1.42, 29.03, -1.450000, 79557 +CTUN, 500, 0.00, 2.99, 0.000000, 0.00, 4, 186, 384, 0 +ATT, 0.00, 1.50, -15.14, -10.38, 0.10, 21.30, 21.11 +MOT, 1378, 1454, 1382, 1391 +CTUN, 500, 0.00, 3.26, 0.000000, 0.00, 4, 182, 384, 0 +ATT, 0.00, 1.30, -15.14, -10.37, 0.00, 21.20, 21.11 +MOT, 1371, 1457, 1352, 1425 +GPS, 3, 109226800, 1774, 9, 2.42, -39.4950329, 176.7483611, 3.21, 49.45, 1.67, 29.62, -1.390000, 79757 +CTUN, 500, 0.00, 3.42, 0.000000, 0.00, 4, 179, 384, 0 +ATT, 0.00, 1.18, -14.92, -10.56, 0.10, 21.12, 21.11 +MOT, 1370, 1464, 1373, 1398 +CTUN, 500, 0.00, 3.67, 0.000000, 0.00, 4, 176, 384, 0 +ATT, 0.00, 0.85, -14.70, -10.80, 0.00, 20.95, 21.11 +MOT, 1369, 1470, 1381, 1385 +DU32, 7, 270713 +CURR, 384, 23918, 1638, 2120, 4897, 32.12435 +GPS, 3, 109227000, 1774, 9, 2.42, -39.4950300, 176.7483634, 3.62, 49.75, 1.83, 31.55, -1.350000, 79958 +CTUN, 500, 0.00, 3.83, 0.000000, 0.00, 4, 174, 384, 0 +ATT, 0.00, 0.45, -14.63, -11.14, 0.10, 20.79, 21.11 +MOT, 1372, 1469, 1365, 1399 +CTUN, 503, 0.00, 3.89, 0.000000, 0.00, 4, 168, 384, 0 +ATT, 0.00, 0.13, -14.70, -11.26, 0.00, 20.62, 21.11 +MOT, 1365, 1477, 1365, 1397 +GPS, 3, 109227200, 1774, 9, 2.42, -39.4950269, 176.7483658, 4.00, 50.04, 2.00, 31.76, -1.300000, 80158 +CTUN, 500, 0.00, 4.25, 0.000000, 0.00, 4, 163, 384, 0 +ATT, 0.00, 0.06, -15.14, -11.37, 0.20, 20.55, 21.11 +MOT, 1381, 1461, 1369, 1394 +CTUN, 500, 0.00, 4.39, 0.000000, 0.00, 5, 160, 388, 0 +ATT, 0.00, -0.15, -15.36, -11.64, 0.00, 20.49, 21.11 +MOT, 1359, 1490, 1368, 1405 +GPS, 3, 109227400, 1774, 9, 2.42, -39.4950235, 176.7483682, 4.37, 50.31, 2.13, 30.68, -1.250000, 80358 +CTUN, 503, 0.00, 4.46, 0.000000, 0.00, 5, 158, 388, 0 +ATT, 0.00, -0.31, -14.92, -11.66, 0.00, 20.48, 21.11 +MOT, 1400, 1442, 1368, 1412 +CTUN, 503, 0.00, 4.79, 0.000000, 0.00, 5, 158, 385, 0 +ATT, 0.00, 0.04, -14.92, -11.49, 0.00, 20.48, 21.11 +MOT, 1389, 1454, 1361, 1405 +GPS, 3, 109227600, 1774, 9, 2.42, -39.4950198, 176.7483708, 4.74, 50.60, 2.27, 30.25, -1.230000, 80558 +CTUN, 500, 0.00, 4.93, 0.000000, 0.00, 5, 158, 385, 0 +ATT, 0.00, 0.21, -15.14, -11.76, 0.10, 20.41, 21.11 +MOT, 1372, 1473, 1355, 1410 +CTUN, 500, 0.00, 5.11, 0.000000, 0.00, 5, 156, 388, 0 +ATT, 0.00, 0.28, -15.28, -11.83, 0.10, 20.37, 21.11 +MOT, 1385, 1463, 1369, 1404 +GPS, 3, 109227800, 1774, 9, 2.42, -39.4950159, 176.7483734, 5.10, 50.89, 2.38, 29.46, -1.240000, 80759 +CTUN, 500, 0.00, 5.32, 0.000000, 0.00, 5, 156, 385, 0 +ATT, 0.00, 0.46, -16.15, -12.29, 0.00, 20.51, 21.11 +MOT, 1402, 1432, 1369, 1407 +CTUN, 503, 0.00, 5.40, 0.000000, 0.00, 6, 157, 389, 0 +ATT, 0.00, 0.46, -15.79, -12.76, 0.10, 20.62, 21.11 +MOT, 1356, 1489, 1376, 1405 +DU32, 7, 270713 +CURR, 386, 27772, 1632, 2005, 4876, 37.88295 +GPS, 3, 109228000, 1774, 9, 2.42, -39.4950118, 176.7483761, 5.46, 51.19, 2.51, 28.74, -1.250000, 80960 +CTUN, 500, 0.00, 5.62, 0.000000, 0.00, 6, 157, 386, 0 +ATT, 0.00, 0.21, -16.22, -12.96, 0.00, 20.73, 21.11 +MOT, 1334, 1496, 1344, 1439 +CTUN, 500, 0.00, 5.52, 0.000000, 0.00, 6, 158, 386, 0 +ATT, 0.00, 0.19, -16.44, -13.16, 0.10, 20.91, 21.11 +MOT, 1378, 1454, 1369, 1413 +GPS, 3, 109228200, 1774, 9, 2.42, -39.4950075, 176.7483790, 5.80, 51.46, 2.68, 28.42, -1.240000, 81159 +CTUN, 500, 0.00, 5.89, 0.000000, 0.00, 7, 159, 387, 0 +ATT, 0.00, 0.20, -16.44, -13.53, 0.00, 21.00, 21.11 +MOT, 1373, 1463, 1381, 1400 +CTUN, 500, 0.00, 5.98, 0.000000, 0.00, 7, 158, 387, 0 +ATT, 0.00, 0.49, -17.09, -14.01, 0.00, 21.04, 21.11 +MOT, 1393, 1441, 1368, 1416 +GPS, 3, 109228400, 1774, 9, 2.42, -39.4950029, 176.7483821, 6.15, 51.73, 2.84, 28.05, -1.260000, 81360 +CTUN, 500, 0.00, 6.09, 0.000000, 0.00, 7, 160, 387, 0 +ATT, 0.00, 0.49, -17.31, -14.25, 0.10, 21.04, 21.11 +MOT, 1370, 1464, 1357, 1427 +CTUN, 500, 0.00, 6.40, 0.000000, 0.00, 8, 164, 388, 0 +ATT, 0.00, 0.63, -17.53, -14.34, 0.00, 20.95, 21.11 +MOT, 1380, 1458, 1357, 1427 +GPS, 3, 109228600, 1774, 9, 2.42, -39.4949981, 176.7483851, 6.51, 52.03, 2.94, 27.33, -1.260000, 81560 +CTUN, 500, 0.00, 6.60, 0.000000, 0.00, 8, 168, 388, 0 +ATT, 0.00, 0.53, -17.74, -14.31, 0.10, 20.90, 21.11 +MOT, 1335, 1510, 1362, 1415 +CTUN, 500, 0.00, 6.98, 0.000000, 0.00, 7, 171, 387, 0 +ATT, 0.00, 0.33, -17.74, -14.12, 0.00, 20.89, 21.11 +MOT, 1377, 1463, 1369, 1409 +GPS, 3, 109228800, 1774, 9, 2.42, -39.4949930, 176.7483886, 6.89, 52.30, 3.15, 27.74, -1.280000, 81761 +CTUN, 500, 0.00, 7.05, 0.000000, 0.00, 8, 167, 388, 0 +ATT, 0.00, 0.40, -17.74, -14.67, 0.00, 20.87, 21.11 +MOT, 1372, 1466, 1355, 1429 +CTUN, 500, 0.00, 7.29, 0.000000, 0.00, 8, 167, 388, 0 +ATT, 0.00, 0.69, -17.31, -14.84, 0.10, 20.94, 21.11 +MOT, 1368, 1473, 1358, 1423 +DU32, 7, 270713 +CURR, 388, 31650, 1629, 2171, 4940, 43.74749 +GPS, 3, 109229000, 1774, 9, 2.42, -39.4949878, 176.7483920, 7.28, 52.59, 3.25, 27.40, -1.320000, 81961 +CTUN, 500, 0.00, 7.41, 0.000000, 0.00, 8, 168, 388, 0 +ATT, 0.00, 0.68, -17.53, -14.85, 0.00, 21.12, 21.11 +MOT, 1373, 1453, 1353, 1443 +CTUN, 500, 0.00, 7.54, 0.000000, 0.00, 8, 168, 388, 0 +ATT, 0.00, 0.77, -18.83, -14.96, 0.00, 21.21, 21.11 +MOT, 1382, 1450, 1380, 1410 +GPS, 3, 109229200, 1774, 9, 2.42, -39.4949823, 176.7483955, 7.66, 52.88, 3.35, 26.84, -1.320000, 82161 +CTUN, 500, 0.00, 7.68, 0.000000, 0.00, 9, 169, 389, 0 +ATT, 0.00, 0.76, -19.27, -15.77, 0.10, 21.32, 21.11 +MOT, 1360, 1472, 1353, 1441 +CTUN, 500, 0.00, 7.81, 0.000000, 0.00, 10, 167, 390, 0 +ATT, 0.00, 0.75, -18.83, -16.59, 0.00, 21.40, 21.11 +MOT, 1372, 1458, 1380, 1420 +GPS, 3, 109229400, 1774, 9, 2.42, -39.4949768, 176.7483993, 8.02, 53.14, 3.47, 27.21, -1.320000, 82361 +CTUN, 503, 0.00, 8.12, 0.000000, 0.00, 11, 168, 394, 0 +ATT, 0.00, 0.64, -19.05, -16.63, 0.10, 21.47, 21.11 +MOT, 1373, 1470, 1378, 1431 +CTUN, 500, 0.00, 8.17, 0.000000, 0.00, 11, 166, 391, 0 +ATT, 0.00, 0.63, -19.49, -17.05, 0.00, 21.46, 21.11 +MOT, 1392, 1444, 1365, 1433 +GPS, 3, 109229600, 1774, 9, 2.42, -39.4949709, 176.7484031, 8.38, 53.42, 3.62, 27.04, -1.300000, 82561 +CTUN, 500, 0.00, 8.30, 0.000000, 0.00, 12, 164, 392, 0 +ATT, 0.00, 0.24, -19.49, -17.67, 0.00, 21.38, 21.11 +MOT, 1333, 1516, 1370, 1420 +CTUN, 500, 0.00, 8.52, 0.000000, 0.00, 12, 164, 392, 0 +ATT, 0.00, -0.25, -19.70, -17.59, 0.00, 21.21, 21.11 +MOT, 1380, 1471, 1361, 1427 +GPS, 3, 109229800, 1774, 9, 2.42, -39.4949648, 176.7484073, 8.73, 53.68, 3.83, 27.39, -1.260000, 82762 +CTUN, 500, 0.00, 8.81, 0.000000, 0.00, 13, 166, 393, 0 +ATT, 0.00, -0.38, -19.70, -18.26, 0.00, 21.12, 21.11 +MOT, 1340, 1513, 1351, 1443 +CTUN, 500, 0.00, 8.87, 0.000000, 0.00, 13, 168, 393, 0 +ATT, 0.00, -0.33, -19.49, -18.28, 0.00, 21.19, 21.11 +MOT, 1369, 1474, 1375, 1430 +DU32, 7, 270713 +CURR, 393, 35555, 1616, 2255, 4897, 49.79305 +GPS, 3, 109230000, 1774, 9, 2.42, -39.4949583, 176.7484116, 9.09, 53.97, 4.03, 27.18, -1.280000, 82962 +CTUN, 500, 0.00, 9.06, 0.000000, 0.00, 13, 168, 393, 0 +ATT, 0.00, -0.44, -19.27, -18.36, 0.10, 21.22, 21.11 +MOT, 1392, 1451, 1371, 1434 +CTUN, 500, 0.00, 9.15, 0.000000, 0.00, 13, 169, 393, 0 +ATT, 0.00, -0.69, -19.27, -18.22, 0.00, 21.26, 21.11 +MOT, 1392, 1451, 1414, 1391 +GPS, 3, 109230200, 1774, 9, 2.42, -39.4949514, 176.7484159, 9.45, 54.27, 4.18, 26.57, -1.310000, 83163 +CTUN, 500, 0.00, 9.42, 0.000000, 0.00, 14, 167, 394, 0 +ATT, 0.00, -1.15, -19.70, -18.94, 0.00, 21.48, 21.11 +MOT, 1390, 1444, 1367, 1451 +CTUN, 500, 0.00, 9.47, 0.000000, 0.00, 14, 159, 394, 0 +ATT, 0.00, -0.93, -19.92, -19.17, 0.20, 21.57, 21.11 +MOT, 1364, 1472, 1378, 1437 +GPS, 3, 109230400, 1774, 9, 2.42, -39.4949441, 176.7484201, 9.79, 54.57, 4.37, 25.60, -1.300000, 83362 +CTUN, 500, 0.00, 9.57, 0.000000, 0.00, 14, 152, 394, 0 +ATT, 0.00, -0.65, -19.92, -19.13, 0.00, 21.57, 21.11 +MOT, 1388, 1453, 1379, 1432 +CTUN, 500, 0.00, 9.78, 0.000000, 0.00, 14, 147, 394, 0 +ATT, 0.00, -0.68, -20.14, -19.27, 0.00, 21.50, 21.11 +MOT, 1359, 1488, 1356, 1449 +GPS, 3, 109230600, 1774, 9, 2.42, -39.4949367, 176.7484245, 10.09, 54.81, 4.52, 25.13, -1.190000, 83563 +CTUN, 500, 0.00, 9.84, 0.000000, 0.00, 14, 144, 394, 0 +ATT, 0.00, -0.30, -20.57, -19.04, 0.00, 21.37, 21.11 +MOT, 1365, 1481, 1377, 1428 +CTUN, 500, 0.00, 10.12, 0.000000, 0.00, 14, 142, 394, 0 +ATT, 0.00, -0.11, -21.22, -19.20, 0.00, 21.37, 21.11 +MOT, 1359, 1485, 1369, 1438 +GPS, 3, 109230800, 1774, 9, 2.42, -39.4949289, 176.7484288, 10.37, 55.05, 4.64, 24.29, -1.090000, 83763 +CTUN, 500, 0.00, 10.25, 0.000000, 0.00, 14, 141, 394, 0 +ATT, 0.00, 0.00, -21.22, -19.30, 0.00, 21.46, 21.11 +MOT, 1367, 1472, 1367, 1446 +CTUN, 500, 0.00, 10.35, 0.000000, 0.00, 14, 142, 394, 0 +ATT, 0.00, -0.13, -21.00, -19.12, 0.00, 21.49, 21.11 +MOT, 1361, 1490, 1371, 1430 +DU32, 7, 270713 +CURR, 394, 39492, 1630, 2280, 4897, 55.94674 +PM, 0, 0, 0, 1000, 10271, 0, 0, 0, 0 +GPS, 3, 109231000, 1774, 9, 2.42, -39.4949207, 176.7484331, 10.66, 55.29, 4.83, 23.32, -1.060000, 83963 +CTUN, 500, 0.00, 10.55, 0.000000, 0.00, 14, 143, 394, 0 +ATT, 0.00, -0.25, -21.22, -18.97, 0.00, 21.61, 21.11 +MOT, 1347, 1498, 1376, 1431 +CTUN, 500, 0.00, 10.54, 0.000000, 0.00, 14, 140, 394, 0 +ATT, 0.00, -0.15, -21.00, -19.21, 0.00, 21.75, 21.11 +MOT, 1333, 1501, 1347, 1471 +GPS, 3, 109231200, 1774, 9, 2.42, -39.4949126, 176.7484375, 10.94, 55.51, 4.93, 23.08, -1.070000, 84164 +CTUN, 500, 0.00, 10.71, 0.000000, 0.00, 14, 138, 394, 0 +ATT, 0.00, -0.05, -21.44, -18.87, 0.00, 21.85, 21.11 +MOT, 1370, 1471, 1395, 1416 +CTUN, 503, 0.00, 10.81, 0.000000, 0.00, 14, 134, 397, 0 +ATT, 0.00, -0.10, -22.53, -19.22, 0.00, 21.84, 21.11 +MOT, 1333, 1514, 1374, 1443 +GPS, 3, 109231400, 1774, 9, 2.42, -39.4949039, 176.7484419, 11.20, 55.75, 5.12, 22.36, -1.050000, 84364 +CTUN, 503, 0.00, 10.91, 0.000000, 0.00, 15, 130, 398, 0 +ATT, 0.00, 0.53, -22.75, -19.95, 0.00, 21.82, 21.11 +MOT, 1396, 1451, 1367, 1455 +CTUN, 503, 0.00, 10.95, 0.000000, 0.00, 17, 121, 400, 0 +ATT, 0.00, 0.15, -22.75, -20.70, 0.00, 21.77, 21.11 +MOT, 1398, 1457, 1378, 1443 +GPS, 3, 109231600, 1774, 9, 2.42, -39.4948950, 176.7484465, 11.43, 55.95, 5.27, 22.03, -0.940000, 84564 +CTUN, 503, 0.00, 11.09, 0.000000, 0.00, 17, 120, 400, 0 +ATT, 0.00, -0.72, -22.75, -20.62, 0.00, 21.66, 21.11 +MOT, 1336, 1513, 1397, 1431 +CTUN, 503, 0.00, 11.32, 0.000000, 0.00, 17, 120, 400, 0 +ATT, 0.00, -0.61, -22.75, -21.13, 0.00, 21.67, 21.11 +MOT, 1404, 1446, 1391, 1435 +GPS, 3, 109231800, 1774, 9, 2.42, -39.4948860, 176.7484510, 11.65, 56.14, 5.36, 21.41, -0.880000, 84765 +CTUN, 503, 0.00, 11.36, 0.000000, 0.00, 18, 114, 401, 0 +ATT, 0.00, -1.16, -22.75, -21.31, 0.00, 21.66, 21.11 +MOT, 1358, 1486, 1390, 1446 +CTUN, 500, 0.00, 11.41, 0.000000, 0.00, 18, 119, 401, 0 +ATT, 0.00, -0.82, -22.75, -21.34, 0.00, 21.71, 21.11 +MOT, 1392, 1459, 1437, 1393 +DU32, 7, 270713 +CURR, 399, 43471, 1591, 2336, 4918, 62.41039 +GPS, 3, 109232000, 1774, 9, 2.42, -39.4948765, 176.7484555, 11.87, 56.32, 5.59, 20.90, -0.850000, 84965 +CTUN, 503, 0.00, 11.66, 0.000000, 0.00, 20, 110, 403, 0 +ATT, 0.00, -1.34, -22.96, -22.52, 0.00, 21.74, 21.11 +MOT, 1384, 1471, 1379, 1455 +CTUN, 503, 0.00, 11.16, 0.000000, 0.00, 22, 96, 405, 0 +ATT, 0.00, -0.96, -22.96, -23.42, 0.00, 21.68, 21.11 +MOT, 1399, 1471, 1408, 1420 +GPS, 3, 109232200, 1774, 9, 2.42, -39.4948665, 176.7484599, 12.02, 56.52, 5.81, 19.69, -0.840000, 85165 +CTUN, 503, 0.00, 11.29, 0.000000, 0.00, 23, 83, 406, 0 +ATT, 0.00, -0.82, -22.75, -24.04, -0.21, 21.61, 21.08 +MOT, 1388, 1478, 1396, 1440 +CTUN, 503, 0.00, 11.23, 0.000000, 0.00, 26, 61, 409, 0 +ATT, 0.00, -0.47, -22.96, -25.41, -0.97, 21.57, 20.84 +MOT, 1397, 1466, 1423, 1428 +GPS, 3, 109232400, 1774, 9, 2.42, -39.4948561, 176.7484644, 12.07, 56.66, 6.05, 19.07, -0.670000, 85365 +CTUN, 503, 0.00, 11.39, 0.000000, 0.00, 27, 38, 410, 0 +ATT, 0.00, -0.43, -22.96, -25.74, -1.95, 21.14, 20.33 +MOT, 1416, 1460, 1427, 1416 +CTUN, 503, 0.00, 11.43, 0.000000, 0.00, 28, 17, 411, 0 +ATT, 0.00, -0.31, -22.96, -26.15, -1.95, 20.41, 19.73 +MOT, 1397, 1479, 1396, 1451 +GPS, 3, 109232600, 1774, 9, 2.42, -39.4948452, 176.7484690, 12.03, 56.71, 6.38, 18.69, -0.370000, 85566 +CTUN, 503, 0.00, 11.35, 0.000000, 0.00, 28, 0, 411, 0 +ATT, 0.00, -0.08, -22.96, -25.93, -1.95, 19.66, 19.13 +MOT, 1395, 1485, 1390, 1453 +CTUN, 503, 0.00, 11.42, 0.000000, 0.00, 27, -11, 410, 0 +ATT, 0.00, 0.14, -22.96, -25.33, -1.62, 18.97, 18.56 +MOT, 1411, 1465, 1421, 1421 +GPS, 3, 109232800, 1774, 9, 2.42, -39.4948337, 176.7484738, 11.93, 56.70, 6.68, 18.28, -0.050000, 85766 +CTUN, 503, 0.00, 11.47, 0.000000, 0.00, 25, -21, 408, 0 +ATT, 0.00, 0.01, -22.75, -24.67, 0.00, 18.39, 18.32 +MOT, 1391, 1506, 1382, 1431 +CTUN, 500, 0.00, 11.39, 0.000000, 0.00, 22, -26, 402, 0 +ATT, 0.00, 0.30, -22.96, -23.18, 0.00, 17.96, 18.32 +MOT, 1387, 1496, 1353, 1450 +DU32, 7, 270713 +CURR, 403, 47539, 1582, 2360, 4940, 69.01168 +GPS, 3, 109233000, 1774, 9, 2.42, -39.4948216, 176.7484787, 11.82, 56.64, 7.02, 17.79, 0.160000, 85966 +CTUN, 503, 0.00, 11.47, 0.000000, 0.00, 20, -26, 400, 0 +ATT, 0.00, 0.69, -22.96, -22.30, 0.00, 17.77, 18.32 +MOT, 1383, 1491, 1380, 1422 +CTUN, 503, 0.00, 11.65, 0.000000, 0.00, 19, -29, 402, 0 +ATT, 0.00, 0.65, -23.18, -21.56, 0.00, 17.86, 18.32 +MOT, 1407, 1468, 1353, 1458 +GPS, 3, 109233200, 1774, 9, 2.42, -39.4948091, 176.7484837, 11.73, 56.55, 7.30, 17.35, 0.300000, 86166 +CTUN, 503, 0.00, 11.75, 0.000000, 0.00, 17, -28, 400, 0 +ATT, 0.00, 0.78, -23.25, -20.81, 0.00, 18.01, 18.32 +MOT, 1385, 1474, 1365, 1452 +CTUN, 503, 0.00, 11.50, 0.000000, 0.00, 16, -24, 399, 0 +ATT, 0.00, 0.81, -23.18, -20.11, 0.00, 18.18, 18.32 +MOT, 1362, 1493, 1363, 1454 +GPS, 3, 109233400, 1774, 9, 2.42, -39.4947963, 176.7484887, 11.67, 56.46, 7.50, 17.12, 0.360000, 86367 +CTUN, 503, 0.00, 11.63, 0.000000, 0.00, 15, -19, 398, 0 +ATT, 0.00, 0.54, -23.18, -19.34, 0.00, 18.41, 18.32 +MOT, 1361, 1492, 1363, 1452 +CTUN, 505, 0.00, 11.36, 0.000000, 0.00, 14, -7, 400, 0 +ATT, 0.00, 0.28, -23.18, -18.62, 0.00, 18.64, 18.32 +MOT, 1333, 1522, 1360, 1461 +GPS, 3, 109233600, 1774, 9, 2.42, -39.4947831, 176.7484940, 11.63, 56.39, 7.66, 17.05, 0.320000, 86567 +CTUN, 505, 0.00, 11.07, 0.000000, 0.00, 12, 10, 398, 0 +ATT, 0.00, 0.00, -22.96, -17.88, 0.00, 18.87, 18.32 +MOT, 1359, 1481, 1369, 1463 +CTUN, 513, 0.00, 11.17, 0.000000, 0.00, 12, 27, 408, 0 +ATT, 0.00, -0.28, -22.96, -17.48, 0.00, 19.06, 18.32 +MOT, 1375, 1480, 1390, 1465 +GPS, 3, 109233800, 1774, 9, 2.42, -39.4947698, 176.7484992, 11.62, 56.36, 7.74, 16.96, 0.220000, 86767 +CTUN, 513, 0.00, 11.41, 0.000000, 0.00, 12, 39, 408, 0 +ATT, 0.00, -0.12, -23.40, -17.21, 0.00, 19.31, 18.32 +MOT, 1387, 1462, 1416, 1445 +CTUN, 510, 0.00, 11.59, 0.000000, 0.00, 12, 49, 404, 0 +ATT, 0.00, -0.23, -23.40, -17.59, 0.00, 19.42, 18.32 +MOT, 1348, 1499, 1362, 1484 +DU32, 7, 270713 +CURR, 404, 51559, 1595, 2465, 4918, 75.52970 +GPS, 3, 109234000, 1774, 9, 2.42, -39.4947562, 176.7485045, 11.70, 56.40, 7.86, 16.78, 0.010000, 86967 +CTUN, 510, 0.00, 11.41, 0.000000, 0.00, 12, 56, 404, 0 +ATT, 0.00, -0.25, -23.18, -17.44, 0.00, 19.50, 18.32 +MOT, 1371, 1476, 1385, 1461 +CTUN, 510, 0.00, 11.72, 0.000000, 0.00, 12, 63, 404, 0 +ATT, 0.00, -0.23, -23.40, -17.53, 0.00, 19.47, 18.32 +MOT, 1359, 1492, 1383, 1459 +GPS, 3, 109234200, 1774, 9, 2.42, -39.4947425, 176.7485097, 11.81, 56.48, 7.86, 16.71, -0.160000, 87168 +CTUN, 510, 0.00, 11.78, 0.000000, 0.00, 13, 69, 405, 0 +ATT, 0.00, -0.05, -23.18, -17.97, 0.00, 19.40, 18.32 +MOT, 1387, 1462, 1381, 1468 +CTUN, 510, 0.00, 11.70, 0.000000, 0.00, 13, 74, 405, 0 +ATT, 0.00, -0.36, -23.40, -18.01, 0.00, 19.33, 18.32 +MOT, 1384, 1464, 1384, 1464 +GPS, 3, 109234400, 1774, 9, 2.42, -39.4947287, 176.7485149, 11.96, 56.60, 7.92, 16.52, -0.360000, 87368 +CTUN, 510, 0.00, 11.98, 0.000000, 0.00, 14, 76, 406, 0 +ATT, 0.00, -0.32, -23.18, -18.33, 0.00, 19.26, 18.32 +MOT, 1370, 1481, 1392, 1455 +CTUN, 510, 0.00, 11.88, 0.000000, 0.00, 14, 75, 406, 0 +ATT, 0.00, -0.25, -23.25, -18.72, 0.00, 19.16, 18.32 +MOT, 1389, 1466, 1362, 1484 +GPS, 3, 109234600, 1774, 9, 2.42, -39.4947151, 176.7485200, 12.11, 56.71, 7.85, 16.34, -0.410000, 87568 +CTUN, 510, 0.00, 12.08, 0.000000, 0.00, 15, 71, 407, 0 +ATT, 0.00, -0.38, -23.18, -19.31, 0.00, 19.05, 18.32 +MOT, 1401, 1460, 1400, 1444 +CTUN, 513, 0.00, 11.95, 0.000000, 0.00, 17, 61, 413, 0 +ATT, 0.00, -0.07, -23.47, -19.99, 0.00, 18.86, 18.32 +MOT, 1383, 1495, 1390, 1459 +GPS, 3, 109234800, 1774, 9, 2.42, -39.4947013, 176.7485250, 12.24, 56.83, 7.86, 16.10, -0.440000, 87769 +CTUN, 510, 0.00, 12.17, 0.000000, 0.00, 18, 51, 410, 0 +ATT, 0.00, 0.14, -23.40, -20.78, 0.10, 18.81, 18.32 +MOT, 1405, 1473, 1403, 1454 +CTUN, 513, 0.00, 12.11, 0.000000, 0.00, 19, 40, 415, 0 +ATT, 0.00, 0.11, -23.40, -21.36, 0.00, 18.77, 18.32 +MOT, 1400, 1482, 1401, 1456 +DU32, 7, 270713 +CURR, 416, 55635, 1639, 2507, 4940, 82.22855 +GPS, 3, 109235000, 1774, 9, 2.42, -39.4946877, 176.7485299, 12.32, 56.92, 7.83, 15.85, -0.330000, 87969 +CTUN, 512, 0.00, 12.05, 0.000000, 0.00, 21, 29, 415, 0 +ATT, 0.00, -0.01, -23.40, -22.20, 0.20, 18.71, 18.32 +MOT, 1430, 1459, 1397, 1458 +CTUN, 514, 0.00, 12.22, 0.000000, 0.00, 22, 17, 419, 0 +ATT, 0.00, 0.25, -23.40, -22.63, 0.00, 18.62, 18.32 +MOT, 1414, 1479, 1402, 1461 +GPS, 3, 109235200, 1774, 9, 2.42, -39.4946738, 176.7485348, 12.34, 56.98, 7.90, 15.64, -0.180000, 88169 +CTUN, 513, 0.00, 12.28, 0.000000, 0.00, 23, 6, 419, 0 +ATT, 0.00, 0.41, -23.47, -23.20, 0.10, 18.68, 18.32 +MOT, 1398, 1495, 1398, 1465 +CTUN, 513, 0.00, 11.94, 0.000000, 0.00, 24, -7, 420, 0 +ATT, 0.00, 0.55, -23.25, -23.61, 0.20, 18.75, 18.32 +MOT, 1374, 1511, 1408, 1448 +GPS, 3, 109235400, 1774, 9, 2.42, -39.4946598, 176.7485396, 12.31, 56.98, 8.02, 14.91, -0.010000, 88370 +CTUN, 513, 0.00, 12.06, 0.000000, 0.00, 23, -13, 419, 0 +ATT, 0.00, 0.24, -23.18, -23.45, 0.00, 18.84, 18.32 +MOT, 1388, 1503, 1411, 1459 +CTUN, 513, 0.00, 12.08, 0.000000, 0.00, 23, -22, 419, 0 +ATT, 0.00, -0.12, -23.18, -23.35, 0.00, 18.89, 18.32 +MOT, 1415, 1468, 1398, 1459 +GPS, 3, 109235600, 1774, 9, 2.42, -39.4946457, 176.7485443, 12.24, 56.94, 8.08, 14.57, 0.170000, 88569 +CTUN, 513, 0.00, 11.98, 0.000000, 0.00, 23, -31, 419, 0 +ATT, 0.00, -0.09, -23.18, -23.34, 0.00, 18.82, 18.32 +MOT, 1385, 1501, 1417, 1453 +CTUN, 510, 0.00, 12.13, 0.000000, 0.00, 22, -37, 414, 0 +ATT, 0.00, -0.19, -23.18, -23.16, 0.10, 18.76, 18.32 +MOT, 1393, 1502, 1394, 1468 +GPS, 3, 109235800, 1774, 9, 2.42, -39.4946312, 176.7485491, 12.14, 56.87, 8.30, 14.48, 0.280000, 88770 +CTUN, 514, 0.00, 12.17, 0.000000, 0.00, 22, -39, 419, 0 +ATT, 0.00, -0.11, -23.18, -22.72, 0.00, 18.77, 18.32 +MOT, 1340, 1534, 1331, 1528 +CTUN, 510, 0.00, 11.97, 0.000000, 0.00, 18, -28, 410, 0 +ATT, 0.00, 0.19, -23.18, -21.09, 0.10, 18.82, 18.32 +MOT, 1407, 1480, 1425, 1428 +DU32, 7, 270713 +CURR, 409, 59817, 1603, 2834, 4962, 89.32329 +GPS, 3, 109236000, 1774, 9, 2.42, -39.4946165, 176.7485539, 12.07, 56.78, 8.43, 14.05, 0.410000, 88970 +CTUN, 513, 0.00, 11.88, 0.000000, 0.00, 17, -15, 413, 0 +ATT, 0.00, 0.10, -23.18, -20.18, 0.00, 18.79, 18.32 +MOT, 1394, 1474, 1365, 1481 +CTUN, 510, 0.00, 12.03, 0.000000, 0.00, 16, -10, 408, 0 +ATT, 0.00, 0.00, -23.18, -19.99, 0.20, 18.79, 18.32 +MOT, 1357, 1511, 1419, 1444 +GPS, 3, 109236200, 1774, 9, 2.42, -39.4946016, 176.7485588, 12.03, 56.70, 8.58, 14.27, 0.350000, 89171 +CTUN, 513, 0.00, 12.01, 0.000000, 0.00, 16, -11, 412, 0 +ATT, 0.00, -0.27, -22.96, -19.82, 0.00, 18.76, 18.32 +MOT, 1405, 1477, 1394, 1451 +CTUN, 513, 0.00, 12.11, 0.000000, 0.00, 17, -10, 413, 0 +ATT, 0.00, -0.25, -23.25, -19.96, 0.00, 18.70, 18.32 +MOT, 1364, 1520, 1382, 1464 +GPS, 3, 109236400, 1774, 9, 2.42, -39.4945866, 176.7485637, 12.00, 56.66, 8.64, 14.21, 0.220000, 89370 +CTUN, 513, 0.00, 11.90, 0.000000, 0.00, 17, -11, 413, 0 +ATT, 0.00, -0.21, -22.96, -20.24, 0.00, 18.66, 18.32 +MOT, 1399, 1477, 1393, 1462 +CTUN, 513, 0.00, 12.01, 0.000000, 0.00, 17, -12, 413, 0 +ATT, 0.00, -0.36, -22.96, -20.08, 0.00, 18.70, 18.32 +MOT, 1409, 1470, 1396, 1461 +GPS, 3, 109236600, 1774, 9, 2.42, -39.4945712, 176.7485685, 11.98, 56.64, 8.73, 13.75, 0.180000, 89571 +CTUN, 513, 0.00, 11.83, 0.000000, 0.00, 17, -8, 413, 0 +ATT, 0.00, -0.49, -22.96, -20.15, 0.10, 18.65, 18.32 +MOT, 1388, 1486, 1398, 1442 +CTUN, 513, 0.00, 11.90, 0.000000, 0.00, 17, -9, 413, 0 +ATT, 0.00, -0.39, -22.96, -20.09, 0.00, 18.66, 18.32 +MOT, 1394, 1482, 1411, 1444 +GPS, 3, 109236800, 1774, 9, 2.42, -39.4945561, 176.7485734, 11.94, 56.56, 8.72, 13.89, 0.260000, 89771 +CTUN, 513, 0.00, 11.64, 0.000000, 0.00, 17, -8, 413, 0 +ATT, 0.00, -0.34, -22.96, -20.24, 0.20, 18.77, 18.32 +MOT, 1355, 1525, 1383, 1468 +CTUN, 514, 0.00, 11.59, 0.000000, 0.00, 16, -2, 413, 0 +ATT, 0.00, -0.16, -22.75, -19.77, 0.00, 18.94, 18.32 +MOT, 1381, 1476, 1389, 1464 +DU32, 7, 270713 +CURR, 412, 63937, 1589, 2580, 4962, 96.24298 +GPS, 3, 109237000, 1774, 9, 2.42, -39.4945405, 176.7485782, 11.90, 56.54, 8.82, 13.43, 0.220000, 89972 +CTUN, 513, 0.00, 11.77, 0.000000, 0.00, 15, 4, 411, 0 +ATT, 0.00, -0.04, -22.96, -19.38, 0.00, 19.00, 18.32 +MOT, 1388, 1476, 1398, 1465 +CTUN, 513, 0.00, 11.73, 0.000000, 0.00, 15, 15, 411, 0 +ATT, 0.00, -0.06, -22.96, -18.94, 0.00, 18.99, 18.32 +MOT, 1371, 1499, 1373, 1480 +GPS, 3, 109237200, 1774, 9, 2.42, -39.4945248, 176.7485830, 11.91, 56.54, 8.94, 13.30, 0.140000, 90172 +CTUN, 513, 0.00, 11.85, 0.000000, 0.00, 15, 21, 411, 0 +ATT, 0.00, 0.12, -22.75, -18.96, 0.00, 18.94, 18.32 +MOT, 1361, 1519, 1369, 1474 +CTUN, 513, 0.00, 11.82, 0.000000, 0.00, 15, 26, 411, 0 +ATT, 0.00, -0.12, -22.75, -18.85, 0.00, 18.89, 18.32 +MOT, 1388, 1489, 1398, 1449 +GPS, 3, 109237400, 1774, 9, 2.42, -39.4945088, 176.7485879, 11.95, 56.56, 9.09, 13.55, 0.020000, 90372 +CTUN, 513, 0.00, 11.82, 0.000000, 0.00, 15, 28, 411, 0 +ATT, 0.00, 0.01, -22.75, -19.14, 0.00, 18.84, 18.32 +MOT, 1365, 1502, 1394, 1461 +CTUN, 513, 0.00, 11.92, 0.000000, 0.00, 15, 31, 411, 0 +ATT, 0.00, -0.13, -22.75, -18.91, 0.10, 18.88, 18.32 +MOT, 1384, 1481, 1396, 1461 +GPS, 3, 109237600, 1774, 9, 2.42, -39.4944927, 176.7485930, 12.00, 56.62, 9.18, 13.63, -0.110000, 90572 +CTUN, 513, 0.00, 11.85, 0.000000, 0.00, 15, 37, 411, 0 +ATT, 0.00, -0.02, -22.75, -18.91, 0.00, 18.84, 18.32 +MOT, 1361, 1513, 1391, 1458 +CTUN, 513, 0.00, 12.07, 0.000000, 0.00, 15, 44, 411, 0 +ATT, 0.00, 0.02, -22.53, -18.94, 0.00, 18.79, 18.32 +MOT, 1385, 1489, 1380, 1469 +GPS, 3, 109237800, 1774, 9, 2.42, -39.4944765, 176.7485980, 12.09, 56.68, 9.22, 13.51, -0.160000, 90773 +CTUN, 513, 0.00, 11.89, 0.000000, 0.00, 15, 49, 411, 0 +ATT, 0.00, -0.14, -22.75, -19.14, 0.00, 18.80, 18.32 +MOT, 1382, 1475, 1393, 1456 +CTUN, 513, 0.00, 11.98, 0.000000, 0.00, 15, 51, 411, 0 +ATT, 0.00, -0.05, -22.75, -19.29, 0.00, 18.86, 18.32 +MOT, 1365, 1511, 1392, 1459 +DU32, 7, 270713 +CURR, 411, 68048, 1597, 2425, 4897, 102.9687 +GPS, 3, 109238000, 1774, 9, 2.42, -39.4944600, 176.7486032, 12.18, 56.78, 9.36, 13.77, -0.270000, 90973 +CTUN, 513, 0.00, 12.13, 0.000000, 0.00, 16, 53, 412, 0 +ATT, 0.00, -0.01, -22.53, -19.50, 0.00, 18.87, 18.32 +MOT, 1405, 1466, 1402, 1449 +CTUN, 510, 0.00, 12.13, 0.000000, 0.00, 16, 52, 408, 0 +ATT, 0.00, 0.12, -22.75, -19.73, 0.10, 18.79, 18.32 +MOT, 1388, 1489, 1396, 1455 +GPS, 3, 109238200, 1774, 9, 2.42, -39.4944434, 176.7486085, 12.28, 56.88, 9.43, 13.86, -0.320000, 91173 +CTUN, 513, 0.00, 12.24, 0.000000, 0.00, 15, 55, 411, 0 +ATT, 0.00, -0.08, -22.75, -19.35, 0.00, 18.74, 18.32 +MOT, 1365, 1513, 1404, 1444 +CTUN, 513, 0.00, 12.52, 0.000000, 0.00, 15, 58, 411, 0 +ATT, 0.00, -0.05, -22.82, -19.12, 0.10, 18.65, 18.32 +MOT, 1359, 1521, 1355, 1488 +GPS, 3, 109238400, 1774, 9, 2.42, -39.4944268, 176.7486139, 12.41, 56.99, 9.47, 14.04, -0.370000, 91374 +CTUN, 513, 0.00, 12.74, 0.000000, 0.00, 15, 61, 411, 0 +ATT, 0.00, 0.02, -22.75, -18.97, 0.00, 18.59, 18.32 +MOT, 1419, 1453, 1416, 1435 +CTUN, 513, 0.00, 12.59, 0.000000, 0.00, 14, 68, 410, 0 +ATT, 0.00, 0.24, -22.75, -18.48, 0.10, 18.55, 18.32 +MOT, 1391, 1479, 1374, 1475 +GPS, 3, 109238600, 1774, 9, 2.42, -39.4944101, 176.7486192, 12.58, 57.13, 9.48, 13.84, -0.460000, 91574 +CTUN, 513, 0.00, 12.62, 0.000000, 0.00, 13, 75, 409, 0 +ATT, 0.00, 0.27, -22.75, -18.13, 0.00, 18.52, 18.32 +MOT, 1379, 1495, 1370, 1471 +CTUN, 513, 0.00, 12.72, 0.000000, 0.00, 13, 83, 409, 0 +ATT, 0.00, 0.20, -22.75, -17.95, 0.00, 18.48, 18.32 +MOT, 1382, 1494, 1381, 1457 +GPS, 3, 109238800, 1774, 9, 2.42, -39.4943935, 176.7486244, 12.76, 57.26, 9.44, 13.73, -0.500000, 91774 +CTUN, 513, 0.00, 13.07, 0.000000, 0.00, 14, 86, 410, 0 +ATT, 0.00, 0.22, -22.75, -18.31, 0.10, 18.56, 18.32 +MOT, 1384, 1481, 1403, 1450 +CTUN, 513, 0.00, 13.03, 0.000000, 0.00, 14, 83, 410, 0 +ATT, 0.00, 0.19, -22.75, -18.36, 0.00, 18.73, 18.32 +MOT, 1411, 1440, 1421, 1446 +DU32, 7, 270713 +CURR, 411, 72155, 1574, 2371, 4940, 109.8004 +GPS, 3, 109239000, 1774, 9, 2.42, -39.4943768, 176.7486297, 12.97, 57.43, 9.45, 13.90, -0.580000, 91974 +CTUN, 513, 0.00, 13.17, 0.000000, 0.00, 15, 75, 411, 0 +ATT, 0.00, -0.05, -22.75, -19.00, 0.00, 18.94, 18.32 +MOT, 1357, 1504, 1400, 1461 +CTUN, 513, 0.00, 13.05, 0.000000, 0.00, 16, 70, 412, 0 +ATT, 0.00, -0.07, -22.75, -19.46, 0.00, 19.00, 18.32 +MOT, 1402, 1468, 1373, 1480 +GPS, 3, 109239200, 1774, 9, 2.42, -39.4943603, 176.7486348, 13.14, 57.61, 9.38, 13.54, -0.660000, 92175 +CTUN, 513, 0.00, 13.13, 0.000000, 0.00, 15, 72, 411, 0 +ATT, 0.00, -0.02, -22.75, -19.19, 0.10, 19.00, 18.32 +MOT, 1391, 1471, 1368, 1494 +CTUN, 513, 0.00, 13.20, 0.000000, 0.00, 15, 77, 411, 0 +ATT, 0.00, 0.02, -22.75, -18.86, 0.00, 18.92, 18.32 +MOT, 1413, 1455, 1378, 1477 +GPS, 3, 109239400, 1774, 9, 2.42, -39.4943439, 176.7486399, 13.30, 57.75, 9.30, 13.72, -0.570000, 92375 +CTUN, 516, 0.00, 13.47, 0.000000, 0.00, 14, 86, 413, 0 +ATT, 0.00, 0.30, -22.75, -18.28, 0.10, 18.71, 18.32 +MOT, 1358, 1528, 1388, 1457 +CTUN, 518, 0.00, 13.50, 0.000000, 0.00, 14, 96, 416, 0 +ATT, 0.00, -0.05, -22.75, -18.04, 0.00, 18.48, 18.32 +MOT, 1385, 1512, 1383, 1463 +GPS, 3, 109239600, 1774, 9, 2.42, -39.4943275, 176.7486450, 13.52, 57.92, 9.29, 13.71, -0.630000, 92575 +CTUN, 518, 0.00, 13.62, 0.000000, 0.00, 13, 109, 415, 0 +ATT, 0.00, -0.22, -22.75, -17.46, 0.10, 18.42, 18.32 +MOT, 1401, 1485, 1392, 1461 +CTUN, 518, 0.00, 13.57, 0.000000, 0.00, 13, 123, 415, 0 +ATT, 0.00, -0.15, -22.75, -17.48, 0.20, 18.39, 18.32 +MOT, 1371, 1508, 1362, 1499 +GPS, 3, 109239800, 1774, 9, 2.42, -39.4943111, 176.7486502, 13.78, 58.12, 9.34, 13.75, -0.810000, 92775 +CTUN, 518, 0.00, 13.88, 0.000000, 0.00, 12, 132, 414, 0 +ATT, 0.00, -0.27, -22.75, -17.10, 0.10, 18.46, 18.32 +MOT, 1378, 1506, 1390, 1461 +CTUN, 518, 0.00, 14.11, 0.000000, 0.00, 13, 136, 415, 0 +ATT, 0.00, -0.35, -22.82, -17.40, 0.00, 18.45, 18.32 +MOT, 1381, 1508, 1376, 1475 +DU32, 7, 270713 +CURR, 419, 76290, 1595, 2482, 4962, 116.7737 +GPS, 3, 109240000, 1774, 9, 2.42, -39.4942946, 176.7486554, 14.08, 58.37, 9.38, 13.59, -1.020000, 92976 +CTUN, 526, 0.00, 14.09, 0.000000, 0.00, 13, 143, 425, 0 +ATT, 0.00, -0.55, -22.75, -17.16, 0.00, 18.47, 18.32 +MOT, 1390, 1516, 1399, 1477 +CTUN, 526, 0.00, 14.38, 0.000000, 0.00, 13, 157, 425, 0 +ATT, 0.00, -0.69, -22.96, -17.21, 0.00, 18.43, 18.32 +MOT, 1416, 1481, 1404, 1480 +GPS, 3, 109240200, 1774, 9, 2.42, -39.4942783, 176.7486605, 14.42, 58.65, 9.27, 13.86, -1.160000, 93176 +CTUN, 526, 0.00, 14.40, 0.000000, 0.00, 13, 173, 425, 0 +ATT, 0.00, -0.69, -22.75, -17.23, 0.10, 18.34, 18.32 +MOT, 1401, 1517, 1382, 1481 +CTUN, 526, 0.00, 14.73, 0.000000, 0.00, 13, 184, 425, 0 +ATT, 0.00, -0.49, -22.96, -17.47, 0.10, 18.23, 18.32 +MOT, 1403, 1513, 1374, 1492 +GPS, 3, 109240400, 1774, 9, 2.42, -39.4942620, 176.7486655, 14.82, 58.97, 9.25, 13.56, -1.370000, 93376 +CTUN, 526, 0.00, 14.70, 0.000000, 0.00, 14, 192, 426, 0 +ATT, 0.00, 0.02, -22.96, -17.82, 0.00, 18.14, 18.32 +MOT, 1396, 1516, 1411, 1463 +CTUN, 527, 0.00, 14.98, 0.000000, 0.00, 14, 200, 427, 0 +ATT, 0.00, -0.34, -23.03, -17.93, 0.00, 18.14, 18.32 +MOT, 1416, 1500, 1395, 1479 +GPS, 3, 109240600, 1774, 9, 2.42, -39.4942457, 176.7486703, 15.23, 59.35, 9.25, 13.04, -1.590000, 93576 +CTUN, 526, 0.00, 15.07, 0.000000, 0.00, 14, 211, 426, 0 +ATT, 0.00, -0.26, -22.96, -17.98, 0.10, 18.31, 18.32 +MOT, 1397, 1504, 1414, 1471 +CTUN, 526, 0.00, 15.47, 0.000000, 0.00, 14, 220, 426, 0 +ATT, 0.00, -0.32, -22.96, -18.16, 0.10, 18.40, 18.32 +MOT, 1380, 1528, 1397, 1481 +GPS, 3, 109240800, 1774, 9, 2.42, -39.4942293, 176.7486750, 15.69, 59.74, 9.27, 12.79, -1.750000, 93777 +CTUN, 526, 0.00, 15.49, 0.000000, 0.00, 15, 228, 427, 0 +ATT, 0.00, -0.32, -22.96, -18.56, 0.00, 18.49, 18.32 +MOT, 1445, 1460, 1405, 1479 +CTUN, 524, 0.00, 15.91, 0.000000, 0.00, 16, 226, 425, 0 +ATT, 0.00, -0.27, -22.75, -19.20, 0.00, 18.52, 18.32 +MOT, 1392, 1512, 1438, 1440 +DU32, 7, 270713 +CURR, 429, 80540, 1606, 2708, 4940, 124.2455 +PM, 0, 0, 0, 1000, 10322, 0, 0, 0, 0 +GPS, 3, 109241000, 1774, 9, 2.42, -39.4942128, 176.7486797, 16.16, 60.18, 9.30, 12.80, -1.940000, 93977 +CTUN, 526, 0.00, 16.18, 0.000000, 0.00, 17, 224, 429, 0 +ATT, 0.00, -0.18, -23.03, -19.78, 0.00, 18.35, 18.32 +MOT, 1418, 1504, 1399, 1481 +CTUN, 526, 0.00, 16.10, 0.000000, 0.00, 18, 219, 430, 0 +ATT, 0.00, 0.05, -23.18, -20.42, 0.00, 18.20, 18.32 +MOT, 1405, 1519, 1399, 1483 +GPS, 3, 109241200, 1774, 9, 2.42, -39.4941962, 176.7486844, 16.62, 60.65, 9.35, 12.47, -1.990000, 94177 +CTUN, 526, 0.00, 16.41, 0.000000, 0.00, 19, 216, 431, 0 +ATT, 0.00, -0.11, -23.62, -20.95, 0.10, 18.13, 18.32 +MOT, 1401, 1531, 1432, 1446 +CTUN, 526, 0.00, 16.73, 0.000000, 0.00, 21, 212, 433, 0 +ATT, 0.00, -0.27, -24.27, -21.58, 0.10, 18.04, 18.32 +MOT, 1450, 1490, 1417, 1463 +GPS, 3, 109241400, 1774, 9, 2.42, -39.4941797, 176.7486888, 17.06, 61.05, 9.32, 12.10, -1.970000, 94378 +CTUN, 526, 0.00, 16.96, 0.000000, 0.00, 22, 208, 434, 0 +ATT, 0.00, -0.42, -24.05, -21.97, 0.00, 18.03, 18.32 +MOT, 1421, 1516, 1407, 1480 +CTUN, 526, 0.00, 17.30, 0.000000, 0.00, 22, 206, 434, 0 +ATT, 0.00, -0.32, -23.83, -22.32, 0.10, 18.05, 18.32 +MOT, 1394, 1533, 1396, 1499 +GPS, 3, 109241600, 1774, 9, 2.42, -39.4941628, 176.7486933, 17.50, 61.49, 9.49, 11.70, -1.940000, 94578 +CTUN, 526, 0.00, 17.42, 0.000000, 0.00, 22, 209, 434, 0 +ATT, 0.00, -0.26, -23.62, -22.28, 0.10, 18.03, 18.32 +MOT, 1449, 1486, 1444, 1444 +CTUN, 526, 0.00, 17.60, 0.000000, 0.00, 24, 205, 436, 0 +ATT, 0.00, -0.33, -23.83, -22.91, 0.00, 17.88, 18.32 +MOT, 1451, 1495, 1404, 1482 +GPS, 3, 109241800, 1774, 9, 2.42, -39.4941457, 176.7486976, 17.93, 61.90, 9.60, 11.04, -1.920000, 94778 +CTUN, 526, 0.00, 17.76, 0.000000, 0.00, 25, 198, 437, 0 +ATT, 0.00, -0.14, -23.62, -23.39, 0.10, 17.75, 18.32 +MOT, 1411, 1538, 1422, 1462 +CTUN, 526, 0.00, 17.88, 0.000000, 0.00, 25, 194, 437, 0 +ATT, 0.00, -0.01, -23.62, -23.42, 0.00, 17.75, 18.32 +MOT, 1428, 1518, 1419, 1472 +DU32, 7, 270713 +CURR, 437, 84870, 1594, 2832, 4962, 131.9923 +GPS, 3, 109242000, 1774, 9, 2.42, -39.4941283, 176.7487018, 18.33, 62.32, 9.76, 10.69, -1.940000, 94980 +CTUN, 526, 0.00, 18.39, 0.000000, 0.00, 25, 189, 437, 0 +ATT, 0.00, 0.05, -23.40, -23.45, 0.10, 17.87, 18.32 +MOT, 1441, 1500, 1418, 1477 +CTUN, 526, 0.00, 18.43, 0.000000, 0.00, 24, 186, 436, 0 +ATT, 0.00, 0.21, -23.40, -23.14, 0.10, 17.96, 18.32 +MOT, 1398, 1537, 1432, 1463 +GPS, 3, 109242200, 1774, 9, 2.42, -39.4941107, 176.7487057, 18.73, 62.71, 9.84, 9.86, -1.840000, 95178 +CTUN, 526, 0.00, 18.69, 0.000000, 0.00, 25, 179, 437, 0 +ATT, 0.00, 0.08, -23.18, -23.38, 0.00, 18.03, 18.32 +MOT, 1440, 1497, 1443, 1456 +CTUN, 527, 0.00, 18.79, 0.000000, 0.00, 25, 167, 438, 0 +ATT, 0.00, 0.24, -23.18, -23.34, 0.10, 18.02, 18.32 +MOT, 1416, 1529, 1405, 1490 +GPS, 3, 109242400, 1774, 9, 2.42, -39.4940928, 176.7487094, 19.09, 63.10, 9.97, 9.24, -1.780000, 95379 +CTUN, 526, 0.00, 19.13, 0.000000, 0.00, 24, 162, 436, 0 +ATT, 0.00, 0.38, -23.18, -23.21, 0.10, 17.98, 18.32 +MOT, 1409, 1537, 1403, 1481 +CTUN, 526, 0.00, 19.25, 0.000000, 0.00, 22, 169, 434, 0 +ATT, 0.00, 0.19, -23.18, -22.22, 0.10, 17.99, 18.32 +MOT, 1417, 1522, 1383, 1501 +GPS, 3, 109242600, 1774, 9, 2.42, -39.4940749, 176.7487128, 19.45, 63.43, 10.03, 8.46, -1.650000, 95580 +CTUN, 526, 0.00, 19.51, 0.000000, 0.00, 20, 182, 432, 0 +ATT, 0.00, 0.38, -23.18, -21.17, 0.00, 18.01, 18.32 +MOT, 1403, 1528, 1415, 1470 +CTUN, 526, 0.00, 19.70, 0.000000, 0.00, 18, 192, 430, 0 +ATT, 0.00, 0.27, -23.18, -20.16, 0.00, 18.18, 18.32 +MOT, 1389, 1534, 1405, 1477 +GPS, 3, 109242800, 1774, 9, 2.42, -39.4940568, 176.7487161, 19.86, 63.76, 10.16, 8.16, -1.690000, 95780 +CTUN, 526, 0.00, 19.88, 0.000000, 0.00, 17, 196, 429, 0 +ATT, 0.00, 0.42, -23.18, -19.88, 0.20, 18.29, 18.32 +MOT, 1413, 1501, 1414, 1475 +CTUN, 526, 0.00, 20.02, 0.000000, 0.00, 17, 196, 429, 0 +ATT, 0.00, 0.46, -22.96, -19.72, 0.10, 18.33, 18.32 +MOT, 1419, 1499, 1420, 1464 +DU32, 7, 270713 +CURR, 429, 89211, 1588, 2721, 4940, 139.7294 +GPS, 3, 109243000, 1774, 9, 2.42, -39.4940384, 176.7487196, 20.28, 64.18, 10.25, 8.25, -1.840000, 95980 +CTUN, 526, 0.00, 20.26, 0.000000, 0.00, 17, 195, 429, 0 +ATT, 0.00, 0.59, -22.96, -19.85, 0.10, 18.37, 18.32 +MOT, 1408, 1506, 1405, 1483 +CTUN, 527, 0.00, 20.43, 0.000000, 0.00, 18, 191, 431, 0 +ATT, 0.00, 0.73, -23.03, -20.32, 0.10, 18.43, 18.32 +MOT, 1429, 1494, 1417, 1472 +GPS, 3, 109243200, 1774, 9, 2.42, -39.4940202, 176.7487230, 20.69, 64.59, 10.16, 8.31, -1.850000, 96181 +CTUN, 526, 0.00, 20.36, 0.000000, 0.00, 19, 185, 431, 0 +ATT, 0.00, 0.57, -23.25, -20.53, 0.00, 18.54, 18.32 +MOT, 1421, 1497, 1424, 1469 +CTUN, 526, 0.00, 20.63, 0.000000, 0.00, 20, 177, 432, 0 +ATT, 0.00, 0.61, -22.96, -20.96, 0.10, 18.57, 18.32 +MOT, 1392, 1532, 1392, 1499 +GPS, 3, 109243400, 1774, 9, 2.42, -39.4940021, 176.7487264, 21.04, 64.96, 10.12, 8.39, -1.780000, 96381 +CTUN, 526, 0.00, 20.81, 0.000000, 0.00, 20, 177, 432, 0 +ATT, 0.00, 0.48, -23.03, -20.98, 0.10, 18.53, 18.32 +MOT, 1398, 1524, 1408, 1485 +CTUN, 524, 0.00, 21.49, 0.000000, 0.00, 20, 173, 429, 0 +ATT, 0.00, 0.40, -22.96, -21.18, 0.10, 18.45, 18.32 +MOT, 1385, 1535, 1393, 1488 +GPS, 3, 109243600, 1774, 9, 2.42, -39.4939842, 176.7487298, 21.42, 65.30, 10.07, 8.24, -1.710000, 96581 +CTUN, 526, 0.00, 21.09, 0.000000, 0.00, 20, 169, 432, 0 +ATT, 0.00, 0.26, -22.96, -21.21, 0.00, 18.51, 18.32 +MOT, 1420, 1504, 1400, 1491 +CTUN, 524, 0.00, 21.59, 0.000000, 0.00, 19, 172, 428, 0 +ATT, 0.00, -0.10, -22.96, -20.87, 0.20, 18.66, 18.32 +MOT, 1400, 1503, 1408, 1483 +GPS, 3, 109243800, 1774, 9, 2.42, -39.4939663, 176.7487330, 21.77, 65.64, 10.01, 7.93, -1.650000, 96782 +CTUN, 526, 0.00, 21.94, 0.000000, 0.00, 19, 173, 431, 0 +ATT, 0.00, -0.27, -22.96, -20.75, 0.00, 18.76, 18.32 +MOT, 1425, 1491, 1415, 1480 +CTUN, 527, 0.00, 21.85, 0.000000, 0.00, 19, 166, 432, 0 +ATT, 0.00, 0.14, -22.96, -20.64, 0.00, 18.68, 18.32 +MOT, 1425, 1503, 1405, 1481 +DU32, 7, 270713 +CURR, 431, 93516, 1586, 2725, 4897, 147.3127 +GPS, 3, 109244000, 1774, 9, 2.42, -39.4939486, 176.7487359, 22.14, 65.97, 9.91, 7.42, -1.620000, 96982 +CTUN, 526, 0.00, 21.77, 0.000000, 0.00, 20, 163, 432, 0 +ATT, 0.00, 0.09, -23.18, -21.08, 0.00, 18.57, 18.32 +MOT, 1453, 1474, 1402, 1486 +CTUN, 526, 0.00, 21.98, 0.000000, 0.00, 20, 154, 432, 0 +ATT, 0.00, 0.20, -23.18, -21.46, 0.20, 18.42, 18.32 +MOT, 1398, 1533, 1445, 1437 +GPS, 3, 109244200, 1774, 9, 2.42, -39.4939310, 176.7487388, 22.44, 66.30, 9.86, 7.18, -1.560000, 97182 +CTUN, 526, 0.00, 22.10, 0.000000, 0.00, 21, 147, 433, 0 +ATT, 0.00, 0.13, -23.18, -21.93, 0.20, 18.33, 18.32 +MOT, 1429, 1500, 1413, 1478 +CTUN, 526, 0.00, 22.57, 0.000000, 0.00, 22, 142, 434, 0 +ATT, 0.00, -0.13, -23.18, -22.16, 0.00, 18.13, 18.32 +MOT, 1449, 1493, 1445, 1437 +GPS, 3, 109244400, 1774, 9, 2.42, -39.4939134, 176.7487416, 22.72, 66.61, 9.84, 6.79, -1.500000, 97383 +CTUN, 526, 0.00, 22.39, 0.000000, 0.00, 23, 131, 435, 0 +ATT, 0.00, -0.47, -23.40, -22.75, 0.00, 17.98, 18.32 +MOT, 1412, 1528, 1403, 1485 +CTUN, 526, 0.00, 22.80, 0.000000, 0.00, 23, 125, 435, 0 +ATT, 0.00, -0.54, -23.40, -22.36, 0.10, 17.99, 18.32 +MOT, 1382, 1552, 1419, 1468 +GPS, 3, 109244600, 1774, 9, 2.42, -39.4938956, 176.7487439, 22.97, 66.89, 9.91, 5.89, -1.390000, 97582 +CTUN, 524, 0.00, 23.26, 0.000000, 0.00, 22, 130, 431, 0 +ATT, 0.00, -0.71, -23.18, -22.12, 0.10, 18.03, 18.32 +MOT, 1414, 1513, 1425, 1459 +CTUN, 526, 0.00, 23.33, 0.000000, 0.00, 22, 132, 434, 0 +ATT, 0.00, -0.69, -23.18, -22.10, 0.00, 18.27, 18.32 +MOT, 1400, 1520, 1442, 1461 +GPS, 3, 109244800, 1774, 9, 2.42, -39.4938778, 176.7487460, 23.28, 67.13, 9.97, 5.01, -1.320000, 97783 +CTUN, 526, 0.00, 23.47, 0.000000, 0.00, 22, 129, 434, 0 +ATT, 0.00, -0.81, -23.18, -22.15, 0.00, 18.53, 18.32 +MOT, 1412, 1506, 1419, 1486 +CTUN, 524, 0.00, 23.58, 0.000000, 0.00, 20, 126, 429, 0 +ATT, 0.00, -0.48, -23.18, -21.40, 0.10, 18.62, 18.32 +MOT, 1420, 1502, 1442, 1438 +DU32, 7, 270713 +CURR, 435, 97842, 1613, 2793, 4876, 155.0120 +GPS, 3, 109245000, 1774, 9, 2.42, -39.4938601, 176.7487477, 23.57, 67.35, 9.94, 4.28, -1.280000, 97983 +CTUN, 526, 0.00, 23.72, 0.000000, 0.00, 25, 100, 437, 0 +ATT, 0.00, -0.25, -23.40, -23.80, 0.00, 18.41, 18.32 +MOT, 1390, 1545, 1391, 1506 +CTUN, 526, 0.00, 23.45, 0.000000, 0.00, 26, 76, 438, 0 +ATT, 0.00, 0.03, -23.62, -24.14, 0.00, 18.30, 18.32 +MOT, 1422, 1521, 1449, 1449 +GPS, 3, 109245200, 1774, 9, 2.42, -39.4938424, 176.7487493, 23.75, 67.60, 9.88, 3.92, -1.210000, 98183 +CTUN, 526, 0.00, 23.60, 0.000000, 0.00, 28, 60, 440, 0 +ATT, 0.00, 0.25, -23.62, -24.68, 0.20, 18.18, 18.32 +MOT, 1430, 1516, 1424, 1479 +CTUN, 526, 0.00, 23.57, 0.000000, 0.00, 27, 46, 439, 0 +ATT, 0.00, 0.41, -23.62, -24.46, 0.00, 18.20, 18.32 +MOT, 1469, 1473, 1421, 1482 +GPS, 3, 109245400, 1774, 9, 2.42, -39.4938251, 176.7487506, 23.84, 67.71, 9.72, 3.31, -0.850000, 98383 +CTUN, 526, 0.00, 23.50, 0.000000, 0.00, 27, 37, 439, 0 +ATT, 0.00, 0.84, -23.62, -24.16, 0.00, 18.30, 18.32 +MOT, 1411, 1530, 1431, 1473 +CTUN, 524, 0.00, 23.78, 0.000000, 0.00, 25, 30, 434, 0 +ATT, 0.00, 0.94, -23.83, -23.44, 0.10, 18.31, 18.32 +MOT, 1441, 1496, 1409, 1478 +GPS, 3, 109245600, 1774, 9, 2.42, -39.4938078, 176.7487515, 23.88, 67.80, 9.66, 2.50, -0.610000, 98584 +CTUN, 526, 0.00, 24.01, 0.000000, 0.00, 23, 36, 435, 0 +ATT, 0.00, 0.85, -24.05, -22.41, 0.10, 18.34, 18.32 +MOT, 1421, 1508, 1401, 1498 +CTUN, 524, 0.00, 23.77, 0.000000, 0.00, 20, 48, 429, 0 +ATT, 0.00, 0.28, -24.27, -21.20, 0.00, 18.51, 18.32 +MOT, 1419, 1486, 1404, 1493 +GPS, 3, 109245800, 1774, 9, 2.42, -39.4937906, 176.7487524, 23.98, 67.86, 9.62, 2.24, -0.490000, 98784 +CTUN, 526, 0.00, 23.80, 0.000000, 0.00, 19, 61, 431, 0 +ATT, 0.00, 0.08, -24.56, -20.61, 0.00, 18.58, 18.32 +MOT, 1388, 1528, 1400, 1495 +CTUN, 526, 0.00, 24.13, 0.000000, 0.00, 18, 72, 430, 0 +ATT, 0.00, -0.19, -24.49, -20.14, 0.20, 18.54, 18.32 +MOT, 1445, 1475, 1418, 1469 +DU32, 7, 270713 +CURR, 430, 102201, 1572, 2820, 5006, 162.7852 +GPS, 3, 109246000, 1774, 9, 2.42, -39.4937735, 176.7487534, 24.12, 67.95, 9.57, 2.59, -0.560000, 98984 +CTUN, 526, 0.00, 23.77, 0.000000, 0.00, 17, 78, 429, 0 +ATT, 0.00, -0.04, -24.27, -19.74, 0.10, 18.44, 18.32 +MOT, 1415, 1512, 1382, 1494 +CTUN, 526, 0.00, 23.85, 0.000000, 0.00, 17, 90, 429, 0 +ATT, 0.00, -0.12, -24.12, -19.61, 0.10, 18.10, 18.32 +MOT, 1429, 1509, 1379, 1486 +GPS, 3, 109246200, 1774, 9, 2.42, -39.4937564, 176.7487545, 24.26, 68.12, 9.56, 2.54, -0.700000, 99185 +CTUN, 526, 0.00, 24.11, 0.000000, 0.00, 17, 98, 429, 0 +ATT, 0.00, 0.30, -24.27, -19.59, 1.97, 17.99, 18.68 +MOT, 1444, 1508, 1413, 1438 +CTUN, 524, 0.00, 24.02, 0.000000, 0.00, 17, 103, 426, 0 +ATT, 0.00, 0.52, -24.49, -20.01, 3.53, 18.27, 19.44 +MOT, 1428, 1530, 1345, 1482 +GPS, 3, 109246400, 1774, 9, 2.42, -39.4937394, 176.7487557, 24.45, 68.29, 9.49, 3.12, -0.840000, 99385 +CTUN, 526, 0.00, 24.30, 0.000000, 0.00, 18, 106, 430, 0 +ATT, 0.00, 0.94, -24.27, -20.26, 2.70, 19.05, 20.28 +MOT, 1397, 1544, 1380, 1481 +CTUN, 526, 0.00, 24.45, 0.000000, 0.00, 18, 111, 430, 0 +ATT, 0.00, 1.09, -24.05, -20.09, 2.59, 19.82, 20.98 +MOT, 1443, 1500, 1399, 1464 +GPS, 3, 109246600, 1774, 9, 2.42, -39.4937224, 176.7487571, 24.67, 68.49, 9.46, 3.50, -0.900000, 99585 +CTUN, 526, 0.00, 24.55, 0.000000, 0.00, 18, 119, 430, 0 +ATT, 0.00, 1.21, -24.05, -19.94, 2.39, 20.54, 21.73 +MOT, 1422, 1519, 1403, 1462 +CTUN, 526, 0.00, 24.77, 0.000000, 0.00, 18, 123, 430, 0 +ATT, 0.00, 1.35, -24.05, -19.94, 0.41, 21.17, 22.12 +MOT, 1418, 1504, 1379, 1505 +GPS, 3, 109246800, 1774, 9, 2.42, -39.4937056, 176.7487587, 24.93, 68.71, 9.36, 4.34, -0.950000, 99786 +CTUN, 526, 0.00, 24.78, 0.000000, 0.00, 18, 127, 430, 0 +ATT, 0.00, 1.28, -24.05, -20.05, 0.41, 21.45, 22.20 +MOT, 1410, 1525, 1405, 1466 +CTUN, 526, 0.00, 24.97, 0.000000, 0.00, 18, 127, 430, 0 +ATT, 0.00, 1.50, -24.05, -20.12, 1.03, 21.58, 22.34 +MOT, 1398, 1543, 1398, 1463 +DU32, 7, 270713 +CURR, 430, 106496, 1587, 2709, 4962, 170.4330 +GPS, 3, 109247000, 1774, 9, 2.42, -39.4936890, 176.7487606, 25.19, 68.95, 9.24, 4.92, -1.000000, 99986 +CTUN, 527, 0.00, 24.82, 0.000000, 0.00, 18, 130, 431, 0 +ATT, 0.00, 1.43, -24.12, -20.07, 0.72, 21.79, 22.58 +MOT, 1430, 1510, 1387, 1485 +CTUN, 524, 0.00, 25.06, 0.000000, 0.00, 18, 133, 427, 0 +ATT, 0.00, 1.31, -24.05, -20.01, 0.72, 21.96, 22.78 +MOT, 1392, 1541, 1411, 1442 +GPS, 3, 109247200, 1774, 9, 2.42, -39.4936724, 176.7487630, 25.44, 69.22, 9.18, 6.22, -1.090000, 100186 +CTUN, 526, 0.00, 25.16, 0.000000, 0.00, 18, 130, 430, 0 +ATT, 0.00, 0.59, -23.83, -20.25, 0.83, 22.16, 22.98 +MOT, 1429, 1513, 1365, 1500 +CTUN, 526, 0.00, 25.36, 0.000000, 0.00, 17, 131, 429, 0 +ATT, 0.00, 0.84, -23.83, -19.83, 0.72, 22.45, 23.18 +MOT, 1414, 1525, 1389, 1475 +GPS, 3, 109247400, 1774, 9, 2.42, -39.4936561, 176.7487655, 25.69, 69.50, 9.06, 6.62, -1.160000, 100386 +CTUN, 526, 0.00, 25.44, 0.000000, 0.00, 17, 146, 429, 0 +ATT, 0.00, 0.75, -23.83, -19.52, 0.72, 22.58, 23.38 +MOT, 1388, 1546, 1379, 1484 +CTUN, 526, 0.00, 25.58, 0.000000, 0.00, 16, 163, 428, 0 +ATT, 0.00, 0.51, -23.83, -19.09, 0.72, 22.75, 23.58 +MOT, 1392, 1538, 1388, 1474 +GPS, 3, 109247600, 1774, 9, 2.42, -39.4936400, 176.7487684, 26.01, 69.75, 9.00, 7.81, -1.190000, 100587 +CTUN, 526, 0.00, 25.65, 0.000000, 0.00, 15, 179, 427, 0 +ATT, 0.00, 0.43, -23.83, -18.66, 0.51, 22.88, 23.77 +MOT, 1434, 1501, 1379, 1476 +CTUN, 526, 0.00, 25.80, 0.000000, 0.00, 15, 193, 427, 0 +ATT, 0.00, 0.40, -23.83, -18.38, 0.10, 23.00, 23.83 +MOT, 1409, 1520, 1394, 1468 +GPS, 3, 109247800, 1774, 9, 2.42, -39.4936239, 176.7487714, 26.37, 70.07, 9.04, 8.03, -1.420000, 100787 +CTUN, 526, 0.00, 26.03, 0.000000, 0.00, 15, 199, 427, 0 +ATT, 0.00, 0.37, -23.90, -18.62, 0.20, 22.99, 23.83 +MOT, 1360, 1563, 1373, 1484 +CTUN, 526, 0.00, 26.11, 0.000000, 0.00, 15, 203, 427, 0 +ATT, 0.00, 0.20, -23.83, -18.50, 0.20, 23.14, 23.83 +MOT, 1421, 1508, 1405, 1456 +DU32, 7, 270713 +CURR, 428, 110779, 1552, 2674, 4940, 177.9816 +GPS, 3, 109248000, 1774, 9, 2.42, -39.4936078, 176.7487747, 26.76, 70.45, 9.00, 8.89, -1.650000, 100988 +CTUN, 526, 0.00, 26.69, 0.000000, 0.00, 17, 196, 429, 0 +ATT, 0.00, 0.47, -23.83, -19.57, 0.10, 23.32, 23.83 +MOT, 1418, 1502, 1419, 1463 +CTUN, 537, 0.00, 26.69, 0.000000, 0.00, 19, 180, 444, 0 +ATT, 0.00, 0.22, -23.83, -20.51, 0.10, 23.55, 23.83 +MOT, 1451, 1505, 1440, 1470 +GPS, 3, 109248200, 1774, 9, 2.42, -39.4935917, 176.7487781, 27.13, 70.85, 8.96, 9.09, -1.770000, 101187 +CTUN, 537, 0.00, 26.86, 0.000000, 0.00, 22, 167, 447, 0 +ATT, 0.00, 0.13, -23.83, -21.73, 0.10, 23.73, 23.83 +MOT, 1413, 1540, 1442, 1480 +CTUN, 534, 0.00, 27.18, 0.000000, 0.00, 23, 159, 445, 0 +ATT, 0.00, -0.29, -24.27, -22.33, 0.10, 23.86, 23.83 +MOT, 1434, 1518, 1438, 1480 +GPS, 3, 109248400, 1774, 9, 2.42, -39.4935759, 176.7487814, 27.45, 71.18, 8.91, 9.35, -1.610000, 101388 +CTUN, 535, 0.00, 27.12, 0.000000, 0.00, 25, 146, 448, 0 +ATT, 0.00, -0.82, -24.12, -23.22, 0.10, 23.92, 23.83 +MOT, 1440, 1524, 1432, 1486 +CTUN, 534, 0.00, 27.33, 0.000000, 0.00, 26, 138, 448, 0 +ATT, 0.00, -1.02, -24.27, -23.65, 0.00, 23.94, 23.83 +MOT, 1428, 1532, 1445, 1477 +GPS, 3, 109248600, 1774, 9, 2.42, -39.4935599, 176.7487846, 27.72, 71.48, 8.92, 8.93, -1.450000, 101588 +CTUN, 534, 0.00, 27.44, 0.000000, 0.00, 27, 133, 449, 0 +ATT, 0.00, -1.22, -24.27, -24.12, 0.00, 23.92, 23.83 +MOT, 1423, 1540, 1450, 1471 +CTUN, 534, 0.00, 27.31, 0.000000, 0.00, 28, 127, 450, 0 +ATT, 0.00, -1.44, -24.27, -24.52, 0.00, 23.82, 23.83 +MOT, 1427, 1539, 1442, 1480 +GPS, 3, 109248800, 1774, 9, 2.42, -39.4935437, 176.7487878, 27.96, 71.76, 9.04, 8.50, -1.340000, 101788 +CTUN, 534, 0.00, 27.68, 0.000000, 0.00, 29, 120, 451, 0 +ATT, 0.00, -1.36, -24.05, -24.60, 0.00, 23.76, 23.83 +MOT, 1446, 1532, 1419, 1497 +CTUN, 534, 0.00, 28.32, 0.000000, 0.00, 29, 113, 451, 0 +ATT, 0.00, -1.02, -24.05, -24.55, 0.00, 23.63, 23.83 +MOT, 1462, 1517, 1419, 1497 +DU32, 7, 270713 +CURR, 452, 115236, 1549, 2955, 4897, 186.0750 +GPS, 3, 109249000, 1774, 9, 2.42, -39.4935274, 176.7487907, 28.20, 72.01, 9.17, 7.84, -1.250000, 101988 +CTUN, 534, 0.00, 28.38, 0.000000, 0.00, 28, 108, 450, 0 +ATT, 0.00, -0.64, -24.05, -24.44, 0.00, 23.53, 23.83 +MOT, 1435, 1537, 1421, 1495 +CTUN, 534, 0.00, 28.40, 0.000000, 0.00, 28, 103, 450, 0 +ATT, 0.00, -0.35, -23.83, -24.44, 0.10, 23.47, 23.83 +MOT, 1466, 1506, 1432, 1486 +GPS, 3, 109249200, 1774, 9, 2.42, -39.4935108, 176.7487937, 28.44, 72.25, 9.27, 7.85, -1.190000, 102189 +CTUN, 534, 0.00, 28.68, 0.000000, 0.00, 28, 98, 450, 0 +ATT, 0.00, -0.18, -23.62, -24.30, 0.00, 23.47, 23.83 +MOT, 1501, 1472, 1401, 1517 +CTUN, 534, 0.00, 28.79, 0.000000, 0.00, 27, 96, 449, 0 +ATT, 0.00, 0.15, -23.18, -23.90, 0.10, 23.45, 23.83 +MOT, 1436, 1532, 1412, 1506 +GPS, 3, 109249400, 1774, 9, 2.42, -39.4934941, 176.7487968, 28.67, 72.45, 9.37, 8.00, -1.060000, 102389 +CTUN, 537, 0.00, 28.49, 0.000000, 0.00, 26, 100, 451, 0 +ATT, 0.00, 0.36, -24.05, -23.33, 0.00, 23.50, 23.83 +MOT, 1464, 1509, 1409, 1514 +CTUN, 537, 0.00, 28.89, 0.000000, 0.00, 26, 101, 451, 0 +ATT, 0.00, 0.59, -24.34, -23.29, 0.00, 23.44, 23.83 +MOT, 1446, 1530, 1396, 1522 +GPS, 3, 109249600, 1774, 9, 2.42, -39.4934772, 176.7487999, 28.89, 72.65, 9.45, 8.15, -0.970000, 102589 +CTUN, 537, 0.00, 29.09, 0.000000, 0.00, 25, 99, 450, 0 +ATT, 0.00, 0.68, -24.27, -23.04, 0.10, 23.43, 23.83 +MOT, 1443, 1529, 1415, 1503 +CTUN, 535, 0.00, 29.02, 0.000000, 0.00, 24, 100, 447, 0 +ATT, 0.00, 0.89, -24.56, -22.54, 0.10, 23.40, 23.83 +MOT, 1422, 1546, 1384, 1521 +GPS, 3, 109249800, 1774, 9, 2.42, -39.4934604, 176.7488032, 29.12, 72.83, 9.43, 8.64, -0.940000, 102790 +CTUN, 534, 0.00, 29.33, 0.000000, 0.00, 22, 106, 444, 0 +ATT, 0.00, 0.73, -24.27, -21.79, 0.10, 23.25, 23.83 +MOT, 1425, 1546, 1419, 1470 +CTUN, 535, 0.00, 29.96, 0.000000, 0.00, 21, 111, 444, 0 +ATT, 0.00, 0.44, -24.27, -21.45, 0.00, 23.04, 23.83 +MOT, 1465, 1510, 1393, 1498 +DU32, 7, 270713 +CURR, 443, 119729, 1572, 2923, 4940, 194.3328 +GPS, 3, 109250000, 1774, 9, 2.42, -39.4934438, 176.7488068, 29.40, 73.03, 9.38, 9.42, -0.970000, 102990 +CTUN, 535, 0.00, 29.78, 0.000000, 0.00, 21, 110, 444, 0 +ATT, 0.00, 0.44, -24.05, -21.52, 0.00, 23.01, 23.83 +MOT, 1425, 1540, 1429, 1469 +CTUN, 535, 0.00, 29.68, 0.000000, 0.00, 22, 105, 445, 0 +ATT, 0.00, 0.33, -24.05, -21.76, 0.00, 23.02, 23.83 +MOT, 1464, 1506, 1392, 1508 +GPS, 3, 109250200, 1774, 9, 2.42, -39.4934273, 176.7488107, 29.66, 73.23, 9.29, 10.12, -0.980000, 103190 +CTUN, 534, 0.00, 29.71, 0.000000, 0.00, 22, 98, 444, 0 +ATT, 0.00, 0.68, -24.27, -21.89, 0.20, 23.15, 23.83 +MOT, 1423, 1533, 1439, 1469 +CTUN, 534, 0.00, 29.84, 0.000000, 0.00, 22, 94, 444, 0 +ATT, 0.00, 0.27, -24.71, -21.79, 0.10, 23.29, 23.83 +MOT, 1454, 1502, 1381, 1528 +GPS, 3, 109250400, 1774, 9, 2.43, -39.4934109, 176.7488145, 29.88, 73.41, 9.21, 10.36, -0.890000, 103390 +CTUN, 534, 0.00, 30.14, 0.000000, 0.00, 22, 100, 444, 0 +ATT, 0.00, 0.58, -24.27, -21.68, 0.10, 23.47, 23.83 +MOT, 1396, 1551, 1423, 1489 +CTUN, 534, 0.00, 30.07, 0.000000, 0.00, 21, 105, 443, 0 +ATT, 0.00, 0.56, -23.90, -21.43, 0.00, 23.46, 23.83 +MOT, 1429, 1528, 1417, 1489 +GPS, 3, 109250600, 1774, 9, 2.43, -39.4933947, 176.7488185, 30.12, 73.57, 9.15, 10.63, -0.820000, 103591 +CTUN, 535, 0.00, 30.10, 0.000000, 0.00, 20, 107, 443, 0 +ATT, 0.00, 0.49, -24.34, -20.76, 0.00, 23.61, 23.83 +MOT, 1392, 1551, 1375, 1535 +CTUN, 534, 0.00, 30.25, 0.000000, 0.00, 19, 115, 441, 0 +ATT, 0.00, 0.70, -24.27, -20.60, 0.10, 23.58, 23.83 +MOT, 1405, 1549, 1409, 1484 +GPS, 3, 109250800, 1774, 9, 2.43, -39.4933787, 176.7488227, 30.36, 73.77, 9.09, 11.45, -0.850000, 103791 +CTUN, 534, 0.00, 30.45, 0.000000, 0.00, 20, 114, 442, 0 +ATT, 0.00, 0.75, -24.71, -20.70, 0.10, 23.31, 23.83 +MOT, 1451, 1524, 1416, 1466 +CTUN, 534, 0.00, 30.97, 0.000000, 0.00, 21, 105, 443, 0 +ATT, 0.00, -0.14, -24.71, -21.54, 0.00, 23.15, 23.83 +MOT, 1450, 1519, 1414, 1479 +DU32, 7, 270713 +CURR, 444, 124162, 1567, 2787, 4876, 202.3738 +PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 +GPS, 3, 109251000, 1774, 9, 2.43, -39.4933628, 176.7488271, 30.62, 73.98, 8.96, 12.25, -0.920000, 103991 +CTUN, 534, 0.00, 30.64, 0.000000, 0.00, 23, 95, 445, 0 +ATT, 0.00, -0.14, -24.71, -22.33, 0.20, 23.18, 23.83 +MOT, 1424, 1541, 1431, 1471 +CTUN, 534, 0.00, 30.33, 0.000000, 0.00, 24, 85, 446, 0 +ATT, 0.00, -0.17, -24.71, -22.78, 0.00, 23.24, 23.83 +MOT, 1476, 1493, 1422, 1483 +GPS, 3, 109251200, 1774, 9, 2.43, -39.4933474, 176.7488315, 30.80, 74.17, 8.77, 12.53, -0.830000, 104192 +CTUN, 534, 0.00, 30.64, 0.000000, 0.00, 25, 76, 447, 0 +ATT, 0.00, 0.10, -24.78, -23.16, 0.20, 23.44, 23.83 +MOT, 1407, 1548, 1439, 1479 +CTUN, 534, 0.00, 30.62, 0.000000, 0.00, 25, 74, 447, 0 +ATT, 0.00, 0.18, -24.71, -23.03, 0.00, 23.79, 23.83 +MOT, 1408, 1542, 1412, 1513 +GPS, 3, 109251400, 1774, 9, 2.43, -39.4933320, 176.7488358, 30.93, 74.33, 8.69, 12.36, -0.700000, 104392 +CTUN, 534, 0.00, 30.56, 0.000000, 0.00, 25, 75, 447, 0 +ATT, 0.00, 0.34, -24.71, -22.95, 0.00, 24.08, 23.83 +MOT, 1430, 1520, 1412, 1517 +CTUN, 534, 0.00, 30.65, 0.000000, 0.00, 24, 70, 446, 0 +ATT, 0.00, 0.19, -24.49, -22.80, 0.00, 24.27, 23.83 +MOT, 1428, 1518, 1457, 1472 +GPS, 3, 109251600, 1774, 9, 2.43, -39.4933167, 176.7488403, 31.04, 74.46, 8.75, 12.74, -0.620000, 104592 +CTUN, 534, 0.00, 31.08, 0.000000, 0.00, 26, 57, 448, 0 +ATT, 0.00, 0.63, -24.05, -23.37, 0.00, 24.27, 23.83 +MOT, 1411, 1545, 1416, 1506 +CTUN, 534, 0.00, 30.94, 0.000000, 0.00, 25, 50, 447, 0 +ATT, 0.00, 0.04, -24.27, -23.07, 0.00, 24.16, 23.83 +MOT, 1446, 1516, 1420, 1496 +GPS, 3, 109251800, 1774, 9, 2.43, -39.4933013, 176.7488448, 31.15, 74.57, 8.76, 12.59, -0.560000, 104793 +CTUN, 534, 0.00, 31.08, 0.000000, 0.00, 25, 49, 447, 0 +ATT, 0.00, 0.40, -24.49, -23.00, 0.00, 24.08, 23.83 +MOT, 1409, 1545, 1403, 1517 +CTUN, 535, 0.00, 31.13, 0.000000, 0.00, 25, 46, 448, 0 +ATT, 0.00, 0.44, -24.56, -23.22, 0.00, 24.00, 23.83 +MOT, 1392, 1563, 1424, 1494 +DU32, 7, 270713 +CURR, 447, 128628, 1559, 2951, 4876, 210.5070 +GPS, 3, 109252000, 1774, 9, 2.43, -39.4932860, 176.7488494, 31.24, 74.66, 8.75, 13.15, -0.460000, 104993 +CTUN, 534, 0.00, 30.87, 0.000000, 0.00, 23, 51, 445, 0 +ATT, 0.00, 0.11, -24.92, -22.34, 0.00, 24.03, 23.83 +MOT, 1468, 1489, 1439, 1475 +CTUN, 534, 0.00, 31.25, 0.000000, 0.00, 23, 48, 445, 0 +ATT, 0.00, 0.52, -24.71, -22.18, 0.00, 23.92, 23.83 +MOT, 1372, 1575, 1396, 1514 +GPS, 3, 109252200, 1774, 9, 2.43, -39.4932706, 176.7488541, 31.32, 74.76, 8.77, 13.44, -0.420000, 105193 +CTUN, 534, 0.00, 31.03, 0.000000, 0.00, 21, 52, 443, 0 +ATT, 0.00, -0.01, -24.99, -21.07, 0.00, 23.83, 23.83 +MOT, 1444, 1516, 1390, 1512 +CTUN, 535, 0.00, 30.83, 0.000000, 0.00, 19, 69, 442, 0 +ATT, 0.00, 0.24, -24.99, -20.29, 0.10, 23.66, 23.83 +MOT, 1376, 1573, 1410, 1485 +GPS, 3, 109252400, 1774, 9, 2.43, -39.4932553, 176.7488593, 31.42, 74.84, 8.81, 14.51, -0.410000, 105393 +CTUN, 534, 0.00, 31.08, 0.000000, 0.00, 18, 88, 440, 0 +ATT, 0.00, 0.42, -24.27, -19.80, 0.00, 23.60, 23.83 +MOT, 1384, 1559, 1391, 1506 +CTUN, 534, 0.00, 30.86, 0.000000, 0.00, 16, 110, 438, 0 +ATT, 0.00, 0.22, -24.34, -18.78, 0.20, 23.64, 23.83 +MOT, 1466, 1483, 1415, 1476 +GPS, 3, 109252600, 1774, 9, 2.43, -39.4932398, 176.7488648, 31.58, 75.00, 8.89, 15.29, -0.590000, 105594 +CTUN, 534, 0.00, 31.39, 0.000000, 0.00, 16, 129, 438, 0 +ATT, 0.00, 0.12, -24.71, -18.64, 0.00, 23.69, 23.83 +MOT, 1414, 1519, 1401, 1506 +CTUN, 534, 0.00, 31.43, 0.000000, 0.00, 15, 145, 437, 0 +ATT, 0.00, -0.03, -25.13, -18.49, 0.00, 23.93, 23.83 +MOT, 1428, 1510, 1419, 1480 +GPS, 3, 109252800, 1774, 9, 2.43, -39.4932243, 176.7488705, 31.85, 75.21, 8.94, 15.88, -0.900000, 105794 +CTUN, 537, 0.00, 31.48, 0.000000, 0.00, 16, 161, 441, 0 +ATT, 0.00, -0.21, -25.13, -18.79, 0.00, 23.93, 23.83 +MOT, 1435, 1515, 1412, 1492 +CTUN, 537, 0.00, 31.67, 0.000000, 0.00, 17, 173, 442, 0 +ATT, 0.00, -0.34, -25.13, -19.11, 0.10, 24.00, 23.83 +MOT, 1462, 1483, 1436, 1476 +DU32, 7, 270713 +CURR, 443, 133043, 1569, 2941, 4876, 218.5246 +GPS, 3, 109253000, 1774, 9, 2.43, -39.4932088, 176.7488763, 32.17, 75.49, 8.97, 16.10, -1.180000, 105994 +CTUN, 537, 0.00, 31.83, 0.000000, 0.00, 19, 171, 444, 0 +ATT, 0.00, -0.49, -25.13, -20.21, 0.10, 24.13, 23.83 +MOT, 1396, 1548, 1402, 1514 +CTUN, 537, 0.00, 32.17, 0.000000, 0.00, 20, 169, 445, 0 +ATT, 0.00, -0.26, -25.13, -20.98, 0.10, 24.12, 23.83 +MOT, 1404, 1548, 1452, 1460 +GPS, 3, 109253200, 1774, 9, 2.43, -39.4931932, 176.7488823, 32.50, 75.83, 8.99, 16.61, -1.370000, 106194 +CTUN, 537, 0.00, 32.30, 0.000000, 0.00, 21, 172, 446, 0 +ATT, 0.00, -0.44, -24.92, -21.17, 0.10, 23.98, 23.83 +MOT, 1436, 1524, 1441, 1473 +CTUN, 537, 0.00, 32.61, 0.000000, 0.00, 21, 179, 446, 0 +ATT, 0.00, -1.19, -24.92, -20.95, 0.00, 23.89, 23.83 +MOT, 1421, 1538, 1416, 1496 +GPS, 3, 109253400, 1774, 9, 2.43, -39.4931774, 176.7488884, 32.87, 76.19, 9.03, 16.91, -1.470000, 106395 +CTUN, 537, 0.00, 33.22, 0.000000, 0.00, 22, 182, 447, 0 +ATT, 0.00, -1.04, -24.99, -21.69, 0.20, 23.71, 23.83 +MOT, 1416, 1550, 1413, 1493 +CTUN, 537, 0.00, 32.91, 0.000000, 0.00, 23, 171, 448, 0 +ATT, 0.00, -0.73, -24.92, -22.34, 0.10, 23.70, 23.83 +MOT, 1501, 1470, 1452, 1460 +GPS, 3, 109253600, 1774, 9, 2.43, -39.4931615, 176.7488947, 33.25, 76.56, 9.11, 17.11, -1.570000, 106595 +CTUN, 542, 0.00, 33.28, 0.000000, 0.00, 27, 154, 459, 0 +ATT, 0.00, -0.59, -24.99, -23.48, 0.00, 23.68, 23.83 +MOT, 1454, 1537, 1452, 1483 +CTUN, 542, 0.00, 33.35, 0.000000, 0.00, 30, 136, 462, 0 +ATT, 0.00, -0.41, -24.92, -24.76, 0.00, 23.62, 23.83 +MOT, 1442, 1551, 1455, 1486 +GPS, 3, 109253800, 1774, 9, 2.43, -39.4931458, 176.7489006, 33.56, 76.90, 9.04, 16.33, -1.530000, 106796 +CTUN, 542, 0.00, 33.47, 0.000000, 0.00, 32, 123, 464, 0 +ATT, 0.00, -0.45, -24.71, -25.39, 0.00, 23.57, 23.83 +MOT, 1469, 1536, 1445, 1498 +CTUN, 542, 0.00, 33.38, 0.000000, 0.00, 33, 108, 465, 0 +ATT, 0.00, -0.60, -24.34, -26.02, 0.20, 23.61, 23.83 +MOT, 1498, 1506, 1492, 1462 +DU32, 7, 270713 +CURR, 467, 137556, 1528, 2975, 4876, 226.8026 +GPS, 3, 109254000, 1774, 9, 2.43, -39.4931300, 176.7489062, 33.77, 77.18, 9.03, 15.68, -1.300000, 106996 +CTUN, 539, 0.00, 33.95, 0.000000, 0.00, 34, 84, 462, 0 +ATT, 0.00, -0.80, -24.05, -26.38, 0.00, 23.47, 23.83 +MOT, 1474, 1532, 1445, 1490 +CTUN, 543, 0.00, 33.68, 0.000000, 0.00, 35, 65, 468, 0 +ATT, 0.00, -0.59, -24.05, -26.31, 0.00, 23.20, 23.83 +MOT, 1504, 1528, 1425, 1514 +GPS, 3, 109254200, 1774, 9, 2.43, -39.4931142, 176.7489117, 33.93, 77.40, 9.06, 14.94, -1.050000, 107196 +CTUN, 539, 0.00, 34.08, 0.000000, 0.00, 33, 56, 461, 0 +ATT, 0.00, -0.42, -24.05, -25.98, 0.10, 22.98, 23.83 +MOT, 1493, 1518, 1463, 1463 +CTUN, 543, 0.00, 34.06, 0.000000, 0.00, 33, 41, 466, 0 +ATT, 0.00, 0.17, -24.05, -25.56, 0.00, 22.83, 23.83 +MOT, 1477, 1546, 1397, 1536 +GPS, 3, 109254400, 1774, 9, 2.43, -39.4930982, 176.7489169, 34.04, 77.55, 9.13, 14.36, -0.760000, 107396 +CTUN, 540, 0.00, 33.96, 0.000000, 0.00, 29, 34, 458, 0 +ATT, 0.00, 1.02, -24.05, -24.52, 0.10, 22.86, 23.83 +MOT, 1468, 1530, 1471, 1456 +CTUN, 542, 0.00, 34.36, 0.000000, 0.00, 29, 25, 461, 0 +ATT, 0.00, 0.79, -24.05, -24.18, 0.00, 23.02, 23.83 +MOT, 1496, 1500, 1407, 1533 +GPS, 3, 109254600, 1774, 9, 2.43, -39.4930821, 176.7489222, 34.11, 77.63, 9.23, 14.03, -0.520000, 107596 +CTUN, 542, 0.00, 34.15, 0.000000, 0.00, 25, 29, 457, 0 +ATT, 0.00, 0.55, -24.12, -22.77, 0.20, 23.43, 23.83 +MOT, 1394, 1573, 1453, 1489 +CTUN, 539, 0.00, 34.88, 0.000000, 0.00, 21, 46, 449, 0 +ATT, 0.00, 0.45, -24.27, -21.18, 0.00, 23.78, 23.83 +MOT, 1407, 1543, 1421, 1512 +GPS, 3, 109254800, 1774, 9, 2.43, -39.4930660, 176.7489274, 34.24, 77.68, 9.26, 13.86, -0.400000, 107797 +CTUN, 539, 0.00, 34.39, 0.000000, 0.00, 19, 56, 447, 0 +ATT, 0.00, 0.38, -24.49, -20.15, 0.00, 23.98, 23.83 +MOT, 1444, 1514, 1373, 1543 +CTUN, 542, 0.00, 34.38, 0.000000, 0.00, 18, 70, 450, 0 +ATT, 0.00, 1.16, -24.49, -19.55, 0.00, 24.16, 23.83 +MOT, 1400, 1551, 1416, 1517 +DU32, 7, 270713 +CURR, 449, 142136, 1554, 2866, 4984, 235.1741 +GPS, 3, 109255000, 1774, 9, 2.43, -39.4930499, 176.7489325, 34.41, 77.78, 9.23, 13.73, -0.470000, 107997 +CTUN, 542, 0.00, 34.33, 0.000000, 0.00, 17, 91, 449, 0 +ATT, 0.00, 1.50, -24.71, -18.72, 0.00, 24.16, 23.83 +MOT, 1414, 1549, 1423, 1495 +CTUN, 540, 0.00, 34.52, 0.000000, 0.00, 15, 114, 444, 0 +ATT, 0.00, 0.73, -24.49, -17.99, 0.10, 24.02, 23.83 +MOT, 1417, 1543, 1403, 1498 +GPS, 3, 109255200, 1774, 9, 2.43, -39.4930336, 176.7489378, 34.64, 77.94, 9.31, 14.09, -0.630000, 108198 +CTUN, 539, 0.00, 34.66, 0.000000, 0.00, 15, 134, 443, 0 +ATT, 0.00, 0.29, -24.49, -17.82, 0.00, 23.90, 23.83 +MOT, 1373, 1576, 1414, 1485 +CTUN, 542, 0.00, 34.48, 0.000000, 0.00, 14, 157, 446, 0 +ATT, 0.00, 0.12, -24.49, -17.51, 0.00, 23.82, 23.83 +MOT, 1433, 1534, 1418, 1488 +GPS, 3, 109255400, 1774, 9, 2.43, -39.4930174, 176.7489433, 34.95, 78.16, 9.31, 14.45, -0.930000, 108397 +CTUN, 539, 0.00, 34.96, 0.000000, 0.00, 14, 178, 442, 0 +ATT, 0.00, -0.11, -24.71, -17.44, 0.00, 23.80, 23.83 +MOT, 1430, 1518, 1410, 1500 +CTUN, 539, 0.00, 35.11, 0.000000, 0.00, 15, 182, 443, 0 +ATT, 0.00, 0.00, -24.27, -18.35, 0.10, 23.78, 23.83 +MOT, 1352, 1584, 1404, 1505 +GPS, 3, 109255600, 1774, 9, 2.43, -39.4930010, 176.7489490, 35.33, 78.49, 9.32, 15.22, -1.240000, 108598 +CTUN, 540, 0.00, 35.31, 0.000000, 0.00, 13, 196, 442, 0 +ATT, 0.00, -0.76, -24.12, -17.17, 0.00, 24.27, 23.83 +MOT, 1492, 1437, 1432, 1497 +CTUN, 543, 0.00, 35.84, 0.000000, 0.00, 15, 201, 448, 0 +ATT, 0.00, -0.98, -24.27, -17.91, 0.00, 24.63, 23.83 +MOT, 1401, 1534, 1422, 1523 +GPS, 3, 109255800, 1774, 9, 2.43, -39.4929849, 176.7489544, 35.77, 78.86, 9.18, 14.86, -1.480000, 108798 +CTUN, 542, 0.00, 35.88, 0.000000, 0.00, 16, 196, 448, 0 +ATT, 0.00, -1.03, -24.49, -18.48, 0.00, 24.70, 23.83 +MOT, 1429, 1519, 1418, 1517 +CTUN, 539, 0.00, 36.00, 0.000000, 0.00, 18, 184, 446, 0 +ATT, 0.00, -1.13, -24.05, -19.78, 0.00, 24.70, 23.83 +MOT, 1437, 1506, 1465, 1465 +DU32, 7, 270713 +CURR, 447, 146589, 1583, 2876, 4940, 243.5272 +GPS, 3, 109256000, 1774, 9, 2.43, -39.4929692, 176.7489597, 36.18, 79.25, 8.94, 14.54, -1.580000, 108998 +CTUN, 539, 0.00, 36.11, 0.000000, 0.00, 20, 167, 448, 0 +ATT, 0.00, -0.67, -24.12, -20.55, 0.20, 24.67, 23.83 +MOT, 1394, 1558, 1466, 1456 +CTUN, 539, 0.00, 36.43, 0.000000, 0.00, 22, 155, 450, 0 +ATT, 0.00, -1.00, -24.05, -21.81, 0.00, 24.39, 23.83 +MOT, 1452, 1517, 1405, 1517 +GPS, 3, 109256200, 1774, 9, 2.43, -39.4929538, 176.7489644, 36.52, 79.61, 8.70, 13.52, -1.510000, 109199 +CTUN, 539, 0.00, 36.44, 0.000000, 0.00, 25, 138, 453, 0 +ATT, 0.00, -0.37, -23.62, -22.84, 0.00, 24.20, 23.83 +MOT, 1459, 1514, 1480, 1451 +CTUN, 542, 0.00, 36.43, 0.000000, 0.00, 26, 125, 458, 0 +ATT, 0.00, 0.00, -23.90, -23.07, 0.20, 24.29, 23.83 +MOT, 1420, 1546, 1414, 1537 +GPS, 3, 109256400, 1774, 9, 2.43, -39.4929387, 176.7489687, 36.78, 79.90, 8.50, 12.77, -1.290000, 109399 +CTUN, 539, 0.00, 36.75, 0.000000, 0.00, 25, 114, 453, 0 +ATT, 0.00, 0.49, -23.62, -23.12, 0.00, 24.32, 23.83 +MOT, 1449, 1518, 1446, 1491 +CTUN, 542, 0.00, 36.85, 0.000000, 0.00, 25, 106, 457, 0 +ATT, 0.00, 0.46, -23.83, -22.79, 0.00, 24.32, 23.83 +MOT, 1455, 1524, 1418, 1523 +GPS, 3, 109256600, 1774, 9, 2.43, -39.4929238, 176.7489731, 37.01, 80.13, 8.44, 12.84, -1.100000, 109599 +CTUN, 539, 0.00, 36.96, 0.000000, 0.00, 25, 108, 453, 0 +ATT, 0.00, 0.56, -24.05, -22.74, 0.10, 24.24, 23.83 +MOT, 1413, 1553, 1424, 1506 +CTUN, 539, 0.00, 37.33, 0.000000, 0.00, 24, 101, 452, 0 +ATT, 0.00, 0.82, -24.05, -22.60, 0.00, 24.28, 23.83 +MOT, 1408, 1549, 1446, 1491 +GPS, 3, 109256800, 1774, 9, 2.43, -39.4929091, 176.7489776, 37.24, 80.33, 8.41, 13.19, -1.010000, 109800 +CTUN, 542, 0.00, 37.40, 0.000000, 0.00, 23, 99, 455, 0 +ATT, 0.00, 0.37, -24.27, -21.92, 0.10, 24.39, 23.83 +MOT, 1423, 1543, 1388, 1548 +CTUN, 542, 0.00, 37.35, 0.000000, 0.00, 21, 112, 453, 0 +ATT, 0.00, 0.29, -24.05, -20.87, 0.10, 24.33, 23.83 +MOT, 1382, 1572, 1400, 1535 +DU32, 7, 270713 +CURR, 450, 151121, 1536, 3095, 4897, 251.8125 +GPS, 3, 109257000, 1774, 9, 2.43, -39.4928947, 176.7489820, 37.49, 80.50, 8.31, 13.04, -0.950000, 110000 +CTUN, 542, 0.00, 37.11, 0.000000, 0.00, 18, 136, 450, 0 +ATT, 0.00, 0.10, -23.83, -19.36, 0.00, 24.36, 23.83 +MOT, 1453, 1501, 1481, 1456 +CTUN, 542, 0.00, 37.54, 0.000000, 0.00, 16, 150, 448, 0 +ATT, 0.00, -0.16, -23.83, -18.58, 0.10, 24.37, 23.83 +MOT, 1431, 1525, 1405, 1521 +GPS, 3, 109257200, 1774, 9, 2.43, -39.4928805, 176.7489863, 37.78, 80.72, 8.17, 13.28, -1.060000, 110201 +CTUN, 542, 0.00, 37.71, 0.000000, 0.00, 16, 157, 448, 0 +ATT, 0.00, -0.30, -23.62, -18.48, 0.00, 24.33, 23.83 +MOT, 1422, 1532, 1418, 1509 +CTUN, 542, 0.00, 37.73, 0.000000, 0.00, 16, 162, 448, 0 +ATT, 0.00, -0.42, -24.12, -18.41, 0.20, 24.23, 23.83 +MOT, 1436, 1526, 1437, 1483 +GPS, 3, 109257400, 1774, 9, 2.43, -39.4928664, 176.7489905, 38.11, 81.02, 8.04, 13.08, -1.280000, 110401 +CTUN, 542, 0.00, 37.68, 0.000000, 0.00, 17, 165, 449, 0 +ATT, 0.00, -0.40, -24.05, -19.03, 0.00, 24.07, 23.83 +MOT, 1400, 1555, 1392, 1532 +CTUN, 539, 0.00, 38.18, 0.000000, 0.00, 18, 165, 446, 0 +ATT, 0.00, -0.30, -24.27, -19.61, 0.00, 23.97, 23.83 +MOT, 1418, 1541, 1413, 1499 +GPS, 3, 109257600, 1774, 9, 2.43, -39.4928525, 176.7489946, 38.43, 81.34, 7.88, 12.96, -1.390000, 110601 +CTUN, 539, 0.00, 38.10, 0.000000, 0.00, 18, 168, 446, 0 +ATT, 0.00, -0.01, -24.27, -19.77, 0.00, 23.89, 23.83 +MOT, 1424, 1537, 1412, 1498 +CTUN, 542, 0.00, 38.00, 0.000000, 0.00, 19, 169, 451, 0 +ATT, 0.00, 0.23, -24.71, -20.11, 0.00, 23.84, 23.83 +MOT, 1440, 1524, 1431, 1500 +GPS, 3, 109257800, 1774, 9, 2.43, -39.4928389, 176.7489986, 38.74, 81.64, 7.73, 12.86, -1.400000, 110801 +CTUN, 539, 0.00, 38.70, 0.000000, 0.00, 20, 165, 448, 0 +ATT, 0.00, 0.27, -24.78, -20.87, 0.00, 23.80, 23.83 +MOT, 1388, 1568, 1398, 1518 +CTUN, 542, 0.00, 38.91, 0.000000, 0.00, 22, 159, 454, 0 +ATT, 0.00, 0.32, -24.49, -21.41, 0.00, 23.73, 23.83 +MOT, 1429, 1539, 1444, 1493 +DU32, 7, 270713 +CURR, 450, 155609, 1554, 2967, 4940, 260.1063 +GPS, 3, 109258000, 1774, 9, 2.43, -39.4928254, 176.7490024, 39.08, 81.97, 7.64, 12.65, -1.450000, 111002 +CTUN, 539, 0.00, 38.86, 0.000000, 0.00, 23, 152, 451, 0 +ATT, 0.00, -0.06, -24.49, -22.12, 0.10, 23.85, 23.83 +MOT, 1466, 1500, 1457, 1472 +CTUN, 539, 0.00, 39.10, 0.000000, 0.00, 25, 139, 453, 0 +ATT, 0.00, 0.00, -24.56, -22.90, 0.00, 23.81, 23.83 +MOT, 1404, 1564, 1437, 1488 +GPS, 3, 109258200, 1774, 9, 2.43, -39.4928122, 176.7490063, 39.37, 82.26, 7.49, 12.75, -1.360000, 111202 +CTUN, 539, 0.00, 39.08, 0.000000, 0.00, 26, 128, 454, 0 +ATT, 0.00, 0.18, -24.56, -23.37, 0.20, 23.73, 23.83 +MOT, 1446, 1535, 1473, 1452 +CTUN, 542, 0.00, 39.69, 0.000000, 0.00, 28, 114, 460, 0 +ATT, 0.00, 0.10, -24.49, -24.10, 0.00, 23.69, 23.83 +MOT, 1427, 1557, 1433, 1509 +GPS, 3, 109258400, 1774, 9, 2.43, -39.4927993, 176.7490101, 39.61, 82.52, 7.38, 12.82, -1.240000, 111402 +CTUN, 539, 0.00, 39.34, 0.000000, 0.00, 29, 101, 457, 0 +ATT, 0.00, 0.09, -24.49, -24.54, 0.00, 23.72, 23.83 +MOT, 1448, 1532, 1449, 1491 +CTUN, 543, 0.00, 39.88, 0.000000, 0.00, 30, 88, 463, 0 +ATT, 0.00, 0.00, -24.49, -24.64, 0.10, 23.76, 23.83 +MOT, 1438, 1551, 1434, 1516 +GPS, 3, 109258600, 1774, 9, 2.43, -39.4927864, 176.7490139, 39.81, 82.72, 7.37, 12.71, -1.060000, 111602 +CTUN, 542, 0.00, 39.79, 0.000000, 0.00, 29, 86, 461, 0 +ATT, 0.00, -0.27, -24.71, -24.08, 0.00, 23.80, 23.83 +MOT, 1436, 1546, 1445, 1504 +CTUN, 543, 0.00, 40.35, 0.000000, 0.00, 28, 87, 461, 0 +ATT, 0.00, -0.58, -24.92, -23.78, 0.00, 23.88, 23.83 +MOT, 1419, 1558, 1462, 1490 +GPS, 3, 109258800, 1774, 9, 2.43, -39.4927735, 176.7490175, 40.02, 82.88, 7.31, 12.50, -0.870000, 111803 +CTUN, 542, 0.00, 39.76, 0.000000, 0.00, 27, 83, 459, 0 +ATT, 0.00, -0.93, -24.92, -23.70, 0.00, 23.95, 23.83 +MOT, 1460, 1525, 1439, 1504 +CTUN, 540, 0.00, 39.67, 0.000000, 0.00, 28, 75, 457, 0 +ATT, 0.00, -0.93, -25.13, -24.20, 0.10, 23.94, 23.83 +MOT, 1427, 1552, 1434, 1501 +DU32, 7, 270713 +CURR, 456, 160185, 1552, 3048, 4918, 268.5145 +GPS, 3, 109259000, 1774, 9, 2.43, -39.4927608, 176.7490210, 40.15, 83.01, 7.32, 12.12, -0.790000, 112003 +CTUN, 542, 0.00, 39.69, 0.000000, 0.00, 29, 65, 461, 0 +ATT, 0.00, -0.48, -24.92, -24.50, 0.20, 23.84, 23.83 +MOT, 1488, 1509, 1450, 1492 +CTUN, 539, 0.00, 39.70, 0.000000, 0.00, 31, 43, 459, 0 +ATT, 0.00, -0.12, -24.92, -25.23, 0.20, 23.83, 23.83 +MOT, 1439, 1549, 1465, 1470 +GPS, 3, 109259200, 1774, 9, 2.43, -39.4927479, 176.7490242, 40.20, 83.12, 7.34, 11.32, -0.670000, 112203 +CTUN, 542, 0.00, 40.02, 0.000000, 0.00, 33, 22, 465, 0 +ATT, 0.00, 0.18, -24.99, -25.68, 0.00, 23.77, 23.83 +MOT, 1478, 1532, 1448, 1500 +CTUN, 542, 0.00, 40.35, 0.000000, 0.00, 35, 2, 467, 0 +ATT, 0.00, 0.68, -24.92, -26.46, 0.00, 23.62, 23.83 +MOT, 1410, 1592, 1461, 1486 +GPS, 3, 109259400, 1774, 9, 2.43, -39.4927349, 176.7490273, 40.22, 83.21, 7.34, 10.86, -0.450000, 112403 +CTUN, 542, 0.00, 39.77, 0.000000, 0.00, 32, -2, 464, 0 +ATT, 0.00, -0.30, -24.71, -25.44, 0.00, 23.55, 23.83 +MOT, 1469, 1531, 1425, 1524 +CTUN, 542, 0.00, 40.08, 0.000000, 0.00, 26, 15, 458, 0 +ATT, 0.00, -1.42, -24.71, -23.06, 0.00, 23.62, 23.83 +MOT, 1423, 1548, 1464, 1483 +GPS, 3, 109259600, 1774, 9, 2.43, -39.4927221, 176.7490301, 40.21, 83.17, 7.31, 10.19, -0.099999, 112604 +CTUN, 539, 0.00, 40.00, 0.000000, 0.00, 22, 40, 450, 0 +ATT, 0.00, -1.87, -24.92, -21.58, 0.00, 23.68, 23.83 +MOT, 1411, 1546, 1420, 1509 +CTUN, 540, 0.00, 40.07, 0.000000, 0.00, 20, 55, 449, 0 +ATT, 0.00, -2.06, -24.71, -20.32, 0.10, 23.67, 23.83 +MOT, 1405, 1554, 1413, 1508 +GPS, 3, 109259800, 1774, 9, 2.43, -39.4927090, 176.7490326, 40.30, 83.18, 7.44, 9.17, -0.110000, 112804 +CTUN, 539, 0.00, 40.07, 0.000000, 0.00, 19, 69, 447, 0 +ATT, 0.00, -2.00, -24.92, -19.91, 0.00, 23.68, 23.83 +MOT, 1445, 1517, 1445, 1471 +CTUN, 539, 0.00, 39.76, 0.000000, 0.00, 19, 78, 447, 0 +ATT, 0.00, -1.72, -24.92, -20.25, 0.00, 23.63, 23.83 +MOT, 1421, 1537, 1407, 1512 +DU32, 7, 270713 +CURR, 447, 164742, 1580, 2990, 4940, 277.0022 +GPS, 3, 109260000, 1774, 9, 2.43, -39.4926954, 176.7490347, 40.42, 83.28, 7.60, 7.95, -0.380000, 113005 +CTUN, 542, 0.00, 40.27, 0.000000, 0.00, 20, 88, 452, 0 +ATT, 0.00, -1.26, -24.71, -20.36, 0.00, 23.60, 23.83 +MOT, 1422, 1547, 1442, 1482 +CTUN, 542, 0.00, 40.27, 0.000000, 0.00, 20, 95, 452, 0 +ATT, 0.00, -0.93, -24.05, -20.66, 0.00, 23.64, 23.83 +MOT, 1393, 1569, 1429, 1498 +GPS, 3, 109260200, 1774, 9, 2.43, -39.4926817, 176.7490362, 40.59, 83.44, 7.64, 6.49, -0.550000, 113205 +CTUN, 542, 0.00, 40.23, 0.000000, 0.00, 20, 97, 452, 0 +ATT, 0.00, -0.28, -23.83, -20.72, 0.20, 23.82, 23.83 +MOT, 1367, 1586, 1433, 1498 +CTUN, 542, 0.00, 40.64, 0.000000, 0.00, 19, 109, 451, 0 +ATT, 0.00, -0.01, -23.40, -20.01, 0.00, 24.07, 23.83 +MOT, 1431, 1529, 1430, 1505 +GPS, 3, 109260400, 1774, 9, 2.43, -39.4926680, 176.7490375, 40.80, 83.60, 7.61, 5.22, -0.650000, 113405 +CTUN, 542, 0.00, 40.60, 0.000000, 0.00, 18, 121, 450, 0 +ATT, 0.00, 0.34, -23.18, -19.29, 0.00, 24.16, 23.83 +MOT, 1440, 1520, 1430, 1501 +CTUN, 542, 0.00, 40.51, 0.000000, 0.00, 16, 130, 448, 0 +ATT, 0.00, 0.48, -22.75, -18.67, 0.00, 24.22, 23.83 +MOT, 1400, 1551, 1423, 1501 +GPS, 3, 109260600, 1774, 9, 2.43, -39.4926544, 176.7490384, 41.04, 83.80, 7.51, 4.14, -0.780000, 113605 +CTUN, 542, 0.00, 40.58, 0.000000, 0.00, 15, 142, 447, 0 +ATT, 0.00, 0.79, -22.53, -18.02, 0.00, 24.17, 23.83 +MOT, 1430, 1533, 1448, 1466 +CTUN, 542, 0.00, 40.94, 0.000000, 0.00, 14, 148, 446, 0 +ATT, 0.00, 0.96, -22.53, -17.53, 0.10, 24.09, 23.83 +MOT, 1417, 1545, 1419, 1489 +GPS, 3, 109260800, 1774, 9, 2.43, -39.4926413, 176.7490391, 41.32, 84.02, 7.29, 3.28, -0.940000, 113805 +CTUN, 542, 0.00, 40.95, 0.000000, 0.00, 14, 153, 446, 0 +ATT, 0.00, 0.87, -22.53, -17.66, 0.10, 23.88, 23.83 +MOT, 1424, 1541, 1378, 1528 +CTUN, 543, 0.00, 41.04, 0.000000, 0.00, 14, 158, 447, 0 +ATT, 0.00, 1.17, -22.75, -17.20, 0.10, 23.70, 23.83 +MOT, 1421, 1548, 1421, 1482 +DU32, 7, 270713 +CURR, 447, 169231, 1539, 2927, 4876, 285.3965 +PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 +GPS, 3, 109261000, 1774, 9, 2.43, -39.4926285, 176.7490398, 41.61, 84.31, 7.06, 2.80, -1.120000, 114006 +CTUN, 542, 0.00, 41.14, 0.000000, 0.00, 14, 164, 446, 0 +ATT, 0.00, 1.18, -22.96, -17.40, 0.00, 23.61, 23.83 +MOT, 1442, 1528, 1392, 1512 +CTUN, 543, 0.00, 41.37, 0.000000, 0.00, 14, 167, 447, 0 +ATT, 0.00, 1.02, -22.75, -17.60, 0.10, 23.66, 23.83 +MOT, 1421, 1540, 1412, 1502 +GPS, 3, 109261200, 1774, 9, 2.43, -39.4926161, 176.7490403, 41.92, 84.60, 6.84, 2.31, -1.210000, 114206 +CTUN, 542, 0.00, 41.35, 0.000000, 0.00, 15, 171, 447, 0 +ATT, 0.00, 0.93, -22.96, -17.77, 0.10, 23.69, 23.83 +MOT, 1428, 1538, 1413, 1497 +CTUN, 542, 0.00, 41.47, 0.000000, 0.00, 15, 175, 447, 0 +ATT, 0.14, 0.74, -22.96, -18.04, 0.10, 23.67, 23.83 +MOT, 1413, 1553, 1393, 1513 +GPS, 3, 109261400, 1774, 9, 2.43, -39.4926043, 176.7490409, 42.23, 84.88, 6.59, 2.18, -1.280000, 114406 +CTUN, 542, 0.00, 41.88, 0.000000, 0.00, 15, 178, 447, 0 +ATT, 0.21, 0.64, -23.18, -18.17, 0.10, 23.70, 23.83 +MOT, 1396, 1563, 1435, 1475 +CTUN, 542, 0.00, 41.68, 0.000000, 0.00, 16, 183, 448, 0 +ATT, 0.21, 0.50, -23.40, -18.41, 0.10, 23.64, 23.83 +MOT, 1434, 1538, 1419, 1489 +GPS, 3, 109261600, 1774, 9, 2.43, -39.4925927, 176.7490415, 42.56, 85.19, 6.40, 2.09, -1.380000, 114606 +CTUN, 542, 0.00, 41.81, 0.000000, 0.00, 16, 191, 448, 0 +ATT, 0.21, 0.66, -23.40, -18.69, 0.20, 23.63, 23.83 +MOT, 1432, 1540, 1425, 1482 +CTUN, 542, 0.00, 42.59, 0.000000, 0.00, 17, 196, 449, 0 +ATT, 0.86, 0.70, -24.05, -18.97, 0.10, 23.57, 23.83 +MOT, 1468, 1510, 1409, 1501 +GPS, 3, 109261800, 1774, 9, 2.43, -39.4925816, 176.7490420, 42.92, 85.49, 6.21, 2.01, -1.430000, 114807 +CTUN, 542, 0.00, 42.46, 0.000000, 0.00, 17, 200, 449, 0 +ATT, 1.29, 0.92, -24.34, -19.18, 0.10, 23.50, 23.83 +MOT, 1456, 1521, 1431, 1479 +CTUN, 539, 0.00, 42.60, 0.000000, 0.00, 18, 201, 446, 0 +ATT, 1.43, 0.89, -24.49, -19.80, 0.10, 23.53, 23.83 +MOT, 1441, 1521, 1436, 1476 +DU32, 7, 270713 +CURR, 448, 173710, 1569, 3056, 4897, 293.6468 +GPS, 3, 109262000, 1774, 9, 2.43, -39.4925706, 176.7490425, 43.29, 85.83, 6.08, 1.99, -1.530000, 115007 +CTUN, 539, 0.00, 42.93, 0.000000, 0.00, 21, 190, 449, 0 +ATT, 1.65, 1.21, -24.49, -21.09, 0.10, 23.56, 23.83 +MOT, 1464, 1509, 1428, 1486 +CTUN, 542, 0.00, 42.83, 0.000000, 0.00, 22, 179, 454, 0 +ATT, 2.16, 1.50, -24.71, -21.46, 0.10, 23.50, 23.83 +MOT, 1472, 1516, 1408, 1513 +GPS, 3, 109262200, 1774, 9, 2.43, -39.4925600, 176.7490430, 43.63, 86.18, 5.88, 2.15, -1.550000, 115207 +CTUN, 539, 0.00, 42.82, 0.000000, 0.00, 22, 178, 450, 0 +ATT, 2.30, 1.83, -24.92, -21.66, 0.20, 23.39, 23.83 +MOT, 1431, 1542, 1438, 1476 +CTUN, 539, 0.00, 43.32, 0.000000, 0.00, 23, 173, 451, 0 +ATT, 2.95, 2.56, -25.35, -22.11, 0.00, 23.39, 23.83 +MOT, 1422, 1550, 1425, 1491 +GPS, 3, 109262400, 1774, 9, 2.43, -39.4925496, 176.7490437, 43.92, 86.47, 5.76, 2.59, -1.430000, 115408 +CTUN, 542, 0.00, 43.43, 0.000000, 0.00, 26, 160, 458, 0 +ATT, 3.02, 2.96, -25.86, -23.18, 0.20, 23.32, 23.83 +MOT, 1464, 1529, 1433, 1498 +CTUN, 539, 0.00, 43.60, 0.000000, 0.00, 28, 145, 456, 0 +ATT, 3.67, 3.24, -25.79, -24.19, 0.00, 23.19, 23.83 +MOT, 1479, 1515, 1448, 1475 +GPS, 3, 109262600, 1774, 9, 2.43, -39.4925393, 176.7490446, 44.18, 86.77, 5.70, 3.32, -1.380000, 115608 +CTUN, 539, 0.00, 44.18, 0.000000, 0.00, 32, 127, 460, 0 +ATT, 3.89, 3.94, -25.79, -25.24, 0.10, 23.14, 23.83 +MOT, 1459, 1538, 1425, 1508 +CTUN, 543, 0.00, 43.76, 0.000000, 0.00, 34, 114, 467, 0 +ATT, 4.10, 4.32, -26.08, -25.84, 0.00, 23.08, 23.83 +MOT, 1526, 1497, 1443, 1500 +GPS, 3, 109262800, 1774, 9, 2.43, -39.4925289, 176.7490456, 44.41, 87.06, 5.70, 4.08, -1.220000, 115808 +CTUN, 542, 0.00, 43.94, 0.000000, 0.00, 37, 98, 469, 0 +ATT, 4.25, 4.46, -26.44, -26.89, 0.00, 22.88, 23.83 +MOT, 1430, 1579, 1433, 1519 +CTUN, 539, 0.00, 44.30, 0.000000, 0.00, 37, 87, 465, 0 +ATT, 4.97, 4.34, -26.66, -27.02, 0.10, 22.83, 23.83 +MOT, 1482, 1535, 1412, 1528 +DU32, 7, 270713 +CURR, 465, 178287, 1573, 3207, 4918, 302.1701 +GPS, 3, 109263000, 1774, 9, 2.43, -39.4925188, 176.7490470, 44.56, 87.25, 5.66, 5.27, -0.980000, 116008 +CTUN, 539, 0.00, 43.95, 0.000000, 0.00, 37, 82, 465, 0 +ATT, 5.40, 4.53, -26.73, -26.89, 0.20, 22.86, 23.83 +MOT, 1460, 1554, 1472, 1465 +CTUN, 542, 0.00, 44.06, 0.000000, 0.00, 36, 84, 468, 0 +ATT, 5.84, 4.81, -27.16, -26.34, 0.00, 22.99, 23.83 +MOT, 1505, 1518, 1463, 1484 +GPS, 3, 109263200, 1774, 9, 2.43, -39.4925087, 176.7490489, 44.67, 87.37, 5.68, 6.75, -0.740000, 116209 +CTUN, 542, 0.00, 44.08, 0.000000, 0.00, 38, 75, 470, 0 +ATT, 4.76, 4.96, -26.66, -26.95, 0.10, 23.04, 23.83 +MOT, 1418, 1583, 1408, 1549 +CTUN, 542, 0.00, 44.36, 0.000000, 0.00, 35, 73, 467, 0 +ATT, 4.54, 4.69, -26.22, -26.14, 0.00, 23.35, 23.83 +MOT, 1471, 1536, 1450, 1509 +GPS, 3, 109263400, 1774, 9, 2.43, -39.4924982, 176.7490512, 44.77, 87.55, 5.86, 8.33, -0.680000, 116409 +CTUN, 542, 0.00, 44.38, 0.000000, 0.00, 33, 75, 465, 0 +ATT, 4.76, 4.58, -26.00, -25.40, 0.10, 23.65, 23.83 +MOT, 1442, 1551, 1478, 1480 +CTUN, 539, 0.00, 44.37, 0.000000, 0.00, 33, 69, 461, 0 +ATT, 4.10, 4.66, -26.08, -25.45, 0.00, 23.93, 23.83 +MOT, 1419, 1558, 1442, 1510 +GPS, 3, 109263600, 1774, 9, 2.43, -39.4924877, 176.7490537, 44.88, 87.67, 5.95, 9.33, -0.630000, 116609 +CTUN, 539, 0.00, 44.81, 0.000000, 0.00, 32, 65, 460, 0 +ATT, 4.10, 4.44, -26.08, -25.44, 0.00, 24.16, 23.83 +MOT, 1443, 1536, 1454, 1498 +CTUN, 540, 0.00, 44.77, 0.000000, 0.00, 32, 59, 461, 0 +ATT, 3.46, 3.91, -26.44, -25.39, 0.00, 24.12, 23.83 +MOT, 1465, 1528, 1458, 1485 +GPS, 3, 109263800, 1774, 9, 2.43, -39.4924771, 176.7490567, 44.99, 87.79, 6.01, 10.61, -0.600000, 116810 +CTUN, 539, 0.00, 44.72, 0.000000, 0.00, 33, 50, 461, 0 +ATT, 3.46, 3.54, -26.95, -25.64, 0.00, 23.95, 23.83 +MOT, 1458, 1534, 1433, 1511 +CTUN, 542, 0.00, 44.56, 0.000000, 0.00, 34, 45, 466, 0 +ATT, 3.39, 3.32, -26.88, -26.12, 0.10, 23.80, 23.83 +MOT, 1457, 1550, 1448, 1502 +DU32, 7, 270713 +CURR, 462, 182930, 1542, 3131, 4897, 310.9405 +GPS, 3, 109264000, 1774, 9, 2.43, -39.4924666, 176.7490601, 45.05, 87.87, 6.02, 12.43, -0.490000, 117010 +CTUN, 540, 0.00, 45.02, 0.000000, 0.00, 34, 43, 463, 0 +ATT, 3.46, 3.32, -26.88, -26.18, 0.00, 23.68, 23.83 +MOT, 1466, 1534, 1432, 1512 +CTUN, 539, 0.00, 45.18, 0.000000, 0.00, 34, 38, 462, 0 +ATT, 3.46, 3.51, -26.88, -26.03, 0.00, 23.63, 23.83 +MOT, 1450, 1544, 1433, 1511 +GPS, 3, 109264200, 1774, 9, 2.43, -39.4924558, 176.7490635, 45.13, 87.98, 6.12, 13.32, -0.430000, 117210 +CTUN, 542, 0.00, 44.45, 0.000000, 0.00, 33, 40, 465, 0 +ATT, 3.46, 3.68, -26.29, -25.57, 0.00, 23.79, 23.83 +MOT, 1438, 1556, 1469, 1488 +CTUN, 542, 0.00, 44.72, 0.000000, 0.00, 32, 44, 464, 0 +ATT, 3.46, 3.38, -26.22, -25.26, 0.00, 23.98, 23.83 +MOT, 1461, 1528, 1451, 1510 +GPS, 3, 109264400, 1774, 9, 2.43, -39.4924451, 176.7490670, 45.16, 88.06, 6.12, 13.83, -0.310000, 117410 +CTUN, 542, 0.00, 44.69, 0.000000, 0.00, 31, 47, 463, 0 +ATT, 4.10, 3.39, -27.09, -24.59, 0.00, 24.14, 23.83 +MOT, 1424, 1560, 1423, 1528 +CTUN, 542, 0.00, 45.14, 0.000000, 0.00, 30, 50, 462, 0 +ATT, 4.54, 3.63, -27.82, -24.38, 0.00, 24.15, 23.83 +MOT, 1436, 1556, 1441, 1500 +GPS, 3, 109264600, 1774, 9, 2.43, -39.4924343, 176.7490708, 45.23, 88.16, 6.17, 14.59, -0.330000, 117611 +CTUN, 542, 0.00, 45.33, 0.000000, 0.00, 30, 54, 462, 0 +ATT, 4.32, 4.10, -27.53, -24.35, 0.00, 24.07, 23.83 +MOT, 1456, 1531, 1452, 1502 +CTUN, 542, 0.00, 44.76, 0.000000, 0.00, 29, 56, 461, 0 +ATT, 4.32, 4.08, -27.75, -24.10, 0.00, 24.12, 23.83 +MOT, 1439, 1549, 1448, 1496 +GPS, 3, 109264800, 1774, 9, 2.43, -39.4924237, 176.7490749, 45.33, 88.24, 6.18, 15.65, -0.380000, 117811 +CTUN, 542, 0.00, 44.95, 0.000000, 0.00, 30, 58, 462, 0 +ATT, 4.10, 4.07, -27.82, -24.33, 0.00, 24.03, 23.83 +MOT, 1468, 1533, 1433, 1506 +CTUN, 542, 0.00, 45.24, 0.000000, 0.00, 31, 54, 463, 0 +ATT, 4.32, 4.08, -27.82, -24.64, 0.00, 23.96, 23.83 +MOT, 1437, 1552, 1450, 1500 +DU32, 7, 270713 +CURR, 463, 187551, 1558, 3122, 4876, 319.6703 +GPS, 3, 109265000, 1774, 9, 2.43, -39.4924130, 176.7490793, 45.42, 88.38, 6.18, 16.76, -0.450000, 118011 +CTUN, 542, 0.00, 45.11, 0.000000, 0.00, 31, 53, 463, 0 +ATT, 4.32, 3.95, -27.53, -24.83, 0.00, 23.97, 23.83 +MOT, 1441, 1547, 1443, 1509 +CTUN, 542, 0.00, 44.96, 0.000000, 0.00, 33, 47, 465, 0 +ATT, 4.54, 3.97, -27.75, -25.49, 0.00, 24.05, 23.83 +MOT, 1453, 1543, 1459, 1499 +GPS, 3, 109265200, 1774, 9, 2.43, -39.4924024, 176.7490838, 45.48, 88.52, 6.16, 17.51, -0.470000, 118212 +CTUN, 542, 0.00, 45.25, 0.000000, 0.00, 35, 34, 467, 0 +ATT, 4.76, 4.05, -27.75, -26.20, 0.00, 24.10, 23.83 +MOT, 1488, 1517, 1453, 1510 +CTUN, 542, 0.00, 45.10, 0.000000, 0.00, 38, 19, 470, 0 +ATT, 4.76, 4.34, -27.82, -27.17, 0.00, 24.01, 23.83 +MOT, 1456, 1554, 1439, 1523 +GPS, 3, 109265400, 1774, 9, 2.43, -39.4923919, 176.7490885, 45.49, 88.59, 6.22, 18.21, -0.390000, 118411 +CTUN, 542, 0.00, 45.02, 0.000000, 0.00, 40, 8, 472, 0 +ATT, 4.97, 4.50, -27.82, -27.80, 0.00, 23.84, 23.83 +MOT, 1493, 1526, 1459, 1510 +CTUN, 543, 0.00, 45.10, 0.000000, 0.00, 41, -4, 474, 0 +ATT, 4.97, 4.75, -27.96, -27.99, 0.00, 23.69, 23.83 +MOT, 1444, 1574, 1442, 1522 +GPS, 3, 109265600, 1774, 9, 2.43, -39.4923812, 176.7490931, 45.44, 88.65, 6.21, 18.56, -0.180000, 118612 +CTUN, 542, 0.00, 44.96, 0.000000, 0.00, 40, -8, 472, 0 +ATT, 3.89, 4.70, -27.82, -27.77, 0.00, 23.77, 23.83 +MOT, 1494, 1521, 1455, 1518 +CTUN, 542, 0.00, 45.47, 0.000000, 0.00, 39, -10, 471, 0 +ATT, 3.24, 4.06, -27.75, -27.39, 0.00, 23.90, 23.83 +MOT, 1443, 1560, 1451, 1520 +GPS, 3, 109265800, 1774, 9, 2.43, -39.4923704, 176.7490979, 45.39, 88.67, 6.29, 18.84, 0.000000, 118812 +CTUN, 542, 0.00, 45.47, 0.000000, 0.00, 36, -10, 468, 0 +ATT, 3.24, 3.81, -27.75, -26.64, 0.00, 24.01, 23.83 +MOT, 1450, 1550, 1468, 1497 +CTUN, 542, 0.00, 45.51, 0.000000, 0.00, 35, -8, 467, 0 +ATT, 3.46, 3.81, -28.03, -26.35, 0.00, 24.06, 23.83 +MOT, 1474, 1528, 1460, 1504 +DU32, 7, 270713 +CURR, 468, 192237, 1576, 3266, 4984, 328.5627 +GPS, 3, 109266000, 1774, 9, 2.43, -39.4923594, 176.7491030, 45.38, 88.67, 6.48, 19.37, 0.070000, 119013 +CTUN, 542, 0.00, 45.19, 0.000000, 0.00, 35, -12, 467, 0 +ATT, 3.46, 3.69, -28.03, -26.41, 0.00, 23.94, 23.83 +MOT, 1440, 1563, 1443, 1511 +CTUN, 542, 0.00, 45.18, 0.000000, 0.00, 36, -12, 468, 0 +ATT, 3.46, 3.80, -27.96, -26.46, 0.00, 23.84, 23.83 +MOT, 1456, 1550, 1461, 1497 +GPS, 3, 109266200, 1774, 9, 2.43, -39.4923484, 176.7491084, 45.33, 88.67, 6.54, 20.06, 0.080000, 119213 +CTUN, 542, 0.00, 44.98, 0.000000, 0.00, 35, -16, 467, 0 +ATT, 3.39, 3.67, -27.75, -26.14, 0.10, 23.83, 23.83 +MOT, 1431, 1569, 1450, 1506 +CTUN, 542, 0.00, 45.16, 0.000000, 0.00, 35, -22, 467, 0 +ATT, 3.24, 3.29, -27.82, -26.34, 0.00, 23.86, 23.83 +MOT, 1452, 1547, 1404, 1551 +GPS, 3, 109266400, 1774, 9, 2.43, -39.4923372, 176.7491139, 45.26, 88.66, 6.64, 20.45, 0.120000, 119413 +CTUN, 542, 0.00, 45.23, 0.000000, 0.00, 34, -22, 466, 0 +ATT, 3.17, 3.15, -27.75, -25.91, 0.00, 24.09, 23.83 +MOT, 1484, 1510, 1486, 1482 +CTUN, 542, 0.00, 44.89, 0.000000, 0.00, 34, -27, 466, 0 +ATT, 3.17, 2.86, -27.53, -26.15, 0.00, 24.14, 23.83 +MOT, 1442, 1550, 1444, 1520 +GPS, 3, 109266600, 1774, 9, 2.43, -39.4923258, 176.7491194, 45.19, 88.65, 6.75, 20.59, 0.150000, 119613 +CTUN, 542, 0.00, 44.98, 0.000000, 0.00, 35, -31, 467, 0 +ATT, 3.24, 2.92, -27.60, -26.45, 0.20, 24.20, 23.83 +MOT, 1458, 1541, 1462, 1502 +CTUN, 542, 0.00, 44.85, 0.000000, 0.00, 36, -35, 468, 0 +ATT, 2.95, 2.87, -27.31, -26.58, 0.00, 24.23, 23.83 +MOT, 1445, 1550, 1455, 1514 +GPS, 3, 109266800, 1774, 9, 2.43, -39.4923143, 176.7491251, 45.08, 88.62, 6.83, 20.76, 0.190000, 119814 +CTUN, 542, 0.00, 44.88, 0.000000, 0.00, 35, -37, 467, 0 +ATT, 2.73, 2.41, -27.09, -26.45, 0.00, 24.23, 23.83 +MOT, 1419, 1569, 1481, 1485 +CTUN, 542, 0.00, 44.89, 0.000000, 0.00, 34, -33, 466, 0 +ATT, 1.94, 1.76, -26.44, -26.11, 0.00, 24.20, 23.83 +MOT, 1440, 1551, 1438, 1526 +DU32, 7, 270713 +CURR, 465, 196908, 1558, 3250, 4897, 337.5396 +GPS, 3, 109267000, 1774, 9, 2.43, -39.4923025, 176.7491308, 44.98, 88.60, 6.95, 20.68, 0.240000, 120014 +CTUN, 542, 0.00, 45.07, 0.000000, 0.00, 32, -29, 464, 0 +ATT, 0.57, 1.43, -26.00, -25.48, 0.00, 24.24, 23.83 +MOT, 1413, 1564, 1474, 1489 +CTUN, 542, 0.00, 45.15, 0.000000, 0.00, 31, -26, 463, 0 +ATT, 0.14, 0.70, -25.79, -24.93, 0.00, 24.21, 23.83 +MOT, 1415, 1571, 1430, 1518 +GPS, 3, 109267200, 1774, 9, 2.43, -39.4922905, 176.7491363, 44.94, 88.58, 7.04, 20.31, 0.220000, 120234 +CTUN, 542, 0.00, 45.00, 0.000000, 0.00, 28, -10, 460, 0 +ATT, 0.00, 0.03, -25.35, -23.81, 0.20, 24.12, 23.83 +MOT, 1444, 1550, 1434, 1499 +CTUN, 542, 0.00, 45.07, 0.000000, 0.00, 26, 2, 458, 0 +ATT, 0.00, -0.21, -25.13, -22.89, 0.00, 24.11, 23.83 +MOT, 1419, 1551, 1461, 1486 +GPS, 3, 109267400, 1774, 9, 2.43, -39.4922782, 176.7491419, 44.95, 88.56, 7.20, 19.83, 0.170000, 120415 +CTUN, 542, 0.00, 45.16, 0.000000, 0.00, 24, 20, 456, 0 +ATT, 0.00, -0.63, -25.13, -22.21, 0.10, 24.16, 23.83 +MOT, 1424, 1546, 1413, 1528 +CTUN, 542, 0.00, 45.02, 0.000000, 0.00, 22, 34, 454, 0 +ATT, 0.00, -0.70, -24.92, -21.57, 0.10, 24.05, 23.83 +MOT, 1453, 1532, 1449, 1474 +GPS, 3, 109267600, 1774, 9, 2.43, -39.4922656, 176.7491472, 45.03, 88.60, 7.31, 19.02, -0.010000, 120615 +CTUN, 542, 0.00, 45.34, 0.000000, 0.00, 22, 45, 454, 0 +ATT, 0.00, -0.64, -24.78, -21.39, 0.00, 23.89, 23.83 +MOT, 1421, 1551, 1439, 1490 +CTUN, 542, 0.00, 45.13, 0.000000, 0.00, 22, 52, 454, 0 +ATT, 0.00, -0.57, -24.71, -21.50, 0.10, 23.87, 23.83 +MOT, 1415, 1558, 1418, 1509 +GPS, 3, 109267800, 1774, 9, 2.43, -39.4922529, 176.7491522, 45.16, 88.71, 7.31, 18.07, -0.240000, 120815 +CTUN, 542, 0.00, 45.28, 0.000000, 0.00, 21, 60, 453, 0 +ATT, 0.00, -0.23, -24.71, -21.19, 0.00, 23.90, 23.83 +MOT, 1434, 1537, 1439, 1492 +CTUN, 542, 0.00, 45.26, 0.000000, 0.00, 21, 63, 453, 0 +ATT, 0.00, -0.11, -24.71, -21.07, 0.10, 23.98, 23.83 +MOT, 1432, 1533, 1438, 1499 +DU32, 7, 270713 +CURR, 453, 201483, 1547, 3050, 4918, 346.1808 +GPS, 3, 109268000, 1774, 9, 2.43, -39.4922400, 176.7491568, 45.31, 88.82, 7.33, 16.88, -0.350000, 121016 +CTUN, 542, 0.00, 45.51, 0.000000, 0.00, 21, 69, 453, 0 +ATT, 0.00, -0.07, -24.71, -20.84, 0.10, 24.00, 23.83 +MOT, 1417, 1550, 1439, 1492 +CTUN, 542, 0.00, 45.16, 0.000000, 0.00, 21, 76, 453, 0 +ATT, 0.00, 0.02, -24.71, -20.89, 0.10, 24.04, 23.83 +MOT, 1397, 1567, 1420, 1509 +GPS, 3, 109268200, 1774, 9, 2.43, -39.4922272, 176.7491610, 45.46, 88.99, 7.25, 15.56, -0.470000, 121216 +CTUN, 542, 0.00, 45.17, 0.000000, 0.00, 21, 79, 453, 0 +ATT, 0.00, 0.00, -24.49, -20.91, 0.20, 24.06, 23.83 +MOT, 1452, 1521, 1445, 1485 +CTUN, 542, 0.00, 45.58, 0.000000, 0.00, 20, 86, 452, 0 +ATT, 0.00, 0.06, -24.12, -20.54, 0.10, 24.08, 23.83 +MOT, 1416, 1547, 1410, 1521 +GPS, 3, 109268400, 1774, 9, 2.43, -39.4922143, 176.7491650, 45.63, 89.16, 7.29, 14.67, -0.610000, 121416 +CTUN, 542, 0.00, 45.63, 0.000000, 0.00, 20, 94, 452, 0 +ATT, 0.00, 0.05, -24.05, -20.45, 0.10, 24.11, 23.83 +MOT, 1420, 1539, 1451, 1486 +CTUN, 542, 0.00, 45.70, 0.000000, 0.00, 20, 100, 452, 0 +ATT, 0.00, -0.04, -24.05, -20.55, 0.20, 24.13, 23.83 +MOT, 1461, 1505, 1421, 1512 +GPS, 3, 109268600, 1774, 9, 2.43, -39.4922013, 176.7491688, 45.84, 89.36, 7.31, 13.73, -0.730000, 121616 +CTUN, 542, 0.00, 45.77, 0.000000, 0.00, 21, 105, 453, 0 +ATT, 0.00, -0.11, -24.05, -20.86, 0.10, 24.16, 23.83 +MOT, 1454, 1515, 1428, 1508 +CTUN, 544, 0.00, 45.94, 0.000000, 0.00, 21, 106, 455, 0 +ATT, 0.00, 0.06, -23.83, -21.20, 0.10, 24.22, 23.83 +MOT, 1412, 1552, 1471, 1471 +GPS, 3, 109268800, 1774, 9, 2.43, -39.4921882, 176.7491721, 46.07, 89.59, 7.29, 12.63, -0.850000, 121817 +CTUN, 550, 0.00, 46.28, 0.000000, 0.00, 23, 106, 465, 0 +ATT, 0.00, 0.22, -23.83, -21.65, 0.20, 24.13, 23.83 +MOT, 1482, 1520, 1478, 1478 +CTUN, 552, 0.00, 46.05, 0.000000, 0.00, 24, 106, 468, 0 +ATT, 0.00, 0.29, -23.83, -21.70, 0.10, 24.13, 23.83 +MOT, 1434, 1558, 1417, 1548 +DU32, 7, 270713 +CURR, 467, 206034, 1595, 3357, 4918, 354.6142 +GPS, 3, 109269000, 1774, 9, 2.43, -39.4921752, 176.7491753, 46.30, 89.80, 7.30, 11.85, -0.880000, 122016 +CTUN, 553, 0.00, 46.13, 0.000000, 0.00, 23, 113, 468, 0 +ATT, 0.00, 0.21, -23.83, -21.57, 0.20, 24.13, 23.83 +MOT, 1413, 1581, 1441, 1521 +CTUN, 558, 0.00, 46.46, 0.000000, 0.00, 23, 114, 474, 0 +ATT, 0.00, 0.13, -23.83, -21.61, 0.10, 24.01, 23.83 +MOT, 1458, 1559, 1490, 1481 +GPS, 3, 109269200, 1774, 9, 2.43, -39.4921620, 176.7491780, 46.54, 90.05, 7.28, 10.46, -0.950000, 122217 +CTUN, 561, 0.00, 46.24, 0.000000, 0.00, 24, 117, 479, 0 +ATT, 0.00, -0.41, -23.90, -21.43, 0.20, 23.98, 23.83 +MOT, 1440, 1576, 1455, 1532 +CTUN, 561, 0.00, 46.74, 0.000000, 0.00, 24, 124, 479, 0 +ATT, 0.00, -0.51, -24.05, -21.43, 0.10, 23.99, 23.83 +MOT, 1443, 1570, 1444, 1543 +GPS, 3, 109269400, 1774, 9, 2.43, -39.4921488, 176.7491805, 46.79, 90.29, 7.37, 9.49, -1.020000, 122417 +CTUN, 561, 0.00, 47.16, 0.000000, 0.00, 23, 138, 478, 0 +ATT, 0.00, -0.34, -24.05, -20.96, 0.10, 24.01, 23.83 +MOT, 1441, 1572, 1494, 1494 +CTUN, 563, 0.00, 47.01, 0.000000, 0.00, 23, 147, 481, 0 +ATT, 0.00, -0.27, -24.27, -20.79, 0.20, 24.04, 23.83 +MOT, 1427, 1590, 1468, 1524 +GPS, 3, 109269600, 1774, 9, 2.43, -39.4921353, 176.7491829, 47.13, 90.56, 7.46, 8.68, -1.130000, 122618 +CTUN, 571, 0.00, 47.05, 0.000000, 0.00, 23, 159, 491, 0 +ATT, 0.00, -0.40, -24.27, -20.86, 0.10, 24.03, 23.83 +MOT, 1474, 1566, 1451, 1558 +CTUN, 571, 0.00, 46.79, 0.000000, 0.00, 22, 173, 490, 0 +ATT, 0.00, -0.39, -24.27, -20.29, 0.20, 23.98, 23.83 +MOT, 1463, 1574, 1494, 1519 +GPS, 3, 109269800, 1774, 9, 2.43, -39.4921219, 176.7491851, 47.47, 90.86, 7.47, 8.03, -1.310000, 122818 +CTUN, 571, 0.00, 47.46, 0.000000, 0.00, 22, 188, 490, 0 +ATT, 0.00, -0.08, -24.78, -20.45, 0.00, 24.06, 23.83 +MOT, 1465, 1569, 1494, 1523 +CTUN, 571, 0.00, 47.80, 0.000000, 0.00, 24, 186, 492, 0 +ATT, 0.00, 0.24, -24.49, -21.45, 0.10, 24.13, 23.83 +MOT, 1425, 1605, 1473, 1542 +DU32, 7, 270713 +CURR, 493, 210838, 1552, 3677, 4940, 364.2424 +GPS, 3, 109270000, 1774, 9, 2.43, -39.4921083, 176.7491870, 47.87, 91.22, 7.51, 7.19, -1.520000, 123018 +CTUN, 571, 0.00, 47.63, 0.000000, 0.00, 25, 185, 493, 0 +ATT, 0.00, -0.01, -24.49, -21.58, 0.00, 24.09, 23.83 +MOT, 1512, 1545, 1484, 1530 +CTUN, 571, 0.00, 48.25, 0.000000, 0.00, 26, 188, 494, 0 +ATT, 0.00, 0.20, -24.71, -21.94, 0.10, 23.86, 23.83 +MOT, 1458, 1593, 1462, 1544 +GPS, 3, 109270200, 1774, 9, 2.43, -39.4920949, 176.7491887, 48.27, 91.57, 7.45, 6.35, -1.640000, 123218 +CTUN, 571, 0.00, 48.51, 0.000000, 0.00, 26, 189, 494, 0 +ATT, 0.00, 0.46, -24.27, -22.18, 0.00, 23.69, 23.83 +MOT, 1474, 1584, 1478, 1528 +CTUN, 568, 0.00, 48.76, 0.000000, 0.00, 25, 196, 489, 0 +ATT, 0.00, 0.02, -23.83, -21.51, 0.00, 23.55, 23.83 +MOT, 1475, 1575, 1478, 1518 +GPS, 3, 109270400, 1774, 9, 2.43, -39.4920815, 176.7491902, 48.71, 91.95, 7.33, 5.71, -1.600000, 123419 +CTUN, 568, 0.00, 48.67, 0.000000, 0.00, 23, 209, 487, 0 +ATT, 0.00, 0.17, -24.12, -20.88, 0.20, 23.52, 23.83 +MOT, 1451, 1581, 1469, 1534 +CTUN, 568, 0.00, 48.70, 0.000000, 0.00, 22, 221, 486, 0 +ATT, 0.00, 0.07, -23.83, -20.12, 0.00, 23.68, 23.83 +MOT, 1475, 1559, 1446, 1551 +GPS, 3, 109270600, 1774, 9, 2.43, -39.4920682, 176.7491915, 49.17, 92.37, 7.30, 5.11, -1.710000, 123619 +CTUN, 568, 0.00, 49.59, 0.000000, 0.00, 19, 237, 483, 0 +ATT, 0.00, 0.26, -24.05, -19.21, 0.10, 23.82, 23.83 +MOT, 1480, 1550, 1471, 1528 +CTUN, 568, 0.00, 49.23, 0.000000, 0.00, 19, 254, 483, 0 +ATT, 0.00, 0.22, -24.05, -18.75, 0.00, 23.98, 23.83 +MOT, 1430, 1586, 1433, 1560 +GPS, 3, 109270800, 1774, 9, 2.43, -39.4920549, 176.7491926, 49.72, 92.84, 7.26, 4.48, -1.920000, 123820 +CTUN, 568, 0.00, 49.49, 0.000000, 0.00, 17, 269, 481, 0 +ATT, 0.00, 0.12, -24.49, -18.38, 0.00, 24.05, 23.83 +MOT, 1466, 1559, 1462, 1529 +CTUN, 569, 0.00, 50.03, 0.000000, 0.00, 18, 274, 483, 0 +ATT, 0.00, 0.38, -24.92, -18.69, 0.00, 24.11, 23.83 +MOT, 1470, 1556, 1474, 1526 +DU32, 7, 270713 +CURR, 484, 215710, 1495, 3305, 4897, 373.9483 +PM, 0, 0, 0, 1000, 10230, 0, 0, 0, 0 +GPS, 3, 109271000, 1774, 9, 2.43, -39.4920420, 176.7491935, 50.29, 93.36, 7.13, 3.90, -2.240000, 124020 +CTUN, 568, 0.00, 50.38, 0.000000, 0.00, 19, 279, 483, 0 +ATT, 0.00, 0.48, -24.34, -19.46, 0.00, 24.08, 23.83 +MOT, 1505, 1530, 1486, 1512 +CTUN, 569, 0.00, 50.47, 0.000000, 0.00, 21, 279, 486, 0 +ATT, 0.00, 0.54, -24.92, -20.34, 0.00, 23.95, 23.83 +MOT, 1481, 1562, 1454, 1537 +GPS, 3, 109271200, 1774, 9, 2.43, -39.4920292, 176.7491943, 50.89, 93.90, 7.02, 3.38, -2.430000, 124220 +CTUN, 568, 0.00, 50.71, 0.000000, 0.00, 24, 271, 488, 0 +ATT, 0.00, 0.66, -26.95, -21.78, 0.00, 23.78, 23.83 +MOT, 1486, 1563, 1491, 1505 +CTUN, 569, 0.00, 50.72, 0.000000, 0.00, 29, 263, 494, 0 +ATT, 0.00, 0.60, -27.96, -23.57, 0.00, 23.60, 23.83 +MOT, 1501, 1563, 1481, 1525 +GPS, 3, 109271400, 1774, 9, 2.43, -39.4920167, 176.7491950, 51.42, 94.45, 6.87, 2.81, -2.480000, 124421 +CTUN, 569, 0.00, 51.08, 0.000000, 0.00, 34, 252, 499, 0 +ATT, 0.00, 0.28, -25.13, -25.35, 0.10, 23.38, 23.83 +MOT, 1553, 1528, 1548, 1459 +CTUN, 568, 0.00, 51.22, 0.000000, 0.00, 35, 248, 499, 0 +ATT, 0.00, 0.18, -21.22, -25.12, 0.00, 23.26, 23.83 +MOT, 1488, 1583, 1489, 1526 +GPS, 3, 109271600, 1774, 9, 2.43, -39.4920041, 176.7491956, 51.91, 94.94, 6.92, 2.55, -2.370000, 124621 +CTUN, 569, 0.00, 51.33, 0.000000, 0.00, 32, 246, 497, 0 +ATT, 0.00, -0.15, -21.00, -24.00, 0.20, 23.13, 23.83 +MOT, 1534, 1549, 1464, 1536 +CTUN, 568, 0.00, 51.82, 0.000000, 0.00, 28, 240, 492, 0 +ATT, 0.00, -0.06, -22.09, -22.74, 0.00, 23.10, 23.83 +MOT, 1472, 1586, 1485, 1513 +GPS, 3, 109271800, 1774, 9, 2.43, -39.4919916, 176.7491961, 52.37, 95.44, 6.91, 2.11, -2.320000, 124821 +CTUN, 569, 0.00, 52.34, 0.000000, 0.00, 26, 240, 491, 0 +ATT, 0.00, 0.04, -21.66, -21.79, 0.10, 23.00, 23.83 +MOT, 1520, 1548, 1472, 1522 +CTUN, 568, 0.00, 52.29, 0.000000, 0.00, 24, 247, 488, 0 +ATT, 0.00, -0.05, -22.53, -21.00, 0.00, 23.14, 23.83 +MOT, 1476, 1566, 1462, 1537 +DU32, 7, 270713 +CURR, 486, 220625, 1544, 3491, 4940, 383.6895 +GPS, 3, 109272000, 1774, 9, 2.43, -39.4919788, 176.7491965, 52.94, 95.89, 7.09, 1.77, -2.280000, 125041 +CTUN, 569, 0.00, 52.41, 0.000000, 0.00, 22, 258, 487, 0 +ATT, 0.00, 0.05, -22.53, -20.18, 0.00, 23.41, 23.83 +MOT, 1461, 1573, 1470, 1533 +CTUN, 568, 0.00, 53.04, 0.000000, 0.00, 20, 269, 484, 0 +ATT, 0.00, 0.16, -22.75, -19.60, 0.00, 23.54, 23.83 +MOT, 1499, 1541, 1463, 1530 +GPS, 3, 109272200, 1774, 9, 2.43, -39.4919661, 176.7491968, 53.42, 96.40, 6.98, 1.41, -2.340000, 125222 +CTUN, 568, 0.00, 53.34, 0.000000, 0.00, 20, 276, 484, 0 +ATT, 0.00, 0.31, -22.75, -19.53, 0.00, 23.58, 23.83 +MOT, 1477, 1564, 1453, 1533 +CTUN, 569, 0.00, 53.55, 0.000000, 0.00, 20, 276, 485, 0 +ATT, 0.00, 0.62, -22.75, -19.49, 0.00, 23.62, 23.83 +MOT, 1459, 1576, 1469, 1525 +GPS, 3, 109272400, 1774, 9, 2.43, -39.4919535, 176.7491972, 54.00, 96.94, 6.94, 1.35, -2.460000, 125422 +CTUN, 568, 0.00, 53.79, 0.000000, 0.00, 20, 275, 484, 0 +ATT, 0.00, 0.59, -22.75, -19.70, 0.10, 23.63, 23.83 +MOT, 1483, 1552, 1465, 1530 +CTUN, 568, 0.00, 53.99, 0.000000, 0.00, 21, 277, 485, 0 +ATT, 0.00, 0.53, -22.75, -19.96, 0.00, 23.66, 23.83 +MOT, 1472, 1569, 1469, 1521 +GPS, 3, 109272600, 1774, 9, 2.43, -39.4919414, 176.7491974, 54.57, 97.47, 6.73, 1.02, -2.520000, 125622 +CTUN, 569, 0.00, 54.04, 0.000000, 0.00, 22, 276, 487, 0 +ATT, 0.00, 0.56, -22.75, -20.39, 0.00, 23.61, 23.83 +MOT, 1473, 1575, 1478, 1512 +CTUN, 568, 0.00, 54.57, 0.000000, 0.00, 23, 269, 487, 0 +ATT, 0.00, 0.12, -22.75, -20.74, 0.00, 23.62, 23.83 +MOT, 1432, 1596, 1465, 1537 +GPS, 3, 109272800, 1774, 9, 2.43, -39.4919294, 176.7491975, 55.11, 98.01, 6.59, 0.68, -2.520000, 125822 +CTUN, 569, 0.00, 54.70, 0.000000, 0.00, 22, 272, 487, 0 +ATT, 0.00, -0.12, -22.75, -20.47, 0.10, 23.71, 23.83 +MOT, 1475, 1562, 1469, 1534 +CTUN, 569, 0.00, 55.02, 0.000000, 0.00, 21, 280, 486, 0 +ATT, 0.00, -0.17, -22.75, -19.98, 0.00, 23.70, 23.83 +MOT, 1489, 1551, 1446, 1548 +DU32, 7, 270713 +CURR, 486, 225480, 1570, 3487, 4876, 393.2772 +GPS, 3, 109273000, 1774, 9, 2.43, -39.4919178, 176.7491974, 55.66, 98.52, 6.41, 0.20, -2.480000, 126023 +CTUN, 568, 0.00, 55.13, 0.000000, 0.00, 20, 292, 484, 0 +ATT, 0.00, 0.08, -22.96, -19.78, 0.00, 23.67, 23.83 +MOT, 1479, 1557, 1458, 1534 +CTUN, 569, 0.00, 55.30, 0.000000, 0.00, 21, 294, 486, 0 +ATT, 0.00, 0.18, -23.40, -20.19, 0.00, 23.65, 23.83 +MOT, 1461, 1578, 1472, 1522 +GPS, 3, 109273200, 1774, 9, 2.43, -39.4919063, 176.7491973, 56.22, 99.07, 6.36, 359.91, -2.580000, 126223 +CTUN, 569, 0.00, 56.00, 0.000000, 0.00, 22, 289, 487, 0 +ATT, 0.00, 0.07, -24.27, -20.64, 0.00, 23.67, 23.83 +MOT, 1489, 1551, 1471, 1532 +CTUN, 568, 0.00, 56.04, 0.000000, 0.00, 24, 288, 488, 0 +ATT, 0.00, 0.11, -24.49, -21.33, 0.00, 23.72, 23.83 +MOT, 1509, 1539, 1480, 1524 +GPS, 3, 109273400, 1774, 9, 2.43, -39.4918948, 176.7491971, 56.80, 99.63, 6.36, 359.51, -2.700000, 126423 +CTUN, 568, 0.00, 56.46, 0.000000, 0.00, 26, 284, 490, 0 +ATT, 0.00, 0.28, -24.71, -22.38, 0.00, 23.74, 23.83 +MOT, 1472, 1574, 1465, 1537 +CTUN, 568, 0.00, 56.91, 0.000000, 0.00, 28, 274, 492, 0 +ATT, 0.00, 0.05, -24.92, -23.15, 0.00, 23.73, 23.83 +MOT, 1473, 1578, 1474, 1532 +GPS, 3, 109273600, 1774, 9, 2.43, -39.4918835, 176.7491967, 57.36, 100.20, 6.26, 359.03, -2.720000, 126623 +CTUN, 568, 0.00, 57.38, 0.000000, 0.00, 29, 267, 493, 0 +ATT, 0.00, -0.21, -24.92, -23.60, 0.20, 23.55, 23.83 +MOT, 1490, 1578, 1504, 1490 +CTUN, 568, 0.00, 57.26, 0.000000, 0.00, 31, 261, 495, 0 +ATT, 0.00, -0.39, -24.92, -23.92, 0.00, 23.39, 23.83 +MOT, 1486, 1578, 1468, 1537 +GPS, 3, 109273800, 1774, 9, 2.43, -39.4918724, 176.7491961, 57.91, 100.73, 6.19, 358.47, -2.610000, 126824 +CTUN, 568, 0.00, 57.63, 0.000000, 0.00, 32, 260, 496, 0 +ATT, 0.00, -0.13, -25.13, -24.26, 0.10, 23.28, 23.83 +MOT, 1465, 1597, 1442, 1556 +CTUN, 568, 0.00, 58.32, 0.000000, 0.00, 32, 257, 496, 0 +ATT, 0.00, 0.05, -25.13, -24.22, 0.20, 23.25, 23.83 +MOT, 1496, 1573, 1481, 1525 +DU32, 7, 270713 +CURR, 496, 230388, 1537, 3598, 4918, 403.0589 +GPS, 3, 109274000, 1774, 9, 2.43, -39.4918613, 176.7491953, 58.45, 101.24, 6.15, 357.74, -2.500000, 127024 +CTUN, 569, 0.00, 58.26, 0.000000, 0.00, 32, 251, 497, 0 +ATT, 0.00, 0.02, -25.13, -24.33, 0.00, 23.25, 23.83 +MOT, 1464, 1600, 1490, 1519 +CTUN, 569, 0.00, 58.45, 0.000000, 0.00, 33, 246, 498, 0 +ATT, 0.00, 0.02, -24.92, -24.70, 0.00, 23.19, 23.83 +MOT, 1461, 1602, 1474, 1537 +GPS, 3, 109274200, 1774, 9, 2.43, -39.4918501, 176.7491945, 58.96, 101.75, 6.18, 357.28, -2.430000, 127224 +CTUN, 569, 0.00, 58.65, 0.000000, 0.00, 32, 243, 497, 0 +ATT, 0.00, -0.08, -25.13, -24.32, 0.00, 23.26, 23.83 +MOT, 1479, 1583, 1475, 1537 +CTUN, 568, 0.00, 58.93, 0.000000, 0.00, 32, 249, 496, 0 +ATT, 0.00, 0.03, -25.79, -24.35, 0.00, 23.30, 23.83 +MOT, 1473, 1592, 1474, 1532 +GPS, 3, 109274400, 1774, 9, 2.43, -39.4918388, 176.7491937, 59.45, 102.24, 6.23, 357.08, -2.350000, 127425 +CTUN, 568, 0.00, 59.15, 0.000000, 0.00, 33, 245, 497, 0 +ATT, 0.00, 0.19, -25.79, -24.71, 0.20, 23.36, 23.83 +MOT, 1437, 1621, 1432, 1566 +CTUN, 569, 0.00, 58.98, 0.000000, 0.00, 33, 244, 498, 0 +ATT, 0.00, 0.29, -28.69, -24.81, 0.00, 23.23, 23.83 +MOT, 1486, 1591, 1504, 1498 +GPS, 3, 109274600, 1774, 9, 2.43, -39.4918275, 176.7491929, 59.92, 102.73, 6.27, 357.01, -2.330000, 127625 +CTUN, 568, 0.00, 59.77, 0.000000, 0.00, 37, 235, 501, 0 +ATT, 0.00, 0.40, -28.69, -26.14, 0.00, 23.08, 23.83 +MOT, 1470, 1607, 1482, 1532 +CTUN, 568, 0.00, 59.72, 0.000000, 0.00, 40, 225, 504, 0 +ATT, 0.00, 0.38, -28.03, -27.12, 0.00, 22.99, 23.83 +MOT, 1518, 1578, 1500, 1517 +GPS, 3, 109274800, 1774, 9, 2.43, -39.4918161, 176.7491922, 60.37, 103.18, 6.37, 357.08, -2.270000, 127825 +CTUN, 568, 0.00, 59.97, 0.000000, 0.00, 42, 212, 506, 0 +ATT, 0.00, 0.49, -28.03, -27.21, 0.00, 22.88, 23.83 +MOT, 1493, 1601, 1432, 1576 +CTUN, 569, 0.00, 59.81, 0.000000, 0.00, 40, 209, 505, 0 +ATT, 0.00, 0.92, -28.03, -26.89, 0.00, 22.77, 23.83 +MOT, 1469, 1616, 1512, 1510 +DU32, 7, 270713 +CURR, 504, 235382, 1516, 3698, 4962, 413.1130 +GPS, 3, 109275000, 1774, 9, 2.43, -39.4918045, 176.7491915, 60.76, 103.62, 6.41, 357.22, -2.140000, 128026 +CTUN, 568, 0.00, 60.23, 0.000000, 0.00, 40, 212, 504, 0 +ATT, 0.00, 0.97, -29.05, -26.92, 0.00, 22.63, 23.83 +MOT, 1531, 1572, 1469, 1539 +CTUN, 568, 0.00, 60.35, 0.000000, 0.00, 41, 211, 505, 0 +ATT, 0.00, 1.05, -28.91, -27.03, 0.00, 22.57, 23.83 +MOT, 1512, 1589, 1453, 1553 +GPS, 3, 109275200, 1774, 9, 2.43, -39.4917927, 176.7491912, 61.14, 104.01, 6.55, 357.96, -2.020000, 128226 +CTUN, 568, 0.00, 60.98, 0.000000, 0.00, 40, 212, 504, 0 +ATT, 0.00, 1.33, -28.62, -26.97, 0.00, 22.52, 23.83 +MOT, 1506, 1590, 1499, 1514 +CTUN, 569, 0.00, 60.88, 0.000000, 0.00, 40, 217, 505, 0 +ATT, 0.00, 1.26, -28.62, -26.84, 0.00, 22.57, 23.83 +MOT, 1514, 1584, 1496, 1521 +GPS, 3, 109275400, 1774, 9, 2.43, -39.4917807, 176.7491914, 61.57, 104.42, 6.68, 359.23, -2.030000, 128426 +CTUN, 568, 0.00, 61.15, 0.000000, 0.00, 41, 219, 505, 0 +ATT, 0.00, 1.00, -26.88, -27.02, 0.20, 22.64, 23.83 +MOT, 1495, 1597, 1444, 1564 +CTUN, 568, 0.00, 61.66, 0.000000, 0.00, 38, 220, 502, 0 +ATT, 0.00, 0.98, -25.57, -26.11, 0.00, 22.76, 23.83 +MOT, 1495, 1589, 1486, 1530 +GPS, 3, 109275600, 1774, 9, 2.43, -39.4917684, 176.7491919, 62.00, 104.84, 6.83, 0.70, -2.060000, 128626 +CTUN, 569, 0.00, 61.47, 0.000000, 0.00, 35, 221, 500, 0 +ATT, 0.86, 0.83, -25.13, -25.10, 0.10, 22.93, 23.83 +MOT, 1481, 1590, 1498, 1523 +CTUN, 569, 0.00, 62.01, 0.000000, 0.00, 32, 225, 497, 0 +ATT, 2.38, 0.80, -25.13, -24.00, 0.00, 23.07, 23.83 +MOT, 1505, 1568, 1441, 1559 +GPS, 3, 109275800, 1774, 9, 2.43, -39.4917559, 176.7491928, 62.44, 105.26, 6.94, 1.96, -2.060000, 128827 +CTUN, 569, 0.00, 61.77, 0.000000, 0.00, 30, 235, 495, 0 +ATT, 1.65, 1.51, -27.53, -23.32, 0.10, 23.24, 23.83 +MOT, 1443, 1610, 1474, 1533 +CTUN, 568, 0.00, 62.56, 0.000000, 0.00, 30, 240, 494, 0 +ATT, 2.38, 1.84, -28.40, -23.80, 0.10, 23.32, 23.83 +MOT, 1443, 1611, 1463, 1537 +GPS, 3, 109276000, 1774, 9, 2.43, -39.4917433, 176.7491939, 62.86, 105.70, 7.01, 2.91, -2.140000, 129007 +DU32, 7, 270713 +CURR, 496, 240398, 1538, 3602, 4940, 423.3008 +CTUN, 568, 0.00, 62.43, 0.000000, 0.00, 31, 247, 495, 0 +ATT, 3.02, 2.06, -28.84, -24.13, 0.00, 23.55, 23.83 +MOT, 1463, 1592, 1480, 1530 +CTUN, 569, 0.00, 62.49, 0.000000, 0.00, 33, 249, 498, 0 +ATT, 4.25, 2.54, -28.62, -24.59, 0.10, 23.70, 23.83 +MOT, 1484, 1579, 1505, 1514 +GPS, 3, 109276200, 1774, 9, 2.43, -39.4917306, 176.7491952, 63.38, 106.17, 7.05, 3.62, -2.210000, 129227 +CTUN, 568, 0.00, 63.33, 0.000000, 0.00, 35, 247, 499, 0 +ATT, 4.25, 3.27, -27.75, -25.08, 0.10, 23.76, 23.83 +MOT, 1506, 1565, 1505, 1514 +CTUN, 568, 0.00, 63.70, 0.000000, 0.00, 36, 243, 500, 0 +ATT, 4.32, 3.72, -27.16, -25.40, 0.00, 23.69, 23.83 +MOT, 1494, 1580, 1479, 1539 +GPS, 3, 109276400, 1774, 9, 2.43, -39.4917180, 176.7491967, 63.90, 106.65, 7.01, 4.57, -2.270000, 129428 +CTUN, 568, 0.00, 63.72, 0.000000, 0.00, 36, 237, 500, 0 +ATT, 4.54, 4.03, -26.22, -25.45, 0.00, 23.61, 23.83 +MOT, 1482, 1587, 1482, 1538 +CTUN, 568, 0.00, 64.07, 0.000000, 0.00, 35, 235, 499, 0 +ATT, 4.47, 4.19, -26.00, -24.94, 0.00, 23.55, 23.83 +MOT, 1485, 1585, 1492, 1523 +GPS, 3, 109276600, 1774, 9, 2.43, -39.4917053, 176.7491985, 64.40, 107.13, 7.02, 5.49, -2.250000, 129628 +CTUN, 568, 0.00, 64.23, 0.000000, 0.00, 34, 239, 498, 0 +ATT, 3.81, 4.28, -27.53, -24.45, 0.00, 23.62, 23.83 +MOT, 1480, 1589, 1468, 1540 +CTUN, 568, 0.00, 65.16, 0.000000, 0.00, 33, 241, 497, 0 +ATT, 3.89, 4.37, -28.62, -24.53, 0.00, 23.66, 23.83 +MOT, 1508, 1566, 1454, 1549 +GPS, 3, 109276800, 1774, 9, 2.43, -39.4916928, 176.7492006, 64.93, 107.60, 6.96, 6.42, -2.200000, 129828 +CTUN, 568, 0.00, 64.32, 0.000000, 0.00, 35, 240, 499, 0 +ATT, 4.32, 4.01, -28.91, -25.04, 0.00, 23.74, 23.83 +MOT, 1482, 1587, 1482, 1532 +CTUN, 568, 0.00, 64.82, 0.000000, 0.00, 36, 234, 500, 0 +ATT, 4.32, 4.05, -30.13, -25.58, 0.00, 23.76, 23.83 +MOT, 1528, 1550, 1499, 1526 +DU32, 7, 270713 +CURR, 503, 245383, 1568, 3634, 4897, 433.3951 +GPS, 3, 109277000, 1774, 9, 2.43, -39.4916806, 176.7492030, 65.38, 108.05, 6.84, 7.44, -2.210000, 130028 +CTUN, 568, 0.00, 65.42, 0.000000, 0.00, 40, 228, 504, 0 +ATT, 3.46, 4.07, -29.99, -26.71, 0.10, 23.80, 23.83 +MOT, 1517, 1565, 1460, 1564 +CTUN, 568, 0.00, 65.67, 0.000000, 0.00, 42, 220, 506, 0 +ATT, 2.95, 3.93, -30.21, -27.35, 0.00, 23.87, 23.83 +MOT, 1493, 1587, 1515, 1523 +GPS, 3, 109277200, 1774, 9, 2.43, -39.4916683, 176.7492055, 65.86, 108.51, 6.82, 8.35, -2.130000, 130229 +CTUN, 569, 0.00, 65.51, 0.000000, 0.00, 44, 209, 509, 0 +ATT, 2.80, 3.36, -29.78, -27.91, 0.00, 23.78, 23.83 +MOT, 1514, 1576, 1497, 1543 +CTUN, 568, 0.00, 66.07, 0.000000, 0.00, 45, 202, 509, 0 +ATT, 2.38, 3.04, -29.78, -28.27, 0.00, 23.74, 23.83 +MOT, 1510, 1581, 1486, 1550 +GPS, 3, 109277400, 1774, 9, 2.43, -39.4916562, 176.7492083, 66.28, 108.94, 6.75, 9.30, -2.050000, 130429 +CTUN, 568, 0.00, 66.48, 0.000000, 0.00, 46, 196, 510, 0 +ATT, 2.38, 2.74, -29.05, -28.46, 0.10, 23.78, 23.83 +MOT, 1501, 1592, 1495, 1541 +CTUN, 571, 0.00, 66.14, 0.000000, 0.00, 46, 187, 514, 0 +ATT, 2.30, 2.38, -28.84, -28.48, 0.00, 23.69, 23.83 +MOT, 1513, 1590, 1513, 1534 +GPS, 3, 109277600, 1774, 9, 2.43, -39.4916442, 176.7492114, 66.68, 109.32, 6.79, 10.15, -1.930000, 130629 +CTUN, 571, 0.00, 66.34, 0.000000, 0.00, 47, 172, 515, 0 +ATT, 2.16, 2.17, -29.12, -28.58, 0.10, 23.61, 23.83 +MOT, 1505, 1596, 1497, 1550 +CTUN, 571, 0.00, 66.74, 0.000000, 0.00, 46, 167, 514, 0 +ATT, 2.30, 1.96, -29.26, -28.48, 0.10, 23.56, 23.83 +MOT, 1514, 1591, 1506, 1537 +GPS, 3, 109277800, 1774, 9, 2.43, -39.4916323, 176.7492145, 67.01, 109.68, 6.72, 10.70, -1.780000, 130829 +CTUN, 569, 0.00, 66.98, 0.000000, 0.00, 46, 157, 511, 0 +ATT, 2.16, 1.83, -29.78, -28.64, 0.00, 23.46, 23.83 +MOT, 1514, 1584, 1499, 1540 +CTUN, 568, 0.00, 66.73, 0.000000, 0.00, 46, 151, 510, 0 +ATT, 2.09, 1.71, -29.92, -28.72, 0.00, 23.38, 23.83 +MOT, 1516, 1586, 1480, 1548 +DU32, 7, 270713 +CURR, 515, 250493, 1539, 3685, 4897, 443.7743 +GPS, 3, 109278000, 1774, 9, 2.43, -39.4916203, 176.7492177, 67.34, 109.99, 6.83, 11.08, -1.640000, 131050 +CTUN, 571, 0.00, 67.34, 0.000000, 0.00, 47, 145, 512, 0 +ATT, 2.09, 1.73, -29.99, -28.66, 0.10, 23.35, 23.83 +MOT, 1532, 1572, 1494, 1544 +CTUN, 568, 0.00, 66.91, 0.000000, 0.00, 47, 139, 511, 0 +ATT, 2.16, 1.88, -29.99, -28.98, 0.10, 23.33, 23.83 +MOT, 1516, 1586, 1484, 1548 +GPS, 3, 109278200, 1774, 10, 1.65, -39.4916081, 176.7492208, 67.59, 110.30, 6.84, 11.09, -1.520000, 131230 +CTUN, 571, 0.00, 66.96, 0.000000, 0.00, 49, 133, 517, 0 +ATT, 2.38, 1.75, -29.99, -29.17, 0.10, 23.34, 23.83 +MOT, 1509, 1601, 1501, 1545 +CTUN, 571, 0.00, 67.39, 0.000000, 0.00, 49, 121, 517, 0 +ATT, 2.38, 1.72, -30.21, -29.35, 0.10, 23.34, 23.83 +MOT, 1518, 1592, 1509, 1541 +GPS, 3, 109278400, 1774, 10, 1.65, -39.4915959, 176.7492240, 67.80, 110.58, 6.91, 11.16, -1.410000, 131431 +CTUN, 571, 0.00, 67.64, 0.000000, 0.00, 49, 116, 517, 0 +ATT, 2.38, 1.59, -29.99, -29.26, 0.10, 23.32, 23.83 +MOT, 1524, 1591, 1485, 1555 +CTUN, 571, 0.00, 67.56, 0.000000, 0.00, 49, 118, 517, 0 +ATT, 2.30, 1.74, -29.99, -29.17, 0.10, 23.25, 23.83 +MOT, 1525, 1593, 1493, 1546 +GPS, 3, 109278600, 1774, 10, 1.65, -39.4915835, 176.7492272, 68.02, 110.82, 7.02, 11.21, -1.260000, 131631 +CTUN, 571, 0.00, 67.51, 0.000000, 0.00, 48, 109, 516, 0 +ATT, 2.59, 1.96, -30.21, -29.00, 0.10, 23.19, 23.83 +MOT, 1509, 1605, 1495, 1543 +CTUN, 571, 0.00, 67.68, 0.000000, 0.00, 48, 109, 516, 0 +ATT, 2.52, 2.16, -30.13, -28.83, 0.10, 23.13, 23.83 +MOT, 1509, 1605, 1494, 1544 +GPS, 3, 109278800, 1774, 10, 1.65, -39.4915708, 176.7492304, 68.20, 111.03, 7.16, 10.98, -1.130000, 131831 +CTUN, 578, 0.00, 68.17, 0.000000, 0.00, 48, 110, 524, 0 +ATT, 2.38, 2.24, -30.21, -28.70, 0.10, 23.07, 23.83 +MOT, 1501, 1625, 1506, 1546 +CTUN, 576, 0.00, 68.09, 0.000000, 0.00, 47, 108, 521, 0 +ATT, 2.38, 2.38, -30.21, -28.48, 0.10, 23.09, 23.83 +MOT, 1528, 1598, 1501, 1546 +DU32, 7, 270713 +CURR, 522, 255675, 1534, 4125, 4918, 454.4429 +GPS, 3, 109279000, 1774, 10, 1.65, -39.4915578, 176.7492336, 68.41, 111.25, 7.33, 10.84, -1.090000, 132031 +CTUN, 576, 0.00, 67.93, 0.000000, 0.00, 47, 109, 523, 0 +ATT, 2.59, 2.40, -30.21, -28.40, 0.20, 23.12, 23.83 +MOT, 1485, 1636, 1498, 1550 +CTUN, 578, 0.00, 67.90, 0.000000, 0.00, 46, 113, 522, 0 +ATT, 2.52, 2.44, -30.21, -28.10, 0.00, 23.12, 23.83 +MOT, 1536, 1593, 1506, 1542 +GPS, 3, 109279200, 1774, 10, 1.65, -39.4915446, 176.7492368, 68.59, 111.47, 7.45, 10.70, -1.080000, 132232 +CTUN, 578, 0.00, 68.57, 0.000000, 0.00, 46, 109, 523, 0 +ATT, 2.80, 2.48, -30.13, -28.06, 0.00, 23.12, 23.83 +MOT, 1481, 1638, 1504, 1547 +CTUN, 578, 0.00, 68.30, 0.000000, 0.00, 46, 108, 522, 0 +ATT, 2.59, 2.48, -30.21, -28.06, 0.10, 23.12, 23.83 +MOT, 1532, 1592, 1513, 1542 +GPS, 3, 109279400, 1774, 10, 1.65, -39.4915309, 176.7492401, 68.80, 111.74, 7.61, 10.66, -1.070000, 132432 +CTUN, 579, 0.00, 68.95, 0.000000, 0.00, 46, 113, 523, 0 +ATT, 2.30, 2.51, -30.35, -27.83, 0.10, 23.20, 23.83 +MOT, 1532, 1593, 1514, 1543 +CTUN, 578, 0.00, 68.51, 0.000000, 0.00, 46, 111, 522, 0 +ATT, 2.38, 2.47, -30.21, -28.03, 0.10, 23.27, 23.83 +MOT, 1494, 1623, 1486, 1563 +GPS, 3, 109279600, 1774, 10, 1.65, -39.4915172, 176.7492435, 69.02, 111.95, 7.73, 10.69, -1.050000, 132632 +CTUN, 579, 0.00, 68.72, 0.000000, 0.00, 45, 107, 522, 0 +ATT, 2.38, 2.53, -30.43, -27.93, 0.10, 23.37, 23.83 +MOT, 1514, 1605, 1516, 1541 +CTUN, 576, 0.00, 68.61, 0.000000, 0.00, 46, 109, 523, 0 +ATT, 2.52, 2.56, -30.35, -28.01, 0.10, 23.40, 23.83 +MOT, 1528, 1592, 1506, 1554 +GPS, 3, 109279800, 1774, 10, 1.65, -39.4915034, 176.7492469, 69.21, 112.21, 7.78, 10.76, -1.070000, 132832 +CTUN, 578, 0.00, 68.65, 0.000000, 0.00, 46, 109, 522, 0 +ATT, 3.02, 2.47, -30.86, -27.98, 0.20, 23.43, 23.83 +MOT, 1522, 1599, 1501, 1553 +CTUN, 577, 0.00, 69.43, 0.000000, 0.00, 46, 107, 521, 0 +ATT, 2.95, 2.53, -30.86, -28.11, 0.10, 23.37, 23.83 +MOT, 1508, 1615, 1491, 1553 +DU32, 7, 270713 +CURR, 521, 260896, 1532, 3928, 4918, 465.4024 +GPS, 3, 109280000, 1774, 10, 1.65, -39.4914893, 176.7492503, 69.40, 112.44, 7.91, 10.72, -1.040000, 133033 +CTUN, 579, 0.00, 69.47, 0.000000, 0.00, 46, 107, 523, 0 +ATT, 2.95, 2.71, -30.79, -28.02, 0.00, 23.35, 23.83 +MOT, 1515, 1608, 1486, 1564 +CTUN, 579, 0.00, 69.75, 0.000000, 0.00, 45, 119, 519, 0 +ATT, 2.80, 2.92, -30.64, -27.72, 0.00, 23.42, 23.83 +MOT, 1528, 1585, 1509, 1547 +GPS, 3, 109280200, 1774, 10, 1.65, -39.4914752, 176.7492538, 69.66, 112.67, 7.95, 10.94, -1.040000, 133233 +CTUN, 578, 0.00, 69.60, 0.000000, 0.00, 45, 120, 521, 0 +ATT, 2.59, 2.83, -30.64, -27.69, 0.10, 23.66, 23.83 +MOT, 1505, 1604, 1489, 1568 +CTUN, 587, 0.00, 69.39, 0.000000, 0.00, 45, 120, 529, 0 +ATT, 2.59, 2.89, -30.64, -27.53, 0.10, 23.82, 23.83 +MOT, 1520, 1604, 1541, 1539 +GPS, 3, 109280400, 1774, 10, 1.65, -39.4914608, 176.7492571, 69.91, 112.91, 8.03, 10.39, -1.050000, 133433 +CTUN, 587, 0.00, 69.81, 0.000000, 0.00, 45, 120, 532, 0 +ATT, 2.59, 2.95, -30.64, -27.44, 0.10, 23.88, 23.83 +MOT, 1532, 1603, 1497, 1576 +CTUN, 590, 0.00, 69.77, 0.000000, 0.00, 46, 121, 537, 0 +ATT, 2.59, 3.00, -30.57, -27.34, 0.10, 23.81, 23.83 +MOT, 1522, 1625, 1513, 1570 +GPS, 3, 109280600, 1774, 10, 1.65, -39.4914464, 176.7492604, 70.14, 113.18, 8.06, 10.36, -1.110000, 133634 +CTUN, 587, 0.00, 69.97, 0.000000, 0.00, 44, 123, 531, 0 +ATT, 2.52, 2.99, -30.86, -27.14, 0.00, 23.96, 23.83 +MOT, 1537, 1592, 1511, 1569 +CTUN, 587, 0.00, 69.89, 0.000000, 0.00, 44, 121, 531, 0 +ATT, 2.80, 3.06, -31.08, -27.08, 0.00, 24.06, 23.83 +MOT, 1526, 1604, 1510, 1568 +GPS, 3, 109280800, 1774, 10, 1.65, -39.4914320, 176.7492637, 70.38, 113.41, 8.06, 10.22, -1.070000, 133834 +CTUN, 587, 0.00, 70.61, 0.000000, 0.00, 43, 128, 530, 0 +ATT, 3.02, 2.93, -31.29, -26.85, 0.10, 23.89, 23.83 +MOT, 1533, 1605, 1510, 1556 +CTUN, 586, 0.00, 70.82, 0.000000, 0.00, 44, 133, 530, 0 +ATT, 2.95, 3.17, -31.44, -27.06, 0.00, 23.85, 23.83 +MOT, 1502, 1623, 1505, 1568 +DU32, 7, 270713 +CURR, 530, 266175, 1478, 3968, 4897, 476.5942 +PM, 0, 0, 0, 1001, 10258, 0, 0, 0, 0 +GPS, 3, 109281000, 1774, 10, 1.65, -39.4914177, 176.7492671, 70.68, 113.67, 8.01, 10.40, -1.100000, 134034 +CTUN, 587, 0.00, 70.62, 0.000000, 0.00, 44, 137, 530, 0 +ATT, 2.80, 3.17, -31.29, -27.02, 0.00, 23.94, 23.83 +MOT, 1518, 1607, 1504, 1572 +CTUN, 587, 0.00, 70.80, 0.000000, 0.00, 43, 145, 529, 0 +ATT, 3.24, 3.14, -30.86, -26.93, 0.10, 24.14, 23.83 +MOT, 1532, 1592, 1504, 1572 +GPS, 3, 109281200, 1774, 10, 1.65, -39.4914036, 176.7492704, 70.98, 113.94, 7.94, 10.25, -1.160000, 134234 +CTUN, 586, 0.00, 71.02, 0.000000, 0.00, 43, 145, 529, 0 +ATT, 3.60, 3.29, -31.51, -26.91, 0.00, 24.23, 23.83 +MOT, 1506, 1616, 1522, 1555 +CTUN, 587, 0.00, 71.04, 0.000000, 0.00, 44, 148, 531, 0 +ATT, 4.54, 3.40, -30.86, -26.99, 0.00, 24.19, 23.83 +MOT, 1509, 1619, 1516, 1561 +GPS, 3, 109281400, 1774, 10, 1.65, -39.4913894, 176.7492737, 71.30, 114.22, 7.93, 10.38, -1.220000, 134435 +CTUN, 586, 0.00, 71.26, 0.000000, 0.00, 43, 158, 529, 0 +ATT, 4.32, 3.75, -30.64, -26.51, 0.00, 24.14, 23.83 +MOT, 1499, 1624, 1500, 1570 +CTUN, 586, 0.00, 71.39, 0.000000, 0.00, 41, 166, 527, 0 +ATT, 4.32, 3.83, -30.43, -26.12, 0.00, 24.17, 23.83 +MOT, 1501, 1617, 1511, 1560 +GPS, 3, 109281600, 1774, 10, 1.65, -39.4913753, 176.7492770, 71.64, 114.51, 7.90, 10.29, -1.290000, 134635 +CTUN, 587, 0.00, 71.51, 0.000000, 0.00, 40, 173, 527, 0 +ATT, 3.39, 3.89, -29.12, -25.70, 0.00, 24.27, 23.83 +MOT, 1513, 1606, 1499, 1571 +CTUN, 586, 0.00, 71.75, 0.000000, 0.00, 38, 179, 524, 0 +ATT, 4.54, 3.81, -29.78, -24.91, 0.00, 24.39, 23.83 +MOT, 1470, 1632, 1523, 1550 +GPS, 3, 109281800, 1774, 10, 1.65, -39.4913613, 176.7492803, 72.01, 114.84, 7.85, 10.40, -1.390000, 134835 +CTUN, 586, 0.00, 72.11, 0.000000, 0.00, 36, 193, 522, 0 +ATT, 4.97, 4.07, -29.99, -24.39, 0.00, 24.41, 23.83 +MOT, 1493, 1614, 1499, 1563 +CTUN, 587, 0.00, 71.98, 0.000000, 0.00, 34, 209, 520, 0 +ATT, 4.32, 4.30, -29.99, -24.05, 0.00, 24.50, 23.83 +MOT, 1505, 1599, 1460, 1592 +DU32, 7, 270713 +CURR, 521, 271450, 1519, 4004, 4918, 487.8539 +GPS, 3, 109282000, 1774, 10, 1.65, -39.4913474, 176.7492837, 72.44, 115.18, 7.78, 10.66, -1.500000, 135035 +CTUN, 586, 0.00, 72.32, 0.000000, 0.00, 33, 216, 519, 0 +ATT, 2.09, 4.13, -30.35, -23.48, 0.20, 24.70, 23.83 +MOT, 1468, 1619, 1522, 1550 +CTUN, 586, 0.00, 72.26, 0.000000, 0.00, 32, 236, 519, 0 +ATT, 1.65, 3.32, -30.35, -23.29, 0.00, 24.84, 23.83 +MOT, 1464, 1624, 1486, 1574 +GPS, 3, 109282200, 1774, 10, 1.65, -39.4913336, 176.7492873, 72.90, 115.60, 7.75, 11.14, -1.760000, 135236 +CTUN, 587, 0.00, 72.47, 0.000000, 0.00, 31, 251, 517, 0 +ATT, 3.24, 2.80, -30.57, -22.92, 0.00, 24.92, 23.83 +MOT, 1486, 1601, 1498, 1565 +CTUN, 586, 0.00, 73.13, 0.000000, 0.00, 30, 275, 517, 0 +ATT, 4.69, 2.92, -31.22, -22.72, 0.20, 24.88, 23.83 +MOT, 1469, 1628, 1502, 1549 +GPS, 3, 109282400, 1774, 10, 1.65, -39.4913198, 176.7492909, 73.44, 116.07, 7.73, 11.25, -2.010000, 135436 +CTUN, 587, 0.00, 73.15, 0.000000, 0.00, 30, 295, 517, 0 +ATT, 3.46, 3.82, -31.51, -22.70, 0.00, 24.74, 23.83 +MOT, 1459, 1633, 1511, 1544 +CTUN, 586, 0.00, 73.68, 0.000000, 0.00, 31, 313, 518, 0 +ATT, 0.79, 3.47, -31.95, -22.90, 0.00, 24.69, 23.83 +MOT, 1552, 1552, 1413, 1627 +GPS, 3, 109282600, 1774, 10, 1.65, -39.4913061, 176.7492946, 74.08, 116.63, 7.66, 12.06, -2.340000, 135637 +CTUN, 585, 0.00, 74.09, 0.000000, 0.00, 31, 327, 516, 0 +ATT, 1.72, 2.63, -31.51, -23.20, 0.00, 24.59, 23.83 +MOT, 1477, 1621, 1461, 1578 +CTUN, 587, 0.00, 73.84, 0.000000, 0.00, 31, 347, 517, 0 +ATT, 1.08, 2.75, -30.86, -23.23, 0.00, 24.53, 23.83 +MOT, 1499, 1596, 1519, 1544 +GPS, 3, 109282800, 1774, 10, 1.65, -39.4912924, 176.7492984, 74.78, 117.27, 7.65, 12.34, -2.700000, 135837 +CTUN, 586, 0.00, 74.32, 0.000000, 0.00, 32, 356, 518, 0 +ATT, 0.64, 2.40, -30.64, -23.38, 0.20, 24.49, 23.83 +MOT, 1493, 1602, 1489, 1569 +CTUN, 587, 0.00, 75.00, 0.000000, 0.00, 33, 367, 520, 0 +ATT, 0.57, 1.97, -31.08, -23.90, 0.00, 24.46, 23.83 +MOT, 1493, 1610, 1474, 1579 +DU32, 7, 270713 +CURR, 521, 276626, 1518, 3935, 4918, 498.9821 +GPS, 3, 109283000, 1774, 10, 1.65, -39.4912789, 176.7493023, 75.51, 117.96, 7.59, 12.67, -3.030000, 136037 +CTUN, 587, 0.00, 74.87, 0.000000, 0.00, 34, 372, 521, 0 +ATT, 0.57, 1.70, -31.51, -24.46, 0.00, 24.36, 23.83 +MOT, 1533, 1579, 1508, 1555 +CTUN, 586, 0.00, 75.40, 0.000000, 0.00, 39, 366, 525, 0 +ATT, 1.50, 1.52, -31.51, -26.01, 0.10, 24.15, 23.83 +MOT, 1493, 1622, 1476, 1583 +GPS, 3, 109283200, 1774, 10, 1.65, -39.4912655, 176.7493062, 76.24, 118.68, 7.53, 13.10, -3.230000, 136237 +CTUN, 586, 0.00, 76.00, 0.000000, 0.00, 43, 354, 530, 0 +ATT, 2.09, 1.54, -31.44, -27.31, 0.10, 23.95, 23.83 +MOT, 1533, 1604, 1534, 1537 +CTUN, 587, 0.00, 76.07, 0.000000, 0.00, 48, 339, 535, 0 +ATT, 1.94, 1.43, -31.51, -28.30, 0.00, 23.72, 23.83 +MOT, 1514, 1630, 1525, 1552 +GPS, 3, 109283400, 1774, 10, 1.65, -39.4912522, 176.7493102, 76.93, 119.40, 7.46, 13.48, -3.280000, 136437 +CTUN, 587, 0.00, 76.19, 0.000000, 0.00, 51, 326, 538, 0 +ATT, 1.87, 1.24, -31.73, -29.23, 0.00, 23.46, 23.83 +MOT, 1561, 1597, 1506, 1569 +CTUN, 587, 0.00, 76.92, 0.000000, 0.00, 54, 309, 541, 0 +ATT, 1.87, 1.22, -31.73, -29.97, 0.20, 23.28, 23.83 +MOT, 1509, 1651, 1541, 1544 +GPS, 3, 109283600, 1774, 10, 1.65, -39.4912389, 176.7493141, 77.53, 120.05, 7.45, 12.97, -3.070000, 136638 +CTUN, 587, 0.00, 76.92, 0.000000, 0.00, 57, 295, 544, 0 +ATT, 2.09, 1.10, -31.95, -30.66, 0.00, 23.08, 23.83 +MOT, 1532, 1636, 1522, 1566 +CTUN, 586, 0.00, 77.62, 0.000000, 0.00, 58, 285, 544, 0 +ATT, 2.09, 0.90, -31.88, -30.97, 0.00, 23.02, 23.83 +MOT, 1545, 1620, 1541, 1552 +GPS, 3, 109283800, 1774, 10, 1.65, -39.4912256, 176.7493179, 78.10, 120.65, 7.48, 12.37, -2.870000, 136838 +CTUN, 585, 0.00, 77.84, 0.000000, 0.00, 61, 272, 548, 0 +ATT, 2.38, 0.92, -32.16, -31.47, 0.10, 22.98, 23.83 +MOT, 1547, 1624, 1541, 1558 +CTUN, 586, 0.00, 77.69, 0.000000, 0.00, 62, 252, 548, 0 +ATT, 2.80, 1.04, -32.16, -31.86, 0.20, 22.83, 23.83 +MOT, 1549, 1628, 1521, 1572 +DU32, 7, 270713 +CURR, 548, 281980, 1508, 4144, 4962, 510.2630 +GPS, 3, 109284000, 1774, 10, 1.65, -39.4912121, 176.7493214, 78.65, 121.20, 7.56, 11.48, -2.660000, 137057 +CTUN, 586, 0.00, 78.51, 0.000000, 0.00, 63, 244, 549, 0 +ATT, 3.46, 1.37, -32.09, -31.86, 0.00, 22.90, 23.83 +MOT, 1541, 1630, 1541, 1562 +CTUN, 587, 0.00, 78.55, 0.000000, 0.00, 63, 229, 550, 0 +ATT, 4.54, 1.76, -32.60, -31.89, 0.10, 22.90, 23.83 +MOT, 1526, 1648, 1537, 1566 +GPS, 3, 109284200, 1774, 10, 1.65, -39.4911985, 176.7493248, 79.07, 121.71, 7.66, 10.91, -2.440000, 137239 +CTUN, 587, 0.00, 78.69, 0.000000, 0.00, 64, 213, 551, 0 +ATT, 6.05, 2.67, -33.04, -32.00, 0.10, 22.98, 23.83 +MOT, 1543, 1633, 1548, 1556 +CTUN, 587, 0.00, 79.24, 0.000000, 0.00, 66, 201, 553, 0 +ATT, 6.49, 4.00, -33.04, -32.36, 0.00, 22.89, 23.83 +MOT, 1540, 1645, 1535, 1568 +GPS, 3, 109284400, 1774, 10, 1.65, -39.4911846, 176.7493280, 79.48, 122.14, 7.80, 10.17, -2.210000, 137439 +CTUN, 587, 0.00, 79.68, 0.000000, 0.00, 67, 182, 554, 0 +ATT, 6.70, 4.86, -33.47, -32.41, 0.00, 22.80, 23.83 +MOT, 1554, 1633, 1542, 1562 +CTUN, 586, 0.00, 79.32, 0.000000, 0.00, 68, 173, 555, 0 +ATT, 6.92, 5.69, -33.47, -32.57, 0.10, 22.80, 23.83 +MOT, 1542, 1644, 1555, 1552 +GPS, 3, 109284600, 1774, 10, 1.65, -39.4911707, 176.7493311, 79.85, 122.52, 7.86, 9.60, -1.990000, 137639 +CTUN, 586, 0.00, 80.32, 0.000000, 0.00, 69, 157, 555, 0 +ATT, 7.35, 6.11, -33.47, -32.65, 0.00, 22.97, 23.83 +MOT, 1530, 1651, 1533, 1579 +CTUN, 587, 0.00, 80.09, 0.000000, 0.00, 68, 151, 555, 0 +ATT, 7.35, 6.37, -33.47, -32.34, 0.00, 23.17, 23.83 +MOT, 1558, 1627, 1521, 1587 +GPS, 3, 109284800, 1774, 10, 1.65, -39.4911566, 176.7493343, 80.20, 122.84, 7.95, 9.72, -1.750000, 137840 +CTUN, 586, 0.00, 79.99, 0.000000, 0.00, 66, 148, 552, 0 +ATT, 7.79, 7.10, -33.69, -31.83, 0.10, 23.34, 23.83 +MOT, 1524, 1651, 1560, 1548 +CTUN, 586, 0.00, 79.75, 0.000000, 0.00, 65, 146, 552, 0 +ATT, 8.00, 7.14, -33.69, -31.50, 0.20, 23.44, 23.83 +MOT, 1547, 1629, 1526, 1581 +DU32, 7, 270713 +CURR, 550, 287497, 1527, 4405, 4984, 521.9993 +GPS, 3, 109285000, 1774, 10, 1.65, -39.4911424, 176.7493376, 80.48, 123.15, 8.03, 10.10, -1.570000, 138040 +CTUN, 586, 0.00, 80.08, 0.000000, 0.00, 64, 152, 550, 0 +ATT, 8.43, 7.36, -33.47, -31.29, 0.00, 23.58, 23.83 +MOT, 1544, 1626, 1526, 1581 +CTUN, 587, 0.00, 80.83, 0.000000, 0.00, 63, 149, 549, 0 +ATT, 8.65, 7.87, -33.47, -30.93, 0.00, 23.73, 23.83 +MOT, 1546, 1619, 1541, 1569 +GPS, 3, 109285200, 1774, 10, 1.65, -39.4911281, 176.7493415, 80.77, 123.41, 8.17, 11.58, -1.490000, 138240 +CTUN, 587, 0.00, 80.71, 0.000000, 0.00, 62, 143, 549, 0 +ATT, 8.43, 8.24, -33.47, -30.81, 0.00, 23.78, 23.83 +MOT, 1547, 1628, 1534, 1565 +CTUN, 587, 0.00, 80.85, 0.000000, 0.00, 63, 137, 550, 0 +ATT, 8.22, 8.56, -33.25, -30.97, 0.00, 23.66, 23.83 +MOT, 1550, 1624, 1520, 1581 +GPS, 3, 109285400, 1774, 10, 1.65, -39.4911135, 176.7493457, 81.07, 123.71, 8.26, 12.33, -1.450000, 138441 +CTUN, 586, 0.00, 81.13, 0.000000, 0.00, 65, 132, 552, 0 +ATT, 8.43, 8.74, -33.04, -31.12, 0.00, 23.60, 23.83 +MOT, 1531, 1646, 1517, 1588 +CTUN, 587, 0.00, 81.12, 0.000000, 0.00, 64, 120, 551, 0 +ATT, 8.22, 8.71, -32.82, -30.96, 0.00, 23.69, 23.83 +MOT, 1537, 1631, 1539, 1573 +GPS, 3, 109285600, 1774, 10, 1.65, -39.4910990, 176.7493503, 81.34, 123.98, 8.28, 13.67, -1.320000, 138640 +CTUN, 586, 0.00, 81.25, 0.000000, 0.00, 63, 118, 550, 0 +ATT, 8.43, 8.70, -32.82, -30.80, 0.00, 23.80, 23.83 +MOT, 1532, 1638, 1528, 1579 +CTUN, 585, 0.00, 81.05, 0.000000, 0.00, 62, 119, 547, 0 +ATT, 8.65, 8.62, -32.75, -30.70, 0.00, 23.77, 23.83 +MOT, 1551, 1620, 1533, 1563 +GPS, 3, 109285800, 1774, 10, 1.65, -39.4910844, 176.7493551, 81.56, 124.21, 8.31, 14.39, -1.160000, 138842 +CTUN, 586, 0.00, 81.25, 0.000000, 0.00, 62, 110, 549, 0 +ATT, 8.87, 8.67, -32.75, -30.56, 0.10, 23.72, 23.83 +MOT, 1531, 1641, 1532, 1570 +CTUN, 587, 0.00, 81.29, 0.000000, 0.00, 61, 106, 547, 0 +ATT, 8.87, 8.63, -32.82, -30.38, 0.10, 23.79, 23.83 +MOT, 1517, 1649, 1520, 1578 +DU32, 7, 270713 +CURR, 546, 292989, 1484, 4226, 4940, 533.8241 +GPS, 3, 109286000, 1774, 10, 1.65, -39.4910700, 176.7493602, 81.76, 124.43, 8.32, 15.15, -1.090000, 139042 +CTUN, 584, 0.00, 81.90, 0.000000, 0.00, 60, 108, 544, 0 +ATT, 8.87, 8.68, -32.16, -30.14, 0.00, 23.95, 23.83 +MOT, 1525, 1633, 1529, 1570 +CTUN, 587, 0.00, 81.54, 0.000000, 0.00, 58, 109, 545, 0 +ATT, 8.87, 8.59, -32.16, -29.58, 0.00, 24.12, 23.83 +MOT, 1536, 1624, 1529, 1572 +GPS, 3, 109286200, 1774, 10, 1.65, -39.4910556, 176.7493656, 81.97, 124.64, 8.32, 15.98, -1.040000, 139242 +CTUN, 586, 0.00, 81.81, 0.000000, 0.00, 57, 108, 544, 0 +ATT, 8.65, 8.53, -32.38, -29.30, 0.00, 24.19, 23.83 +MOT, 1521, 1638, 1525, 1572 +CTUN, 586, 0.00, 81.88, 0.000000, 0.00, 56, 104, 542, 0 +ATT, 8.65, 8.54, -32.82, -29.20, 0.00, 24.15, 23.83 +MOT, 1526, 1628, 1519, 1575 +GPS, 3, 109286400, 1774, 10, 1.65, -39.4910411, 176.7493712, 82.17, 124.85, 8.35, 16.79, -1.010000, 139442 +CTUN, 586, 0.00, 82.18, 0.000000, 0.00, 55, 100, 541, 0 +ATT, 8.87, 8.23, -33.25, -29.05, 0.00, 24.15, 23.83 +MOT, 1522, 1635, 1528, 1562 +CTUN, 586, 0.00, 82.12, 0.000000, 0.00, 56, 97, 542, 0 +ATT, 8.43, 8.30, -33.47, -29.21, 0.00, 24.08, 23.83 +MOT, 1525, 1629, 1516, 1578 +GPS, 3, 109286600, 1774, 10, 1.65, -39.4910269, 176.7493772, 82.38, 125.05, 8.32, 17.71, -0.990000, 139642 +CTUN, 587, 0.00, 82.35, 0.000000, 0.00, 55, 104, 542, 0 +ATT, 8.43, 7.99, -33.69, -28.97, 0.00, 24.32, 23.83 +MOT, 1541, 1615, 1496, 1593 +CTUN, 586, 0.00, 82.32, 0.000000, 0.00, 55, 107, 542, 0 +ATT, 8.22, 7.94, -33.69, -29.08, 0.10, 24.48, 23.83 +MOT, 1525, 1628, 1541, 1556 +GPS, 3, 109286800, 1774, 10, 1.65, -39.4910127, 176.7493832, 82.60, 125.24, 8.27, 18.23, -0.920000, 139843 +CTUN, 587, 0.00, 81.80, 0.000000, 0.00, 55, 113, 542, 0 +ATT, 8.22, 7.85, -33.69, -29.05, 0.00, 24.58, 23.83 +MOT, 1541, 1610, 1526, 1573 +CTUN, 587, 0.00, 82.73, 0.000000, 0.00, 55, 110, 541, 0 +ATT, 8.22, 7.70, -33.69, -29.29, 0.00, 24.66, 23.83 +MOT, 1538, 1612, 1512, 1583 +DU32, 7, 270713 +CURR, 541, 298413, 1475, 4087, 4876, 545.4614 +GPS, 3, 109287000, 1774, 10, 1.65, -39.4909986, 176.7493893, 82.78, 125.44, 8.23, 18.62, -0.930000, 140043 +CTUN, 587, 0.00, 82.99, 0.000000, 0.00, 56, 110, 542, 0 +ATT, 8.22, 7.74, -33.69, -29.39, 0.00, 24.63, 23.83 +MOT, 1522, 1632, 1526, 1569 +CTUN, 584, 0.00, 82.54, 0.000000, 0.00, 56, 111, 543, 0 +ATT, 8.22, 7.70, -33.69, -29.56, 0.00, 24.59, 23.83 +MOT, 1531, 1623, 1531, 1570 +GPS, 3, 109287200, 1774, 10, 1.65, -39.4909847, 176.7493956, 83.01, 125.61, 8.21, 19.12, -0.910000, 140243 +CTUN, 586, 0.00, 82.88, 0.000000, 0.00, 56, 113, 542, 0 +ATT, 8.00, 7.61, -33.69, -29.40, 0.20, 24.65, 23.83 +MOT, 1508, 1638, 1522, 1578 +CTUN, 587, 0.00, 82.90, 0.000000, 0.00, 55, 118, 541, 0 +ATT, 8.00, 7.51, -33.69, -29.16, 0.00, 24.75, 23.83 +MOT, 1532, 1615, 1532, 1569 +GPS, 3, 109287400, 1774, 10, 1.65, -39.4909707, 176.7494020, 83.23, 125.83, 8.16, 19.61, -0.950000, 140443 +CTUN, 586, 0.00, 82.86, 0.000000, 0.00, 55, 119, 541, 0 +ATT, 8.00, 7.33, -33.47, -29.24, 0.00, 24.77, 23.83 +MOT, 1511, 1636, 1508, 1586 +CTUN, 586, 0.00, 83.14, 0.000000, 0.00, 55, 120, 542, 0 +ATT, 8.00, 7.28, -33.69, -29.15, 0.00, 24.66, 23.83 +MOT, 1537, 1617, 1528, 1570 +GPS, 3, 109287600, 1774, 10, 1.65, -39.4909567, 176.7494086, 83.46, 126.06, 8.23, 20.21, -1.030000, 140644 +CTUN, 587, 0.00, 83.29, 0.000000, 0.00, 55, 123, 542, 0 +ATT, 8.22, 7.38, -33.91, -29.09, 0.00, 24.61, 23.83 +MOT, 1537, 1617, 1515, 1580 +CTUN, 587, 0.00, 83.78, 0.000000, 0.00, 56, 124, 543, 0 +ATT, 8.00, 7.55, -33.83, -29.31, 0.00, 24.62, 23.83 +MOT, 1512, 1637, 1532, 1571 +GPS, 3, 109287800, 1774, 10, 1.65, -39.4909430, 176.7494154, 83.72, 126.27, 8.20, 20.77, -1.080000, 140844 +CTUN, 586, 0.00, 83.59, 0.000000, 0.00, 55, 127, 542, 0 +ATT, 7.79, 7.50, -33.91, -29.33, 0.00, 24.69, 23.83 +MOT, 1532, 1620, 1528, 1572 +CTUN, 587, 0.00, 84.02, 0.000000, 0.00, 56, 132, 543, 0 +ATT, 7.79, 7.44, -34.12, -29.34, 0.00, 24.64, 23.83 +MOT, 1516, 1637, 1515, 1582 +DU32, 7, 270713 +CURR, 541, 303831, 1502, 4242, 4897, 557.1648 +GPS, 3, 109288000, 1774, 10, 1.65, -39.4909291, 176.7494222, 84.01, 126.51, 8.22, 20.73, -1.130000, 141044 +CTUN, 587, 0.00, 83.28, 0.000000, 0.00, 56, 142, 542, 0 +ATT, 7.79, 7.57, -34.12, -29.49, 0.10, 24.62, 23.83 +MOT, 1528, 1625, 1541, 1556 +CTUN, 587, 0.00, 83.80, 0.000000, 0.00, 58, 139, 545, 0 +ATT, 7.79, 7.56, -34.12, -29.99, 0.00, 24.49, 23.83 +MOT, 1530, 1632, 1533, 1566 +GPS, 3, 109288200, 1774, 10, 1.65, -39.4909151, 176.7494292, 84.25, 126.77, 8.29, 21.35, -1.190000, 141245 +CTUN, 587, 0.00, 84.07, 0.000000, 0.00, 59, 139, 545, 0 +ATT, 7.79, 7.50, -34.12, -30.43, 0.10, 24.34, 23.83 +MOT, 1538, 1624, 1532, 1568 +CTUN, 587, 0.00, 83.77, 0.000000, 0.00, 61, 130, 548, 0 +ATT, 7.79, 7.32, -34.12, -30.60, 0.00, 24.30, 23.83 +MOT, 1537, 1627, 1544, 1564 +GPS, 3, 109288400, 1774, 10, 1.65, -39.4909010, 176.7494364, 84.48, 127.03, 8.38, 21.33, -1.220000, 141445 +CTUN, 587, 0.00, 84.40, 0.000000, 0.00, 62, 118, 549, 0 +ATT, 7.79, 7.43, -34.12, -30.91, 0.10, 24.27, 23.83 +MOT, 1518, 1642, 1518, 1592 +CTUN, 587, 0.00, 84.41, 0.000000, 0.00, 62, 115, 549, 0 +ATT, 7.79, 7.37, -34.34, -31.06, 0.00, 24.26, 23.83 +MOT, 1549, 1619, 1551, 1555 +GPS, 3, 109288600, 1774, 10, 1.65, -39.4908868, 176.7494436, 84.71, 127.28, 8.40, 21.41, -1.200000, 141645 +CTUN, 586, 0.00, 84.47, 0.000000, 0.00, 64, 111, 550, 0 +ATT, 7.79, 7.35, -34.34, -31.32, 0.00, 24.18, 23.83 +MOT, 1537, 1633, 1522, 1584 +CTUN, 587, 0.00, 84.51, 0.000000, 0.00, 64, 109, 551, 0 +ATT, 8.00, 7.52, -34.34, -31.45, 0.00, 24.15, 23.83 +MOT, 1537, 1633, 1544, 1567 +GPS, 3, 109288800, 1774, 10, 1.65, -39.4908725, 176.7494507, 84.91, 127.50, 8.49, 21.20, -1.120000, 141845 +CTUN, 587, 0.00, 84.56, 0.000000, 0.00, 65, 98, 552, 0 +ATT, 8.00, 7.55, -34.34, -31.55, 0.00, 24.15, 23.83 +MOT, 1548, 1622, 1524, 1589 +CTUN, 587, 0.00, 85.49, 0.000000, 0.00, 66, 88, 552, 0 +ATT, 8.00, 7.75, -34.34, -31.84, 0.10, 24.19, 23.83 +MOT, 1541, 1627, 1541, 1575 +DU32, 7, 270713 +CURR, 553, 309307, 1480, 4221, 4962, 569.0137 +GPS, 3, 109289000, 1774, 10, 1.65, -39.4908582, 176.7494580, 85.11, 127.71, 8.51, 21.31, -1.040000, 142046 +CTUN, 587, 0.00, 85.37, 0.000000, 0.00, 68, 84, 555, 0 +ATT, 7.79, 7.84, -34.34, -31.99, 0.00, 24.16, 23.83 +MOT, 1534, 1641, 1541, 1578 +CTUN, 587, 0.00, 84.39, 0.000000, 0.00, 67, 78, 554, 0 +ATT, 8.00, 7.53, -34.34, -31.95, 0.00, 24.23, 23.83 +MOT, 1547, 1623, 1537, 1584 +GPS, 3, 109289200, 1774, 10, 1.65, -39.4908437, 176.7494652, 85.27, 127.91, 8.58, 21.07, -0.940000, 142246 +CTUN, 586, 0.00, 86.09, 0.000000, 0.00, 68, 65, 554, 0 +ATT, 8.00, 7.46, -34.34, -32.23, 0.00, 24.15, 23.83 +MOT, 1521, 1651, 1547, 1570 +CTUN, 586, 0.00, 85.72, 0.000000, 0.00, 68, 62, 554, 0 +ATT, 8.00, 7.66, -34.34, -32.18, 0.00, 24.11, 23.83 +MOT, 1541, 1634, 1542, 1573 +GPS, 3, 109289400, 1774, 10, 1.65, -39.4908292, 176.7494725, 85.45, 128.05, 8.60, 21.15, -0.770000, 142446 +CTUN, 587, 0.00, 85.24, 0.000000, 0.00, 68, 56, 554, 0 +ATT, 8.00, 7.56, -34.34, -32.25, 0.00, 24.08, 23.83 +MOT, 1541, 1633, 1542, 1573 +CTUN, 585, 0.00, 85.85, 0.000000, 0.00, 69, 39, 554, 0 +ATT, 8.00, 7.72, -34.34, -32.55, 0.00, 23.91, 23.83 +MOT, 1525, 1654, 1544, 1567 +GPS, 3, 109289600, 1774, 10, 1.65, -39.4908149, 176.7494797, 85.56, 128.15, 8.58, 21.03, -0.610000, 142646 +CTUN, 586, 0.00, 85.77, 0.000000, 0.00, 71, 32, 557, 0 +ATT, 8.00, 7.84, -34.56, -32.96, 0.00, 23.94, 23.83 +MOT, 1556, 1620, 1553, 1571 +CTUN, 587, 0.00, 85.92, 0.000000, 0.00, 72, 13, 558, 0 +ATT, 8.00, 7.85, -34.56, -32.99, 0.00, 24.25, 23.83 +MOT, 1560, 1609, 1503, 1627 +GPS, 3, 109289800, 1774, 10, 1.65, -39.4908002, 176.7494868, 85.63, 128.23, 8.65, 20.47, -0.450000, 142847 +CTUN, 585, 0.00, 86.00, 0.000000, 0.00, 72, 8, 557, 0 +ATT, 7.79, 8.22, -34.56, -32.99, 0.00, 24.46, 23.83 +MOT, 1520, 1653, 1570, 1555 +CTUN, 587, 0.00, 85.25, 0.000000, 0.00, 72, 2, 559, 0 +ATT, 7.93, 7.74, -34.78, -32.80, 0.00, 24.49, 23.83 +MOT, 1560, 1620, 1517, 1608 +DU32, 7, 270713 +CURR, 555, 314863, 1488, 4347, 4897, 580.8494 +GPS, 3, 109290000, 1774, 10, 1.65, -39.4907856, 176.7494938, 85.65, 128.25, 8.66, 20.10, -0.250000, 143048 +CTUN, 584, 0.00, 85.80, 0.000000, 0.00, 70, -3, 554, 0 +ATT, 8.22, 7.98, -34.78, -32.75, 0.00, 24.38, 23.83 +MOT, 1514, 1658, 1564, 1552 +CTUN, 586, 0.00, 85.86, 0.000000, 0.00, 71, -12, 557, 0 +ATT, 8.22, 7.91, -34.78, -32.73, 0.00, 24.18, 23.83 +MOT, 1541, 1644, 1534, 1582 +GPS, 3, 109290200, 1774, 10, 1.65, -39.4907711, 176.7495011, 85.64, 128.26, 8.67, 21.24, -0.070000, 143247 +CTUN, 587, 0.00, 85.71, 0.000000, 0.00, 70, -11, 556, 0 +ATT, 8.22, 8.14, -35.00, -32.58, 0.00, 24.09, 23.83 +MOT, 1549, 1633, 1541, 1575 +CTUN, 586, 0.00, 85.83, 0.000000, 0.00, 71, -24, 557, 0 +ATT, 8.22, 8.21, -35.00, -32.69, 0.00, 23.95, 23.83 +MOT, 1546, 1636, 1531, 1588 +GPS, 3, 109290400, 1774, 10, 1.65, -39.4907563, 176.7495088, 85.62, 128.24, 8.84, 21.81, 0.050000, 143447 +CTUN, 584, 0.00, 85.49, 0.000000, 0.00, 71, -30, 558, 0 +ATT, 8.22, 7.94, -35.00, -32.85, 0.20, 23.89, 23.83 +MOT, 1544, 1641, 1547, 1572 +CTUN, 586, 0.00, 84.90, 0.000000, 0.00, 71, -34, 557, 0 +ATT, 8.22, 7.73, -35.00, -32.74, 0.00, 24.00, 23.83 +MOT, 1518, 1658, 1540, 1583 +GPS, 3, 109290600, 1774, 10, 1.65, -39.4907414, 176.7495169, 85.51, 128.19, 8.96, 22.60, 0.150000, 143648 +CTUN, 587, 0.00, 85.29, 0.000000, 0.00, 70, -34, 554, 0 +ATT, 8.00, 7.68, -35.00, -32.67, 0.00, 24.05, 23.83 +MOT, 1478, 1684, 1543, 1574 +CTUN, 587, 0.00, 85.75, 0.000000, 0.00, 67, -28, 554, 0 +ATT, 7.79, 7.72, -34.78, -32.05, 0.00, 24.23, 23.83 +MOT, 1601, 1571, 1484, 1625 +GPS, 3, 109290800, 1774, 10, 1.65, -39.4907264, 176.7495255, 85.44, 128.11, 9.12, 23.81, 0.260000, 143848 +CTUN, 586, 0.00, 85.68, 0.000000, 0.00, 68, -22, 555, 0 +ATT, 7.57, 8.33, -34.56, -31.88, 0.00, 24.40, 23.83 +MOT, 1556, 1610, 1516, 1609 +CTUN, 586, 0.00, 85.23, 0.000000, 0.00, 68, -35, 554, 0 +ATT, 7.79, 8.55, -35.00, -32.01, 0.20, 24.57, 23.83 +MOT, 1522, 1638, 1587, 1541 +DU32, 7, 270713 +CURR, 555, 320426, 1487, 4377, 4897, 592.9659 +PM, 0, 0, 0, 1000, 10230, 0, 0, 0, 0 +GPS, 3, 109291000, 1774, 10, 1.65, -39.4907111, 176.7495343, 85.39, 128.06, 9.31, 24.01, 0.240000, 144049 +CTUN, 586, 0.00, 85.51, 0.000000, 0.00, 70, -44, 557, 0 +ATT, 7.57, 8.02, -35.00, -32.50, 0.00, 24.71, 23.83 +MOT, 1532, 1637, 1509, 1619 +CTUN, 586, 0.00, 86.29, 0.000000, 0.00, 69, -48, 555, 0 +ATT, 9.30, 8.44, -35.00, -32.45, 0.10, 25.08, 23.83 +MOT, 1554, 1603, 1557, 1580 +GPS, 3, 109291200, 1774, 10, 1.65, -39.4906956, 176.7495434, 85.32, 127.99, 9.50, 24.28, 0.280000, 144249 +CTUN, 587, 0.00, 86.31, 0.000000, 0.00, 74, -66, 561, 0 +ATT, 9.95, 9.36, -35.00, -33.20, 0.00, 25.40, 23.83 +MOT, 1538, 1620, 1541, 1614 +CTUN, 587, 0.00, 86.54, 0.000000, 0.00, 77, -83, 563, 0 +ATT, 10.39, 9.80, -35.00, -33.64, 0.10, 25.62, 23.83 +MOT, 1550, 1617, 1550, 1604 +GPS, 3, 109291400, 1774, 10, 1.65, -39.4906802, 176.7495527, 85.28, 127.87, 9.47, 24.63, 0.460000, 144449 +CTUN, 586, 0.00, 86.75, 0.000000, 0.00, 75, -98, 561, 0 +ATT, 10.17, 10.41, -35.00, -32.80, 0.00, 26.03, 23.83 +MOT, 1552, 1610, 1530, 1622 +CTUN, 587, 0.00, 86.73, 0.000000, 0.00, 70, -94, 556, 0 +ATT, 9.52, 10.30, -35.00, -31.64, 0.00, 26.31, 23.83 +MOT, 1555, 1603, 1475, 1652 +GPS, 3, 109291600, 1774, 10, 1.65, -39.4906651, 176.7495620, 85.24, 127.67, 9.33, 25.43, 0.810000, 144649 +CTUN, 587, 0.00, 86.41, 0.000000, 0.00, 61, -73, 547, 0 +ATT, 8.22, 9.46, -35.00, -29.49, 0.00, 26.70, 23.83 +MOT, 1492, 1641, 1427, 1679 +CTUN, 587, 0.00, 85.79, 0.000000, 0.00, 45, -14, 532, 0 +ATT, 6.92, 9.21, -35.00, -24.85, 0.00, 27.43, 23.83 +MOT, 1435, 1656, 1520, 1583 +GPS, 3, 109291800, 1774, 10, 1.65, -39.4906505, 176.7495719, 85.29, 127.48, 9.14, 27.44, 0.930000, 144850 +CTUN, 586, 0.00, 85.81, 0.000000, 0.00, 32, 66, 519, 0 +ATT, 6.92, 7.59, -35.00, -21.90, 0.00, 27.89, 23.83 +MOT, 1478, 1599, 1448, 1619 +CTUN, 586, 0.00, 85.24, 0.000000, 0.00, 26, 120, 512, 0 +ATT, 6.92, 6.72, -35.00, -20.04, 0.00, 28.10, 23.83 +MOT, 1435, 1621, 1518, 1553 +DU32, 7, 270713 +CURR, 510, 325904, 1519, 3821, 4918, 604.7382 +GPS, 3, 109292000, 1774, 10, 1.65, -39.4906362, 176.7495829, 85.55, 127.42, 9.29, 30.98, 0.430000, 145050 +CTUN, 587, 0.00, 85.04, 0.000000, 0.00, 23, 167, 510, 0 +ATT, 6.49, 5.54, -35.00, -19.39, 0.00, 27.96, 23.83 +MOT, 1451, 1604, 1480, 1581 +CTUN, 587, 0.00, 84.98, 0.000000, 0.00, 23, 196, 510, 0 +ATT, 6.49, 5.06, -35.00, -20.18, 0.00, 27.55, 23.83 +MOT, 1469, 1603, 1534, 1523 +GPS, 3, 109292200, 1774, 10, 1.65, -39.4906220, 176.7495949, 85.88, 127.66, 9.42, 33.88, -0.560000, 145250 +CTUN, 587, 0.00, 84.97, 0.000000, 0.00, 27, 206, 514, 0 +ATT, 6.27, 3.92, -35.00, -21.67, 0.00, 26.82, 23.83 +MOT, 1502, 1588, 1490, 1562 +CTUN, 586, 0.00, 85.04, 0.000000, 0.00, 32, 211, 519, 0 +ATT, 4.97, 3.98, -35.00, -23.72, 0.00, 26.05, 23.83 +MOT, 1474, 1625, 1494, 1560 +GPS, 3, 109292400, 1774, 10, 1.65, -39.4906081, 176.7496067, 86.22, 128.09, 9.12, 34.40, -1.280000, 145450 +CTUN, 587, 0.00, 85.48, 0.000000, 0.00, 38, 214, 525, 0 +ATT, 4.97, 3.70, -35.00, -25.36, 0.00, 25.45, 23.83 +MOT, 1502, 1615, 1504, 1560 +CTUN, 587, 0.00, 86.03, 0.000000, 0.00, 44, 205, 531, 0 +ATT, 5.62, 3.78, -35.00, -27.43, 0.00, 24.90, 23.83 +MOT, 1494, 1638, 1537, 1537 +GPS, 3, 109292600, 1774, 10, 1.65, -39.4905947, 176.7496183, 86.59, 128.48, 8.88, 34.51, -1.510000, 145651 +CTUN, 586, 0.00, 85.46, 0.000000, 0.00, 51, 198, 538, 0 +ATT, 7.57, 4.19, -35.00, -29.09, 0.00, 24.33, 23.83 +MOT, 1533, 1619, 1540, 1546 +CTUN, 587, 0.00, 85.84, 0.000000, 0.00, 57, 190, 544, 0 +ATT, 7.79, 5.20, -35.00, -30.26, 0.00, 23.94, 23.83 +MOT, 1506, 1652, 1530, 1564 +GPS, 3, 109292800, 1774, 10, 1.65, -39.4905815, 176.7496297, 86.89, 128.84, 8.74, 34.25, -1.510000, 145851 +CTUN, 587, 0.00, 86.04, 0.000000, 0.00, 60, 184, 547, 0 +ATT, 7.79, 5.86, -35.00, -30.82, 0.00, 23.96, 23.83 +MOT, 1545, 1615, 1526, 1581 +CTUN, 586, 0.00, 85.95, 0.000000, 0.00, 64, 175, 550, 0 +ATT, 7.79, 6.65, -35.00, -31.50, 0.00, 23.94, 23.83 +MOT, 1517, 1647, 1533, 1578 +DU32, 7, 270713 +CURR, 550, 331171, 1477, 4230, 4962, 616.0119 +GPS, 3, 109293000, 1774, 10, 1.65, -39.4905683, 176.7496408, 87.16, 129.17, 8.70, 33.36, -1.450000, 146051 +CTUN, 587, 0.00, 86.88, 0.000000, 0.00, 65, 171, 549, 0 +ATT, 8.00, 7.15, -35.00, -31.64, 0.00, 23.96, 23.83 +MOT, 1528, 1638, 1520, 1586 +CTUN, 586, 0.00, 86.66, 0.000000, 0.00, 63, 172, 549, 0 +ATT, 7.79, 7.16, -35.00, -31.11, 0.20, 24.07, 23.83 +MOT, 1547, 1618, 1546, 1563 +GPS, 3, 109293200, 1774, 10, 1.65, -39.4905545, 176.7496519, 87.47, 129.51, 8.91, 32.56, -1.450000, 146252 +CTUN, 587, 0.00, 87.09, 0.000000, 0.00, 63, 168, 547, 0 +ATT, 7.79, 7.27, -35.00, -31.23, 0.10, 24.12, 23.83 +MOT, 1551, 1610, 1502, 1598 +CTUN, 587, 0.00, 87.26, 0.000000, 0.00, 64, 169, 551, 0 +ATT, 7.79, 7.28, -35.00, -31.40, 0.00, 24.02, 23.83 +MOT, 1537, 1637, 1515, 1590 +GPS, 3, 109293400, 1774, 10, 1.65, -39.4905407, 176.7496632, 87.79, 129.82, 9.05, 32.62, -1.450000, 146452 +CTUN, 587, 0.00, 87.40, 0.000000, 0.00, 64, 173, 550, 0 +ATT, 8.00, 7.43, -35.00, -31.42, 0.00, 24.04, 23.83 +MOT, 1517, 1652, 1541, 1564 +CTUN, 586, 0.00, 87.93, 0.000000, 0.00, 63, 177, 549, 0 +ATT, 8.00, 7.41, -35.00, -30.98, 0.00, 24.19, 23.83 +MOT, 1511, 1647, 1499, 1607 +GPS, 3, 109293600, 1774, 10, 1.65, -39.4905265, 176.7496747, 88.13, 130.15, 9.29, 32.35, -1.490000, 146652 +CTUN, 587, 0.00, 87.67, 0.000000, 0.00, 57, 188, 544, 0 +ATT, 8.00, 7.56, -35.00, -29.53, 0.10, 24.30, 23.83 +MOT, 1541, 1624, 1578, 1512 +CTUN, 587, 0.00, 88.04, 0.000000, 0.00, 55, 208, 542, 0 +ATT, 8.00, 7.02, -35.00, -29.15, 0.00, 24.27, 23.83 +MOT, 1525, 1631, 1477, 1606 +GPS, 3, 109293800, 1774, 10, 1.65, -39.4905122, 176.7496863, 88.53, 130.47, 9.38, 32.09, -1.570000, 146853 +CTUN, 586, 0.00, 88.01, 0.000000, 0.00, 52, 230, 538, 0 +ATT, 8.00, 6.87, -35.00, -28.52, 0.10, 24.49, 23.83 +MOT, 1494, 1647, 1524, 1564 +CTUN, 587, 0.00, 88.36, 0.000000, 0.00, 52, 230, 539, 0 +ATT, 8.00, 6.87, -35.00, -28.73, 0.00, 24.48, 23.83 +MOT, 1537, 1609, 1506, 1585 +DU32, 7, 270713 +CURR, 540, 336640, 1493, 4220, 4876, 628.0048 +GPS, 3, 109294000, 1774, 10, 1.65, -39.4904974, 176.7496983, 88.97, 130.89, 9.64, 32.40, -1.820000, 147053 +CTUN, 587, 0.00, 87.86, 0.000000, 0.00, 55, 235, 542, 0 +ATT, 7.79, 6.60, -35.00, -29.34, 0.20, 24.59, 23.83 +MOT, 1534, 1611, 1496, 1603 +CTUN, 585, 0.00, 88.65, 0.000000, 0.00, 57, 230, 543, 0 +ATT, 8.00, 6.92, -35.00, -30.15, 0.10, 24.62, 23.83 +MOT, 1511, 1636, 1551, 1553 +GPS, 3, 109294200, 1774, 10, 1.65, -39.4904825, 176.7497103, 89.36, 131.34, 9.71, 32.28, -2.020000, 147253 +CTUN, 587, 0.00, 89.67, 0.000000, 0.00, 62, 215, 548, 0 +ATT, 7.79, 6.63, -35.00, -31.43, 0.00, 24.54, 23.83 +MOT, 1546, 1610, 1557, 1559 +CTUN, 587, 0.00, 89.84, 0.000000, 0.00, 67, 199, 554, 0 +ATT, 7.57, 6.63, -35.00, -32.14, 0.20, 24.50, 23.83 +MOT, 1534, 1633, 1553, 1571 +GPS, 3, 109294400, 1774, 10, 1.65, -39.4904677, 176.7497220, 89.82, 131.77, 9.64, 31.44, -2.040000, 147453 +CTUN, 586, 0.00, 89.40, 0.000000, 0.00, 69, 183, 555, 0 +ATT, 7.35, 6.65, -35.00, -32.61, 0.00, 24.38, 23.83 +MOT, 1513, 1657, 1529, 1592 +CTUN, 586, 0.00, 89.89, 0.000000, 0.00, 69, 178, 556, 0 +ATT, 6.70, 6.63, -35.00, -32.62, 0.10, 24.38, 23.83 +MOT, 1560, 1610, 1555, 1572 +GPS, 3, 109294600, 1774, 10, 1.65, -39.4904528, 176.7497332, 90.17, 132.17, 9.50, 30.37, -1.900000, 147653 +CTUN, 586, 0.00, 89.89, 0.000000, 0.00, 71, 168, 557, 0 +ATT, 6.49, 6.40, -35.00, -33.12, 0.00, 24.42, 23.83 +MOT, 1555, 1614, 1532, 1600 +CTUN, 586, 0.00, 89.77, 0.000000, 0.00, 73, 148, 559, 0 +ATT, 6.49, 6.32, -35.00, -33.66, 0.10, 24.34, 23.83 +MOT, 1557, 1615, 1546, 1589 +GPS, 3, 109294800, 1774, 10, 1.65, -39.4904378, 176.7497439, 90.46, 132.53, 9.48, 29.13, -1.750000, 147854 +CTUN, 585, 0.00, 90.01, 0.000000, 0.00, 76, 135, 561, 0 +ATT, 6.70, 6.41, -35.00, -34.09, 0.00, 24.35, 23.83 +MOT, 1537, 1643, 1554, 1580 +CTUN, 586, 0.00, 91.14, 0.000000, 0.00, 77, 122, 563, 0 +ATT, 6.27, 6.47, -35.00, -34.26, 0.00, 24.33, 23.83 +MOT, 1524, 1656, 1544, 1595 +DU32, 7, 270713 +CURR, 562, 342168, 1498, 4220, 4897, 639.7413 +GPS, 3, 109295000, 1774, 10, 1.65, -39.4904229, 176.7497544, 90.72, 132.84, 9.40, 28.66, -1.580000, 148054 +CTUN, 586, 0.00, 90.95, 0.000000, 0.00, 74, 107, 561, 0 +ATT, 6.49, 6.18, -35.00, -33.60, 0.10, 24.34, 23.83 +MOT, 1550, 1633, 1548, 1583 +CTUN, 587, 0.00, 91.12, 0.000000, 0.00, 72, 111, 559, 0 +ATT, 6.27, 6.60, -35.00, -33.18, 0.00, 24.27, 23.83 +MOT, 1555, 1623, 1531, 1598 +GPS, 3, 109295200, 1774, 10, 1.65, -39.4904080, 176.7497646, 90.98, 133.07, 9.38, 27.76, -1.330000, 148254 +CTUN, 587, 0.00, 90.30, 0.000000, 0.00, 70, 105, 557, 0 +ATT, 5.84, 6.70, -35.00, -32.62, 0.10, 24.34, 23.83 +MOT, 1556, 1617, 1531, 1596 +CTUN, 587, 0.00, 90.62, 0.000000, 0.00, 68, 103, 555, 0 +ATT, 5.40, 6.55, -35.00, -32.36, 0.10, 24.44, 23.83 +MOT, 1511, 1657, 1562, 1560 +GPS, 3, 109295400, 1774, 10, 1.65, -39.4903930, 176.7497748, 91.15, 133.27, 9.47, 27.38, -1.210000, 148455 +CTUN, 586, 0.00, 90.98, 0.000000, 0.00, 66, 105, 553, 0 +ATT, 5.40, 5.95, -35.00, -32.00, 0.00, 24.51, 23.83 +MOT, 1545, 1627, 1526, 1589 +CTUN, 587, 0.00, 90.92, 0.000000, 0.00, 63, 109, 550, 0 +ATT, 5.40, 5.75, -35.00, -31.30, 0.10, 24.48, 23.83 +MOT, 1532, 1631, 1532, 1583 +GPS, 3, 109295600, 1774, 10, 1.65, -39.4903776, 176.7497850, 91.35, 133.50, 9.59, 27.09, -1.180000, 148655 +CTUN, 587, 0.00, 90.75, 0.000000, 0.00, 61, 113, 548, 0 +ATT, 5.40, 5.62, -35.00, -30.90, 0.00, 24.41, 23.83 +MOT, 1535, 1628, 1514, 1591 +CTUN, 586, 0.00, 91.09, 0.000000, 0.00, 59, 113, 545, 0 +ATT, 5.62, 5.64, -35.00, -30.62, 0.00, 24.39, 23.83 +MOT, 1520, 1633, 1528, 1578 +GPS, 3, 109295800, 1774, 10, 1.65, -39.4903621, 176.7497952, 91.53, 133.73, 9.70, 26.89, -1.190000, 148855 +CTUN, 586, 0.00, 91.17, 0.000000, 0.00, 58, 115, 544, 0 +ATT, 5.62, 5.79, -35.00, -30.28, 0.20, 24.35, 23.83 +MOT, 1529, 1631, 1528, 1569 +CTUN, 587, 0.00, 91.69, 0.000000, 0.00, 58, 116, 545, 0 +ATT, 5.40, 5.74, -35.00, -30.24, 0.20, 24.39, 23.83 +MOT, 1476, 1665, 1532, 1578 +DU32, 7, 270713 +CURR, 544, 347690, 1484, 4202, 4940, 651.5557 +GPS, 3, 109296000, 1774, 10, 1.65, -39.4903463, 176.7498054, 91.79, 133.97, 9.83, 26.38, -1.240000, 149075 +CTUN, 587, 0.00, 91.80, 0.000000, 0.00, 57, 120, 544, 0 +ATT, 6.27, 5.60, -35.00, -30.26, 0.00, 24.47, 23.83 +MOT, 1532, 1622, 1545, 1560 +CTUN, 587, 0.00, 91.60, 0.000000, 0.00, 56, 116, 543, 0 +ATT, 6.27, 5.47, -35.00, -29.85, 0.00, 24.44, 23.83 +MOT, 1551, 1607, 1511, 1582 +GPS, 3, 109296200, 1774, 10, 1.65, -39.4903304, 176.7498155, 92.01, 134.24, 9.85, 26.26, -1.280000, 149256 +CTUN, 586, 0.00, 91.59, 0.000000, 0.00, 57, 119, 543, 0 +ATT, 6.27, 6.06, -35.00, -30.02, 0.00, 24.34, 23.83 +MOT, 1524, 1632, 1492, 1598 +CTUN, 586, 0.00, 91.84, 0.000000, 0.00, 57, 115, 543, 0 +ATT, 6.27, 6.51, -35.00, -30.13, 0.00, 24.27, 23.83 +MOT, 1545, 1614, 1514, 1579 +GPS, 3, 109296400, 1774, 10, 1.65, -39.4903144, 176.7498253, 92.22, 134.50, 9.82, 25.62, -1.290000, 149456 +CTUN, 587, 0.00, 92.21, 0.000000, 0.00, 60, 108, 546, 0 +ATT, 6.27, 6.64, -35.00, -30.65, 0.20, 24.19, 23.83 +MOT, 1521, 1641, 1549, 1552 +CTUN, 586, 0.00, 92.23, 0.000000, 0.00, 59, 102, 545, 0 +ATT, 6.70, 5.47, -35.00, -30.47, 0.00, 24.22, 23.83 +MOT, 1546, 1615, 1504, 1590 +GPS, 3, 109296600, 1774, 10, 1.65, -39.4902985, 176.7498352, 92.43, 134.76, 9.80, 25.70, -1.250000, 149656 +CTUN, 587, 0.00, 92.25, 0.000000, 0.00, 60, 106, 547, 0 +ATT, 6.49, 6.37, -35.00, -30.55, 0.00, 24.15, 23.83 +MOT, 1504, 1647, 1529, 1582 +CTUN, 587, 0.00, 92.50, 0.000000, 0.00, 56, 114, 543, 0 +ATT, 6.70, 6.21, -35.00, -29.70, 0.00, 24.39, 23.83 +MOT, 1571, 1581, 1520, 1581 +GPS, 3, 109296800, 1774, 10, 1.65, -39.4902827, 176.7498451, 92.66, 134.99, 9.72, 25.71, -1.120000, 149857 +CTUN, 586, 0.00, 92.58, 0.000000, 0.00, 57, 123, 543, 0 +ATT, 6.70, 6.49, -35.00, -29.83, 0.00, 24.36, 23.83 +MOT, 1504, 1647, 1473, 1613 +CTUN, 587, 0.00, 92.35, 0.000000, 0.00, 55, 135, 542, 0 +ATT, 6.49, 6.60, -35.00, -29.38, 0.00, 24.37, 23.83 +MOT, 1516, 1637, 1530, 1566 +DU32, 7, 270713 +CURR, 541, 353130, 1468, 4215, 4918, 663.2684 +GPS, 3, 109297000, 1774, 10, 1.65, -39.4902666, 176.7498551, 92.92, 135.24, 9.89, 25.79, -1.190000, 150057 +CTUN, 586, 0.00, 93.06, 0.000000, 0.00, 52, 150, 538, 0 +ATT, 6.49, 6.41, -35.00, -28.65, 0.20, 24.26, 23.83 +MOT, 1497, 1655, 1501, 1573 +CTUN, 586, 0.00, 93.13, 0.000000, 0.00, 50, 177, 536, 0 +ATT, 6.70, 6.07, -35.00, -28.17, 0.20, 24.19, 23.83 +MOT, 1522, 1627, 1512, 1566 +GPS, 3, 109297200, 1774, 10, 1.65, -39.4902503, 176.7498652, 93.28, 135.58, 9.95, 25.86, -1.390000, 150257 +CTUN, 586, 0.00, 93.49, 0.000000, 0.00, 49, 195, 535, 0 +ATT, 6.49, 6.23, -35.00, -27.80, 0.00, 24.37, 23.83 +MOT, 1494, 1639, 1529, 1555 +CTUN, 586, 0.00, 93.54, 0.000000, 0.00, 48, 209, 534, 0 +ATT, 6.70, 5.89, -35.00, -27.74, 0.00, 24.42, 23.83 +MOT, 1512, 1622, 1472, 1601 +GPS, 3, 109297400, 1774, 10, 1.65, -39.4902339, 176.7498754, 93.73, 135.96, 10.12, 25.78, -1.660000, 150457 +CTUN, 586, 0.00, 93.31, 0.000000, 0.00, 48, 222, 535, 0 +ATT, 6.49, 5.97, -35.00, -27.94, 0.10, 24.53, 23.83 +MOT, 1562, 1573, 1531, 1559 +CTUN, 587, 0.00, 94.35, 0.000000, 0.00, 53, 210, 540, 0 +ATT, 6.49, 6.27, -35.00, -28.89, 0.00, 24.61, 23.83 +MOT, 1484, 1651, 1515, 1582 +GPS, 3, 109297600, 1774, 10, 1.65, -39.4902172, 176.7498856, 94.18, 136.42, 10.15, 25.69, -1.940000, 150657 +CTUN, 587, 0.00, 94.35, 0.000000, 0.00, 53, 211, 540, 0 +ATT, 6.70, 6.70, -35.00, -29.10, 0.00, 24.68, 23.83 +MOT, 1509, 1636, 1537, 1559 +CTUN, 586, 0.00, 94.14, 0.000000, 0.00, 55, 210, 541, 0 +ATT, 6.70, 6.68, -35.00, -29.54, 0.00, 24.69, 23.83 +MOT, 1537, 1607, 1524, 1579 +GPS, 3, 109297800, 1774, 10, 1.65, -39.4902007, 176.7498958, 94.64, 136.89, 10.07, 25.93, -1.980000, 150858 +CTUN, 586, 0.00, 95.08, 0.000000, 0.00, 58, 210, 544, 0 +ATT, 6.70, 6.99, -35.00, -30.28, 0.00, 24.75, 23.83 +MOT, 1505, 1632, 1530, 1586 +CTUN, 586, 0.00, 94.72, 0.000000, 0.00, 59, 211, 545, 0 +ATT, 6.49, 6.86, -34.78, -30.34, 0.00, 24.94, 23.83 +MOT, 1532, 1613, 1534, 1582 +DU32, 7, 270713 +CURR, 547, 358519, 1477, 4201, 4897, 674.8842 +GPS, 3, 109298000, 1774, 10, 1.65, -39.4901845, 176.7499060, 95.11, 137.35, 9.95, 26.21, -2.000000, 151058 +CTUN, 586, 0.00, 95.09, 0.000000, 0.00, 61, 206, 547, 0 +ATT, 6.70, 6.76, -35.00, -30.89, 0.00, 24.97, 23.83 +MOT, 1526, 1625, 1541, 1574 +CTUN, 586, 0.00, 94.91, 0.000000, 0.00, 61, 203, 547, 0 +ATT, 6.49, 6.55, -35.00, -30.97, 0.00, 24.90, 23.83 +MOT, 1550, 1602, 1534, 1582 +GPS, 3, 109298200, 1774, 10, 1.65, -39.4901683, 176.7499162, 95.53, 137.80, 9.92, 26.35, -2.020000, 151258 +CTUN, 587, 0.00, 95.64, 0.000000, 0.00, 64, 196, 551, 0 +ATT, 6.49, 6.38, -35.00, -31.66, 0.00, 24.89, 23.83 +MOT, 1538, 1617, 1541, 1584 +CTUN, 587, 0.00, 95.77, 0.000000, 0.00, 67, 179, 554, 0 +ATT, 6.05, 5.97, -35.00, -32.54, 0.20, 24.61, 23.83 +MOT, 1562, 1611, 1518, 1597 +GPS, 3, 109298400, 1774, 10, 1.65, -39.4901521, 176.7499265, 95.92, 138.24, 9.94, 26.39, -2.020000, 151460 +CTUN, 586, 0.00, 96.53, 0.000000, 0.00, 68, 164, 554, 0 +ATT, 6.05, 5.83, -35.00, -32.66, 0.10, 24.42, 23.83 +MOT, 1559, 1613, 1555, 1564 +CTUN, 587, 0.00, 96.28, 0.000000, 0.00, 70, 159, 556, 0 +ATT, 5.19, 5.95, -35.00, -32.84, 0.00, 24.24, 23.83 +MOT, 1534, 1644, 1504, 1610 +GPS, 3, 109298600, 1774, 10, 1.65, -39.4901362, 176.7499365, 96.31, 138.61, 9.82, 26.02, -1.840000, 151660 +CTUN, 587, 0.00, 96.09, 0.000000, 0.00, 70, 157, 557, 0 +ATT, 4.76, 5.39, -35.00, -33.05, 0.00, 24.16, 23.83 +MOT, 1546, 1631, 1536, 1588 +CTUN, 586, 0.00, 96.98, 0.000000, 0.00, 69, 153, 555, 0 +ATT, 5.19, 5.13, -35.00, -32.95, 0.00, 24.14, 23.83 +MOT, 1546, 1628, 1557, 1564 +GPS, 3, 109298800, 1774, 10, 1.65, -39.4901201, 176.7499464, 96.65, 138.96, 9.89, 25.36, -1.710000, 151860 +CTUN, 586, 0.00, 96.27, 0.000000, 0.00, 70, 142, 556, 0 +ATT, 5.62, 5.20, -35.00, -33.03, 0.00, 24.10, 23.83 +MOT, 1547, 1623, 1526, 1601 +CTUN, 587, 0.00, 96.81, 0.000000, 0.00, 71, 127, 557, 0 +ATT, 5.84, 5.23, -35.00, -33.34, 0.00, 24.03, 23.83 +MOT, 1528, 1649, 1548, 1576 +DU32, 7, 270713 +CURR, 558, 364051, 1485, 4274, 4940, 686.6675 +GPS, 3, 109299000, 1774, 10, 1.65, -39.4901039, 176.7499562, 96.92, 139.29, 9.90, 25.02, -1.640000, 152060 +CTUN, 586, 0.00, 97.59, 0.000000, 0.00, 71, 121, 557, 0 +ATT, 6.05, 5.17, -35.00, -33.36, 0.00, 23.95, 23.83 +MOT, 1546, 1634, 1553, 1568 +CTUN, 586, 0.00, 97.13, 0.000000, 0.00, 72, 113, 558, 0 +ATT, 5.98, 5.22, -35.00, -33.44, 0.10, 23.92, 23.83 +MOT, 1550, 1629, 1550, 1574 +GPS, 3, 109299200, 1774, 10, 1.65, -39.4900878, 176.7499657, 97.21, 139.57, 9.84, 24.56, -1.460000, 152260 +CTUN, 587, 0.00, 97.79, 0.000000, 0.00, 72, 98, 559, 0 +ATT, 6.05, 5.29, -35.00, -33.40, 0.10, 23.80, 23.83 +MOT, 1548, 1640, 1521, 1596 +CTUN, 586, 0.00, 97.52, 0.000000, 0.00, 71, 96, 558, 0 +ATT, 6.05, 5.51, -35.00, -33.30, 0.00, 23.78, 23.83 +MOT, 1542, 1639, 1555, 1567 +GPS, 3, 109299400, 1774, 10, 1.65, -39.4900715, 176.7499749, 97.45, 139.81, 9.90, 23.61, -1.310000, 152461 +CTUN, 587, 0.00, 97.33, 0.000000, 0.00, 72, 76, 559, 0 +ATT, 6.05, 5.51, -35.00, -33.46, 0.00, 23.64, 23.83 +MOT, 1554, 1633, 1553, 1568 +CTUN, 586, 0.00, 98.06, 0.000000, 0.00, 73, 63, 559, 0 +ATT, 6.05, 5.61, -35.00, -33.69, 0.00, 23.67, 23.83 +MOT, 1526, 1653, 1548, 1579 +GPS, 3, 109299600, 1774, 10, 1.65, -39.4900553, 176.7499838, 97.61, 140.01, 9.83, 22.69, -1.150000, 152661 +CTUN, 586, 0.00, 97.76, 0.000000, 0.00, 73, 48, 560, 0 +ATT, 6.05, 5.50, -35.00, -33.42, 0.10, 23.77, 23.83 +MOT, 1564, 1618, 1536, 1593 +CTUN, 586, 0.00, 97.92, 0.000000, 0.00, 71, 47, 557, 0 +ATT, 6.27, 5.55, -35.00, -33.18, 0.10, 23.91, 23.83 +MOT, 1545, 1632, 1546, 1578 +GPS, 3, 109299800, 1774, 10, 1.65, -39.4900391, 176.7499923, 97.74, 140.17, 9.73, 22.00, -0.910000, 152862 +CTUN, 586, 0.00, 98.20, 0.000000, 0.00, 70, 42, 556, 0 +ATT, 6.27, 5.41, -35.00, -32.87, 0.20, 24.04, 23.83 +MOT, 1510, 1660, 1535, 1589 +CTUN, 586, 0.00, 98.04, 0.000000, 0.00, 66, 45, 552, 0 +ATT, 6.27, 5.55, -35.00, -31.94, 0.00, 24.31, 23.83 +MOT, 1524, 1638, 1537, 1584 +DU32, 7, 270713 +CURR, 556, 369629, 1471, 4241, 4940, 698.4905 +GPS, 3, 109300000, 1774, 10, 1.65, -39.4900229, 176.7500003, 97.88, 140.26, 9.70, 20.87, -0.710000, 153062 +CTUN, 590, 0.00, 97.56, 0.000000, 0.00, 63, 58, 554, 0 +ATT, 6.27, 5.51, -35.00, -31.13, 0.10, 24.59, 23.83 +MOT, 1550, 1617, 1533, 1591 +CTUN, 590, 0.00, 98.49, 0.000000, 0.00, 61, 59, 551, 0 +ATT, 6.27, 5.79, -35.00, -30.78, 0.20, 24.68, 23.83 +MOT, 1497, 1658, 1529, 1590 +GPS, 3, 109300200, 1774, 10, 1.65, -39.4900066, 176.7500084, 98.01, 140.37, 9.74, 20.73, -0.700000, 153262 +CTUN, 592, 0.00, 98.23, 0.000000, 0.00, 60, 55, 550, 0 +ATT, 6.27, 5.94, -35.00, -30.51, 0.20, 24.76, 23.83 +MOT, 1513, 1642, 1544, 1575 +CTUN, 598, 0.00, 97.99, 0.000000, 0.00, 60, 56, 561, 0 +ATT, 6.27, 6.12, -35.00, -30.07, 0.10, 24.81, 23.83 +MOT, 1534, 1641, 1532, 1607 +GPS, 3, 109300400, 1774, 10, 1.65, -39.4899902, 176.7500163, 98.15, 140.51, 9.74, 20.44, -0.720000, 153463 +CTUN, 605, 0.00, 98.52, 0.000000, 0.00, 60, 60, 570, 0 +ATT, 6.05, 6.21, -35.00, -29.77, 0.10, 24.78, 23.83 +MOT, 1570, 1624, 1530, 1619 +CTUN, 605, 0.00, 97.75, 0.000000, 0.00, 59, 74, 569, 0 +ATT, 6.27, 6.57, -35.00, -29.47, 0.00, 24.68, 23.83 +MOT, 1522, 1678, 1555, 1583 +GPS, 3, 109300600, 1774, 10, 1.65, -39.4899737, 176.7500242, 98.30, 140.65, 9.76, 20.23, -0.710000, 153662 +CTUN, 605, 0.00, 98.48, 0.000000, 0.00, 57, 83, 567, 0 +ATT, 6.27, 6.60, -35.00, -29.11, 0.10, 24.66, 23.83 +MOT, 1555, 1637, 1530, 1612 +CTUN, 605, 0.00, 98.99, 0.000000, 0.00, 57, 90, 567, 0 +ATT, 6.27, 6.56, -35.00, -28.94, 0.20, 24.67, 23.83 +MOT, 1533, 1658, 1544, 1598 +GPS, 3, 109300800, 1774, 10, 1.65, -39.4899574, 176.7500321, 98.52, 140.80, 9.70, 20.48, -0.800000, 153863 +CTUN, 605, 0.00, 98.34, 0.000000, 0.00, 56, 105, 566, 0 +ATT, 6.27, 6.55, -35.00, -28.95, 0.00, 24.75, 23.83 +MOT, 1533, 1651, 1560, 1586 +CTUN, 605, 0.00, 98.85, 0.000000, 0.00, 57, 103, 564, 0 +ATT, 6.27, 6.44, -35.00, -29.24, 0.00, 24.75, 23.83 +MOT, 1546, 1642, 1541, 1594 +DU32, 7, 270713 +CURR, 569, 375254, 1486, 4500, 4897, 710.8842 +PM, 0, 0, 0, 1000, 10201, 0, 0, 0, 0 +GPS, 3, 109301000, 1774, 10, 1.65, -39.4899410, 176.7500401, 98.75, 141.02, 9.75, 20.72, -0.930000, 154063 +CTUN, 605, 0.00, 99.03, 0.000000, 0.00, 58, 109, 568, 0 +ATT, 6.27, 6.30, -35.00, -29.39, 0.00, 24.88, 23.83 +MOT, 1544, 1644, 1552, 1596 +CTUN, 605, 0.00, 99.23, 0.000000, 0.00, 59, 105, 569, 0 +ATT, 6.27, 6.11, -35.00, -29.60, 0.00, 24.90, 23.83 +MOT, 1537, 1651, 1545, 1607 +GPS, 3, 109301200, 1774, 10, 1.65, -39.4899245, 176.7500481, 99.02, 141.26, 9.73, 20.51, -1.020000, 154263 +CTUN, 605, 0.00, 98.87, 0.000000, 0.00, 59, 112, 569, 0 +ATT, 6.27, 5.98, -35.00, -29.56, 0.20, 24.91, 23.83 +MOT, 1541, 1653, 1547, 1598 +CTUN, 605, 0.00, 99.39, 0.000000, 0.00, 59, 114, 569, 0 +ATT, 6.27, 5.89, -35.00, -29.55, 0.00, 24.89, 23.83 +MOT, 1547, 1642, 1556, 1594 +GPS, 3, 109301400, 1774, 10, 1.65, -39.4899081, 176.7500560, 99.27, 141.50, 9.65, 20.51, -1.060000, 154463 +CTUN, 605, 0.00, 99.20, 0.000000, 0.00, 58, 119, 568, 0 +ATT, 6.19, 5.88, -35.00, -29.47, 0.10, 24.90, 23.83 +MOT, 1544, 1646, 1546, 1601 +CTUN, 605, 0.00, 99.20, 0.000000, 0.00, 58, 128, 568, 0 +ATT, 6.27, 5.93, -35.00, -29.45, 0.10, 24.88, 23.83 +MOT, 1546, 1647, 1541, 1602 +GPS, 3, 109301600, 1774, 10, 1.65, -39.4898918, 176.7500637, 99.53, 141.78, 9.57, 20.46, -1.130000, 154664 +CTUN, 605, 0.00, 100.01, 0.000000, 0.00, 57, 132, 567, 0 +ATT, 6.27, 6.40, -35.00, -28.86, 0.00, 24.77, 23.83 +MOT, 1537, 1661, 1526, 1609 +CTUN, 605, 0.00, 99.55, 0.000000, 0.00, 55, 151, 565, 0 +ATT, 6.27, 6.41, -35.00, -28.58, 0.00, 24.70, 23.83 +MOT, 1555, 1633, 1530, 1609 +GPS, 3, 109301800, 1774, 10, 1.65, -39.4898755, 176.7500715, 99.86, 142.05, 9.59, 20.35, -1.210000, 154864 +CTUN, 605, 0.00, 100.11, 0.000000, 0.00, 54, 151, 564, 0 +ATT, 6.05, 6.77, -35.00, -28.44, 0.00, 24.61, 23.83 +MOT, 1551, 1640, 1549, 1583 +CTUN, 605, 0.00, 100.59, 0.000000, 0.00, 54, 161, 564, 0 +ATT, 6.27, 6.99, -35.00, -28.07, 0.00, 24.59, 23.83 +MOT, 1540, 1653, 1516, 1612 +DU32, 7, 270713 +CURR, 563, 380921, 1467, 4529, 4897, 723.4895 +GPS, 3, 109302000, 1774, 10, 1.65, -39.4898594, 176.7500793, 100.23, 142.39, 9.46, 20.69, -1.390000, 155065 +CTUN, 605, 0.00, 100.44, 0.000000, 0.00, 53, 177, 563, 0 +ATT, 6.27, 7.00, -35.00, -27.81, 0.10, 24.63, 23.83 +MOT, 1547, 1641, 1525, 1606 +ERR, 9, 1 +CTUN, 605, 0.00, 100.60, 0.000000, 0.00, 53, 182, 563, 0 +ATT, 6.49, 6.53, -35.00, -27.92, 0.00, 24.64, 23.83 +MOT, 1525, 1657, 1525, 1611 +GPS, 3, 109302200, 1774, 10, 1.65, -39.4898436, 176.7500872, 100.65, 142.73, 9.39, 21.39, -1.550000, 155264 +CTUN, 605, 0.00, 100.74, 0.000000, 0.00, 52, 202, 562, 0 +ATT, 6.49, 6.15, -35.00, -27.90, 0.00, 24.78, 23.83 +MOT, 1545, 1633, 1553, 1586 +CTUN, 605, 0.00, 101.14, 0.000000, 0.00, 51, 208, 561, 0 +ATT, 6.70, 5.61, -35.00, -27.66, 0.00, 25.02, 23.83 +MOT, 1552, 1621, 1528, 1613 +GPS, 3, 109302400, 1774, 10, 1.65, -39.4898280, 176.7500952, 101.12, 143.13, 9.32, 21.66, -1.760000, 155465 +CTUN, 605, 0.00, 101.16, 0.000000, 0.00, 51, 223, 561, 0 +ATT, 6.49, 5.65, -35.00, -27.84, 0.00, 25.08, 23.83 +MOT, 1528, 1649, 1550, 1587 +CTUN, 605, 0.00, 101.28, 0.000000, 0.00, 53, 232, 563, 0 +ATT, 6.49, 5.75, -35.00, -28.07, 0.00, 25.01, 23.83 +MOT, 1511, 1667, 1521, 1616 +GPS, 3, 109302600, 1774, 10, 1.65, -39.4898124, 176.7501031, 101.61, 143.60, 9.19, 21.74, -1.960000, 155665 +CTUN, 605, 0.00, 101.81, 0.000000, 0.00, 52, 237, 562, 0 +ATT, 6.49, 5.68, -35.00, -28.10, 0.00, 24.88, 23.83 +MOT, 1529, 1657, 1546, 1584 +CTUN, 605, 0.00, 101.81, 0.000000, 0.00, 53, 241, 563, 0 +ATT, 6.41, 5.29, -35.00, -28.35, 0.00, 24.77, 23.83 +MOT, 1550, 1635, 1524, 1610 +GPS, 3, 109302800, 1774, 10, 1.65, -39.4897970, 176.7501107, 102.13, 144.10, 9.07, 21.20, -2.100000, 155866 +CTUN, 605, 0.00, 102.30, 0.000000, 0.00, 54, 244, 564, 0 +ATT, 6.70, 6.07, -35.00, -28.52, 0.10, 24.69, 23.83 +MOT, 1539, 1647, 1562, 1575 +CTUN, 605, 0.00, 102.35, 0.000000, 0.00, 54, 245, 564, 0 +ATT, 6.41, 5.64, -35.00, -28.50, 0.10, 24.79, 23.83 +MOT, 1565, 1618, 1530, 1610 +DU32, 7, 270713 +CURR, 564, 386546, 1437, 4411, 4918, 735.9553 +GPS, 3, 109303000, 1774, 10, 1.65, -39.4897816, 176.7501182, 102.66, 144.60, 9.08, 20.98, -2.210000, 156066 +CTUN, 605, 0.00, 102.37, 0.000000, 0.00, 54, 248, 564, 0 +ATT, 6.49, 5.70, -35.00, -28.51, 0.10, 24.78, 23.83 +MOT, 1530, 1656, 1557, 1580 +CTUN, 605, 0.00, 103.30, 0.000000, 0.00, 56, 254, 566, 0 +ATT, 6.70, 5.99, -35.00, -28.96, 0.10, 24.70, 23.83 +MOT, 1525, 1664, 1528, 1612 +GPS, 3, 109303200, 1774, 10, 1.65, -39.4897662, 176.7501255, 103.19, 145.11, 9.01, 20.23, -2.290000, 156266 +CTUN, 605, 0.00, 103.28, 0.000000, 0.00, 56, 247, 566, 0 +ATT, 6.49, 5.58, -35.00, -28.98, 0.10, 24.69, 23.83 +MOT, 1541, 1648, 1530, 1610 +CTUN, 605, 0.00, 103.66, 0.000000, 0.00, 56, 257, 566, 0 +ATT, 6.49, 5.93, -35.00, -29.06, 0.10, 24.59, 23.83 +MOT, 1534, 1661, 1555, 1581 +GPS, 3, 109303400, 1774, 10, 1.65, -39.4897510, 176.7501327, 103.75, 145.63, 8.91, 20.35, -2.360000, 156466 +CTUN, 605, 0.00, 104.04, 0.000000, 0.00, 59, 254, 569, 0 +ATT, 6.70, 6.21, -35.00, -29.66, 0.20, 24.37, 23.83 +MOT, 1549, 1651, 1535, 1605 +CTUN, 605, 0.00, 103.82, 0.000000, 0.00, 61, 242, 571, 0 +ATT, 6.49, 6.32, -35.00, -30.06, 0.00, 24.23, 23.83 +MOT, 1572, 1631, 1555, 1588 +GPS, 3, 109303600, 1774, 10, 1.65, -39.4897360, 176.7501398, 104.29, 146.17, 8.83, 20.26, -2.450000, 156667 +CTUN, 605, 0.00, 104.80, 0.000000, 0.00, 63, 239, 573, 0 +ATT, 6.49, 6.17, -35.00, -30.66, 0.00, 24.10, 23.83 +MOT, 1547, 1659, 1537, 1614 +CTUN, 605, 0.00, 104.79, 0.000000, 0.00, 65, 226, 575, 0 +ATT, 6.70, 5.97, -35.00, -31.10, 0.00, 24.06, 23.83 +MOT, 1582, 1633, 1552, 1596 +GPS, 3, 109303800, 1774, 10, 1.65, -39.4897211, 176.7501467, 104.82, 146.68, 8.74, 20.03, -2.410000, 156867 +CTUN, 605, 0.00, 104.84, 0.000000, 0.00, 68, 215, 578, 0 +ATT, 6.70, 6.23, -35.00, -31.56, 0.00, 23.98, 23.83 +MOT, 1558, 1653, 1568, 1594 +CTUN, 605, 0.00, 104.65, 0.000000, 0.00, 70, 206, 580, 0 +ATT, 6.70, 6.15, -35.00, -31.95, 0.00, 23.92, 23.83 +MOT, 1557, 1664, 1557, 1601 +DU32, 7, 270713 +CURR, 580, 392248, 1482, 4564, 4897, 748.5086 +GPS, 3, 109304000, 1774, 10, 1.65, -39.4897063, 176.7501535, 105.25, 147.15, 8.68, 19.65, -2.260000, 157067 +CTUN, 605, 0.00, 104.73, 0.000000, 0.00, 71, 188, 581, 0 +ATT, 6.70, 6.13, -35.00, -32.19, 0.00, 23.86, 23.83 +MOT, 1564, 1661, 1567, 1592 +CTUN, 605, 0.00, 105.85, 0.000000, 0.00, 73, 181, 583, 0 +ATT, 6.70, 6.14, -35.00, -32.55, 0.00, 23.75, 23.83 +MOT, 1561, 1665, 1564, 1600 +GPS, 3, 109304200, 1774, 10, 1.65, -39.4896916, 176.7501600, 105.62, 147.57, 8.61, 18.91, -2.050000, 157267 +CTUN, 605, 0.00, 106.40, 0.000000, 0.00, 74, 171, 584, 0 +ATT, 6.70, 6.31, -35.00, -32.80, 0.00, 23.71, 23.83 +MOT, 1573, 1649, 1570, 1600 +CTUN, 605, 0.00, 106.31, 0.000000, 0.00, 74, 158, 584, 0 +ATT, 6.70, 6.24, -35.00, -32.73, 0.00, 23.76, 23.83 +MOT, 1559, 1665, 1573, 1596 +GPS, 3, 109304400, 1774, 10, 1.65, -39.4896769, 176.7501664, 106.04, 147.93, 8.58, 18.48, -1.860000, 157467 +CTUN, 605, 0.00, 106.11, 0.000000, 0.00, 73, 151, 583, 0 +ATT, 6.70, 6.22, -35.00, -32.51, 0.00, 23.84, 23.83 +MOT, 1554, 1672, 1559, 1605 +CTUN, 605, 0.00, 106.49, 0.000000, 0.00, 72, 151, 582, 0 +ATT, 6.70, 6.29, -35.00, -32.28, 0.00, 23.76, 23.83 +MOT, 1559, 1669, 1559, 1600 +GPS, 3, 109304600, 1774, 10, 1.65, -39.4896621, 176.7501725, 106.40, 148.26, 8.64, 17.80, -1.700000, 157668 +CTUN, 605, 0.00, 106.20, 0.000000, 0.00, 71, 153, 581, 0 +ATT, 6.70, 6.34, -35.00, -32.11, 0.00, 23.78, 23.83 +MOT, 1575, 1646, 1564, 1597 +CTUN, 605, 0.00, 106.26, 0.000000, 0.00, 71, 157, 581, 0 +ATT, 6.70, 6.42, -35.00, -31.99, 0.00, 23.84, 23.83 +MOT, 1564, 1655, 1556, 1607 +GPS, 3, 109304800, 1774, 10, 1.65, -39.4896471, 176.7501786, 106.70, 148.60, 8.70, 17.43, -1.650000, 157868 +CTUN, 605, 0.00, 106.80, 0.000000, 0.00, 69, 148, 579, 0 +ATT, 6.70, 6.43, -35.00, -31.63, 0.00, 23.94, 23.83 +MOT, 1546, 1672, 1571, 1587 +CTUN, 605, 0.00, 107.32, 0.000000, 0.00, 69, 145, 579, 0 +ATT, 0.00, 5.99, 0.00, -31.68, 0.00, 23.96, 23.83 +MOT, 1550, 1665, 1551, 1609 +MODE, RTL, 271 +ERR, 5, 1 +NTUN, 0.00, 1.94, 0.000000, 0.000000, 0.000000, 0.000000, 811.7078, 246.9585, 0.000000, 0.000000, 5.98, -31.63 +DU32, 7, 270713 +CURR, 578, 398064, 1493, 4659, 4918, 761.2452 +GPS, 3, 109305000, 1774, 10, 1.65, -39.4896320, 176.7501846, 107.04, 148.94, 8.76, 17.18, -1.640000, 158069 +CTUN, 0, 0.00, 107.63, 106.9908, 0.00, 77, 140, 646, 0 +ATT, 0.00, 5.96, 0.00, -31.48, 0.00, 23.80, 23.83 +MOT, 1845, 1369, 1950, 1231 +ERR, 5, 0 +NTUN, 625.49, 1.94, 1235.391, 375.9043, 476.6813, 145.0445, 813.9984, 235.1397, -337.0000, -99.00000, 2.34, 19.54 +CTUN, 605, 0.00, 106.94, 106.9908, 0.00, 124, 90, 796, 0 +ATT, 10.29, 3.61, -45.00, -35.85, 0.10, 20.72, 23.83 +MOT, 1809, 1872, 1938, 1546 +NTUN, 626.36, 1.94, 1151.688, 351.6025, 459.5132, 140.2863, 797.9639, 209.7603, -544.1852, -141.5525, 3.57, 29.62 +GPS, 3, 109305200, 1774, 10, 1.65, -39.4896170, 176.7501905, 107.29, 149.24, 8.74, 16.93, -1.590000, 158269 +CTUN, 605, 0.00, 106.79, 106.9908, 0.00, 186, 40, 945, 0 +ATT, 10.20, -3.55, -45.00, -39.79, 0.10, 18.85, 23.83 +MOT, 1656, 1950, 1918, 1370 +NTUN, 627.20, 1.94, 1068.617, 329.3184, 441.7150, 136.1244, 794.4001, 177.5082, -565.2200, -116.2072, 3.57, 30.25 +CTUN, 605, 0.00, 106.32, 106.9908, 0.00, 217, 5, 979, 0 +ATT, 10.57, -18.85, -45.00, -38.15, 0.20, 19.11, 23.83 +MOT, 1241, 1864, 1572, 1127 +NTUN, 628.04, 1.94, 986.3828, 309.9365, 423.2056, 132.9777, 799.1141, 127.5548, -608.0937, -75.46729, 5.72, 31.43 +GPS, 3, 109305400, 1774, 10, 1.65, -39.4896020, 176.7501956, 107.26, 149.42, 8.61, 14.54, -1.140000, 158469 +CTUN, 605, 0.00, 105.87, 106.9908, 0.00, 143, 7, 783, 0 +ATT, 10.57, -29.97, -45.00, -24.69, 0.20, 12.42, 22.42 +MOT, 1271, 1950, 1293, 1205 +NTUN, 628.87, 1.94, 904.1836, 294.8281, 403.5948, 131.6006, 808.8745, 50.89818, -665.1084, -5.770905, 8.66, 33.22 +CTUN, 605, 0.00, 105.89, 106.9908, 0.00, 76, 29, 563, 0 +ATT, 10.85, -34.63, -45.00, -1.94, 0.20, 358.06, 8.06 +MOT, 1471, 1950, 1276, 1503 +NTUN, 629.68, 1.94, 820.8320, 286.8574, 382.1828, 133.5620, 774.8207, -54.05908, -733.2821, 119.8125, 10.18, 35.00 +GPS, 3, 109305600, 1774, 10, 1.65, -39.4895875, 176.7501986, 107.16, 149.46, 8.19, 9.39, -0.540000, 158669 +CTUN, 605, 0.00, 106.26, 106.9908, 0.00, 92, 61, 434, 0 +ATT, 11.41, -43.35, -45.00, 22.73, 0.00, 336.87, 346.87 +MOT, 1239, 1897, 1235, 1231 +NTUN, 630.41, 1.94, 739.0469, 288.5508, 359.1792, 140.2366, 673.9511, -160.7752, -739.7587, 289.0852, 5.77, 35.00 +CTUN, 605, 0.00, 105.68, 106.9908, 0.00, 198, 59, 526, 0 +ATT, 11.41, -60.33, -45.00, 37.61, 0.00, 312.01, 322.01 +MOT, 1457, 1789, 1534, 1498 +NTUN, 631.00, 1.94, 665.0859, 303.2285, 335.7863, 153.0929, 528.2927, -232.6928, -675.9294, 481.5632, -1.75, 35.00 +GPS, 3, 109305800, 1774, 10, 1.65, -39.4895738, 176.7501986, 107.14, 149.57, 7.75, 6.05, -0.620000, 158870 +CTUN, 602, 0.00, 104.52, 106.9908, 0.00, 7, 23, 461, 0 +ATT, 10.57, -75.58, -45.00, 42.19, 0.00, 289.42, 299.42 +MOT, 1453, 1533, 1514, 1440 +NTUN, 631.42, 1.94, 604.1875, 327.0537, 313.9003, 169.9179, 340.0601, -276.2674, -534.8596, 625.2494, -8.19, 35.00 +CTUN, 603, 0.00, 103.79, 106.9908, 0.00, -147, -35, 569, 0 +ATT, 7.51, -78.57, -38.57, 42.27, 0.20, 277.52, 287.52 +MOT, 1569, 1658, 1705, 1492 +NTUN, 631.63, 1.94, 561.6563, 359.5801, 295.8232, 189.3901, 153.9193, -290.6631, -324.7706, 730.7223, -7.69, 35.00 +DU32, 7, 270713 +CURR, 792, 404695, 1483, 4564, 4834, 770.2328 +GPS, 3, 109306000, 1774, 10, 1.65, -39.4895630, 176.7501948, 106.78, 149.73, 6.42, 0.53, -0.740000, 159070 +CTUN, 605, 0.00, 103.12, 106.9899, 0.00, 0, -94, 1000, 0 +ATT, 0.00, -71.48, -27.29, 40.54, 0.10, 279.18, 286.65 +MOT, 1555, 1764, 1950, 1460 +NTUN, 631.63, 1.94, 536.4297, 394.8818, 282.6924, 208.0983, -58.25970, -292.0712, -88.00821, 772.2295, 0.24, 35.00 +CTUN, 605, 0.00, 106.12, 106.9882, 0.00, 0, -126, 1000, 0 +ATT, 0.00, -58.10, -24.22, 35.07, 0.00, 301.74, 291.74 +MOT, 1250, 1225, 1456, 1127 +NTUN, 631.38, 1.94, 533.4102, 433.6162, 277.0552, 225.2218, -224.5737, -356.2780, 210.6276, 816.2355, 19.07, 35.00 +GPS, 3, 109306200, 1774, 10, 1.65, -39.4895582, 176.7501897, 106.25, 149.82, 3.97, 348.77, -0.530000, 159270 +CTUN, 605, 0.00, 106.09, 106.9857, 0.00, 0, -137, 1000, 0 +ATT, 0.00, -48.32, -18.63, 14.08, 0.00, 338.68, 328.68 +MOT, 1381, 1158, 1818, 1127 +NTUN, 630.94, 1.94, 548.7383, 476.7510, 277.7562, 241.3182, -310.1249, -435.4615, 431.0131, 880.1295, 35.00, 13.22 +CTUN, 605, 0.00, 104.79, 106.9823, 0.00, 0, -152, 1000, 0 +ATT, 0.00, -50.72, -13.78, -9.34, 0.00, 14.05, 4.05 +MOT, 1304, 1448, 1950, 1525 +NTUN, 630.35, 1.94, 581.9023, 526.8828, 284.2108, 257.3384, -323.7206, -510.0528, 491.4966, 847.8391, 35.00, -24.24 +GPS, 3, 109306400, 1774, 10, 1.65, -39.4895599, 176.7501842, 105.86, 149.77, 2.58, 337.59, -0.120000, 159470 +CTUN, 605, 0.00, 104.49, 106.9780, 0.00, 0, -183, 1000, 0 +ATT, 0.00, -59.89, -11.08, -21.92, 0.00, 44.07, 34.07 +MOT, 1288, 1368, 1950, 1429 +NTUN, 629.71, 1.94, 618.9063, 584.3594, 291.0594, 274.8127, -288.1436, -566.4642, 469.5681, 860.1778, 26.60, -35.00 +CTUN, 605, 0.00, 105.09, 106.9729, 0.00, 0, -238, 1000, 0 +ATT, 0.00, -69.64, -7.36, -25.82, 0.10, 68.31, 58.31 +MOT, 1357, 1633, 1950, 1757 +NTUN, 629.04, 1.94, 660.0039, 645.2188, 298.7920, 292.0985, -222.1008, -606.6698, 440.8907, 875.2231, 5.06, -35.00 +GPS, 3, 109306600, 1774, 10, 1.65, -39.4895672, 176.7501787, 105.26, 149.52, 3.91, 248.20, 0.570000, 159671 +CTUN, 605, 0.00, 104.40, 106.9670, 0.00, 0, -291, 1000, 0 +ATT, 0.00, -75.51, -6.52, -25.48, 0.10, 85.05, 75.05 +MOT, 1417, 1333, 1950, 1494 +NTUN, 628.42, 1.94, 695.9180, 709.4805, 304.2365, 310.1657, -129.5809, -619.2767, 376.4690, 904.8044, -8.32, -35.00 +CTUN, 605, 0.00, 104.20, 106.9602, 0.00, -204, -354, 796, 0 +ATT, 0.00, -79.17, -2.32, -24.27, 0.10, 100.16, 90.16 +MOT, 1340, 1424, 1950, 1496 +NTUN, 627.85, 1.94, 725.6641, 773.0742, 307.6432, 327.7427, -56.93126, -609.9177, 317.2957, 927.2127, -18.69, -35.00 +GPS, 3, 109306800, 1774, 10, 1.65, -39.4895736, 176.7501698, 104.45, 149.32, 4.92, 234.60, 0.940000, 159871 +CTUN, 605, 0.00, 103.37, 106.9525, 0.00, -416, -429, 584, 0 +ATT, 0.00, -82.76, -0.93, -22.75, 0.20, 114.10, 104.10 +MOT, 1387, 1387, 1924, 1512 +NTUN, 627.38, 1.94, 746.6406, 835.2422, 308.3490, 344.9398, -6.010325, -585.3898, 265.3326, 943.3974, -26.43, -35.00 +CTUN, 605, 0.00, 103.33, 106.9441, 0.00, -582, -506, 418, 0 +ATT, 0.00, -85.49, -0.09, -21.49, 0.00, 128.14, 118.14 +MOT, 1226, 1221, 1770, 1350 +NTUN, 626.99, 1.94, 755.7734, 893.8633, 305.6556, 361.5030, 28.52817, -554.4348, 226.8805, 953.3757, -33.01, -35.00 +DU32, 7, 270713 +CURR, 358, 413577, 1521, 2393, 4855, 779.6537 +GPS, 3, 109307000, 1774, 10, 1.65, -39.4895754, 176.7501599, 103.32, 149.03, 4.51, 239.98, 1.310000, 160071 +CTUN, 605, 0.00, 103.39, 106.9347, 0.00, -618, -581, 382, 0 +ATT, 0.00, -84.61, 0.00, -21.52, 0.00, 139.35, 129.35 +MOT, 1399, 1391, 1514, 1548 +NTUN, 626.68, 1.94, 757.8672, 948.6914, 301.1791, 377.0134, 57.08358, -517.2155, 206.0006, 958.1042, -35.00, -28.66 +CTUN, 607, 0.00, 102.93, 106.9245, 0.00, -74, -645, 926, 0 +ATT, 0.00, -73.69, 0.00, -22.63, 0.10, 142.32, 132.32 +MOT, 1818, 1869, 1950, 1879 +NTUN, 626.48, 1.94, 746.1094, 996.9775, 292.9480, 391.4474, 90.83958, -440.2201, 171.7545, 964.8318, -35.00, -25.35 +GPS, 3, 109307200, 1774, 10, 1.65, -39.4895749, 176.7501501, 101.99, 148.43, 4.37, 251.64, 1.950000, 160272 +CTUN, 605, 0.00, 103.69, 106.9180, 0.00, 0, -661, 1000, 0 +ATT, 0.00, -54.33, 0.00, -22.08, 0.20, 140.34, 132.34 +MOT, 1733, 1172, 1201, 1950 +NTUN, 626.38, 1.93, 737.8672, 1041.070, 286.3396, 404.0018, 121.9568, -329.5644, 167.3953, 965.5976, -35.00, -25.28 +CTUN, 605, 0.00, 103.87, 106.9140, 0.00, 0, -623, 1000, 0 +ATT, 0.00, -17.94, 0.00, -11.57, 0.10, 136.40, 132.34 +MOT, 1215, 1187, 1127, 1410 +NTUN, 626.38, 1.93, 724.5234, 1072.183, 279.2793, 413.2902, 117.7836, -288.9771, 162.5869, 966.4189, -35.00, -28.26 +GPS, 3, 109307400, 1774, 10, 1.65, -39.4895710, 176.7501422, 100.86, 147.34, 4.23, 270.38, 3.020000, 160472 +CTUN, 603, 0.00, 101.47, 106.9105, 0.00, 0, -554, 1000, 0 +ATT, 0.00, 22.33, 0.00, 5.21, 0.00, 142.73, 132.73 +MOT, 1560, 1317, 1127, 1826 +NTUN, 626.41, 1.93, 709.4297, 1095.600, 271.7639, 419.6956, 79.96101, -329.7435, 178.4351, 963.6187, -35.00, -28.11 +CTUN, 605, 0.00, 99.43, 106.9060, 0.00, 0, -481, 1000, 0 +ATT, 0.00, 54.18, 0.00, 10.71, 0.10, 155.52, 145.52 +MOT, 1950, 1537, 1343, 1883 +NTUN, 626.43, 1.93, 689.0547, 1115.125, 262.8296, 425.3477, 29.64819, -460.4289, 189.0110, 961.6001, -35.00, -18.37 +GPS, 3, 109307600, 1774, 10, 1.65, -39.4895693, 176.7501394, 99.81, 145.84, 2.41, 280.24, 3.980000, 160672 +CTUN, 605, 0.00, 98.67, 106.9007, 0.00, 0, -489, 1000, 0 +ATT, 0.00, 78.36, 0.00, 7.95, 0.10, 163.50, 153.50 +MOT, 1950, 1288, 1470, 1732 +NTUN, 626.39, 1.93, 670.0117, 1142.883, 252.8727, 431.3414, -29.72285, -607.2896, 201.1700, 959.1302, -35.00, -7.41 +ERR, 9, 0 +CTUN, 605, 0.00, 98.99, 106.8946, 0.00, -870, -555, 130, 0 +ATT, 0.00, 91.47, 0.00, 3.49, 0.00, 156.90, 153.60 +MOT, 1401, 1127, 1319, 1197 +NTUN, 626.26, 1.93, 653.9766, 1178.352, 242.6334, 437.1830, -96.73808, -739.2455, 218.7059, 955.2841, -35.00, -4.93 +GPS, 3, 109307800, 1774, 10, 1.65, -39.4895675, 176.7501345, 98.56, 144.92, 2.56, 289.93, 3.940000, 160873 +CTUN, 608, 0.00, 99.61, 106.8876, 0.00, -870, -638, 130, 0 +ATT, 0.00, 89.13, 0.00, -0.44, 0.10, 140.66, 150.66 +MOT, 1408, 1234, 1385, 1127 +NTUN, 626.03, 1.93, 642.1602, 1225.878, 232.0130, 442.9108, -182.7007, -836.3657, 241.8324, 949.6931, -35.00, -15.65 +CTUN, 605, 0.00, 98.36, 106.8798, 0.00, -266, -719, 734, 0 +ATT, 0.00, 76.79, 0.00, -7.25, 0.00, 122.41, 132.41 +MOT, 1918, 1950, 1795, 1784 +NTUN, 625.70, 1.93, 636.7656, 1283.848, 222.1659, 447.9311, -292.3903, -909.1473, 284.9275, 937.6653, -35.00, -27.87 +DU32, 7, 270713 +CURR, 1000, 420534, 1561, 1209, 4616, 788.4255 +GPS, 3, 109308000, 1774, 10, 1.65, -39.4895668, 176.7501238, 97.16, 144.05, 4.22, 280.93, 3.990000, 161073 +CTUN, 605, 0.00, 96.31, 106.8711, 0.00, 0, -771, 1000, 0 +ATT, 0.00, 63.27, 0.00, -15.03, 0.00, 109.79, 119.79 +MOT, 1950, 1726, 1541, 1695 +NTUN, 625.21, 1.93, 639.2617, 1349.182, 214.0912, 451.8462, -451.8521, -958.2631, 348.0969, 916.0942, -35.00, -34.57 +CTUN, 605, 0.00, 96.28, 106.8615, 0.00, 0, -783, 1000, 0 +ATT, 0.00, 53.72, 0.00, -23.98, 0.20, 101.73, 111.73 +MOT, 1950, 1661, 1677, 1759 +NTUN, 624.53, 1.93, 655.6016, 1426.131, 208.8427, 454.2958, -626.0864, -965.0202, 434.5451, 878.3909, -32.12, -35.00 +GPS, 3, 109308200, 1774, 10, 1.65, -39.4895703, 176.7501095, 95.45, 142.50, 6.07, 265.26, 4.850000, 161273 +CTUN, 605, 0.00, 95.93, 106.8512, 0.00, 0, -771, 1000, 0 +ATT, 0.00, 47.13, 0.00, -32.29, 0.00, 95.11, 105.11 +MOT, 1950, 1734, 1761, 1775 +NTUN, 623.67, 1.93, 687.5273, 1506.539, 207.5861, 454.8715, -780.5817, -919.5109, 528.2693, 825.4282, -30.16, -35.00 +CTUN, 605, 0.00, 96.25, 106.8400, 0.00, 0, -740, 1000, 0 +ATT, 0.00, 40.28, 0.00, -36.26, 0.00, 91.46, 101.46 +MOT, 1950, 1659, 1611, 1797 +NTUN, 622.63, 1.93, 737.8516, 1587.854, 210.7045, 453.4353, -946.8992, -835.1133, 619.0580, 759.7152, -28.77, -35.00 +GPS, 3, 109308400, 1774, 10, 1.65, -39.4895771, 176.7500967, 93.96, 140.71, 6.59, 243.25, 5.700000, 161473 +CTUN, 605, 0.00, 95.83, 106.8279, 0.00, 0, -677, 1000, 0 +ATT, 0.00, 34.75, 0.00, -39.16, 0.00, 87.43, 97.43 +MOT, 1950, 1661, 1644, 1752 +NTUN, 621.45, 1.93, 802.8945, 1662.299, 217.4636, 450.2328, -1082.753, -724.8730, 698.9538, 686.9234, -29.36, -35.00 +CTUN, 605, 0.00, 95.55, 106.8150, 0.00, 0, -618, 1000, 0 +ATT, 0.00, 32.05, 0.00, -41.19, 0.00, 82.67, 92.67 +MOT, 1950, 1651, 1695, 1649 +NTUN, 620.15, 1.93, 885.1250, 1723.182, 228.4530, 444.7575, -1165.760, -598.9265, 761.4490, 616.9240, -28.86, -34.68 +GPS, 3, 109308600, 1774, 10, 1.65, -39.4895889, 176.7500861, 92.84, 139.21, 7.59, 219.65, 5.950000, 161674 +CTUN, 605, 0.00, 94.71, 106.8011, 0.00, 0, -584, 1000, 0 +ATT, 0.00, 30.55, 0.00, -42.98, 0.00, 76.55, 86.55 +MOT, 1950, 1616, 1586, 1665 +NTUN, 618.78, 1.93, 976.4297, 1770.481, 241.4652, 437.8293, -1237.568, -482.2914, 806.2280, 557.1323, -27.54, -35.00 +CTUN, 605, 0.00, 94.45, 106.7867, 0.00, 0, -549, 1000, 0 +ATT, 0.00, 30.84, 0.00, -44.32, 0.00, 69.10, 79.10 +MOT, 1950, 1634, 1601, 1631 +NTUN, 617.36, 1.93, 1078.125, 1798.336, 257.0941, 428.8386, -1292.612, -365.5301, 847.6306, 491.8560, -26.23, -35.00 +GPS, 3, 109308800, 1774, 10, 1.65, -39.4896040, 176.7500808, 91.87, 138.15, 8.44, 199.22, 5.710000, 161874 +CTUN, 605, 0.00, 93.88, 106.7711, 0.00, 0, -531, 1000, 0 +ATT, 0.00, 31.91, 0.00, -45.31, 0.00, 60.60, 70.60 +MOT, 1950, 1638, 1607, 1619 +NTUN, 615.92, 1.93, 1184.375, 1811.837, 273.5782, 418.5152, -1325.614, -244.3797, 877.8202, 435.6969, -23.83, -35.00 +CTUN, 605, 0.00, 93.55, 106.7548, 0.00, 0, -514, 1000, 0 +ATT, 0.00, 34.14, 0.00, -46.24, 0.00, 50.47, 60.47 +MOT, 1950, 1572, 1565, 1578 +NTUN, 614.51, 1.93, 1293.250, 1802.732, 291.4518, 406.2707, -1336.823, -127.0351, 906.3613, 372.7051, -20.95, -35.00 +DU32, 7, 270713 +CURR, 1000, 430534, 1387, 5844, 4876, 807.2175 +GPS, 3, 109309000, 1774, 10, 1.65, -39.4896207, 176.7500813, 91.01, 137.38, 9.17, 181.44, 5.260000, 162074 +CTUN, 605, 0.00, 93.30, 106.7376, 0.00, 0, -509, 1000, 0 +ATT, 0.00, 38.10, 0.00, -47.31, 0.00, 38.51, 48.51 +MOT, 1950, 1585, 1581, 1583 +NTUN, 613.14, 1.93, 1402.234, 1778.488, 309.5724, 392.6383, -1331.628, -15.43563, 927.5319, 316.3617, -16.63, -35.00 +CTUN, 605, 0.00, 93.89, 106.7196, 0.00, 0, -518, 1000, 0 +ATT, 0.00, 43.47, 0.00, -48.18, 0.00, 24.81, 34.81 +MOT, 1950, 1549, 1566, 1574 +NTUN, 611.86, 1.93, 1505.504, 1732.763, 327.9348, 377.4371, -1309.987, 90.43272, 944.7438, 260.4977, -10.79, -35.00 +GPS, 3, 109309200, 1774, 10, 1.65, -39.4896368, 176.7500860, 90.21, 136.70, 9.34, 168.53, 4.860000, 162274 +CTUN, 605, 0.00, 93.81, 106.7006, 0.00, 0, -538, 1000, 0 +ATT, 0.00, 49.58, 0.00, -48.22, 0.00, 9.72, 19.72 +MOT, 1950, 1615, 1605, 1617 +NTUN, 610.67, 1.93, 1603.777, 1673.038, 346.0032, 360.9457, -1267.905, 189.5441, 957.1492, 210.3930, -3.26, -35.00 +CTUN, 605, 0.00, 93.80, 106.6811, 0.00, 0, -564, 1000, 0 +ATT, 0.00, 57.22, 0.00, -47.55, 0.00, 352.41, 2.41 +MOT, 1950, 1557, 1624, 1558 +NTUN, 609.62, 1.93, 1689.992, 1596.900, 363.4211, 343.4023, -1210.072, 279.8782, 967.4070, 156.6004, 5.09, -35.00 +GPS, 3, 109309400, 1774, 10, 1.65, -39.4896509, 176.7500943, 89.46, 136.03, 8.94, 156.79, 4.590000, 162475 +CTUN, 605, 0.00, 93.00, 106.6604, 0.00, 0, -598, 1000, 0 +ATT, 0.00, 65.34, 0.00, -45.55, 0.00, 333.48, 343.48 +MOT, 1950, 1588, 1578, 1552 +NTUN, 608.70, 1.93, 1766.344, 1508.796, 380.1822, 324.7484, -1127.765, 356.6176, 973.7379, 110.6085, 15.29, -35.00 +CTUN, 605, 0.00, 92.45, 106.6392, 0.00, 0, -642, 1000, 0 +ATT, 0.00, 73.07, 0.00, -42.40, 0.00, 313.65, 323.65 +MOT, 1950, 1573, 1589, 1497 +NTUN, 607.97, 1.93, 1824.480, 1409.027, 395.7263, 305.6153, -1023.186, 411.7567, 977.6873, 67.28786, 24.83, -35.00 +GPS, 3, 109309600, 1774, 10, 1.65, -39.4896635, 176.7501055, 88.53, 135.19, 8.66, 147.34, 4.540000, 162675 +CTUN, 605, 0.00, 92.26, 106.6180, 0.00, -226, -693, 774, 0 +ATT, 0.00, 80.26, 0.00, -38.21, 0.00, 293.00, 303.00 +MOT, 1950, 1525, 1633, 1540 +NTUN, 607.40, 1.94, 1870.340, 1302.120, 410.3483, 285.6822, -892.8578, 442.7764, 979.6035, 27.87698, 32.93, -27.68 +CTUN, 605, 0.00, 92.23, 106.5969, 0.00, -608, -750, 392, 0 +ATT, 0.00, 86.42, 0.00, -31.95, 0.00, 272.14, 282.14 +MOT, 1558, 1135, 1443, 1258 +NTUN, 607.05, 1.94, 1894.629, 1190.492, 423.3603, 266.0189, -749.3270, 433.1040, 979.9940, 3.435690, 35.00, -12.03 +GPS, 3, 109309800, 1774, 10, 1.65, -39.4896719, 176.7501197, 87.42, 134.17, 7.82, 132.77, 4.720000, 162875 +CTUN, 605, 0.00, 91.33, 106.5757, 0.00, -593, -808, 407, 0 +ATT, 0.00, 83.72, 0.00, -26.12, 0.00, 254.44, 264.44 +MOT, 1461, 1293, 1730, 1537 +NTUN, 606.88, 1.94, 1902.102, 1078.564, 434.9417, 246.6286, -601.0383, 383.9391, 980.0000, 0.056778, 35.00, 7.25 +CTUN, 605, 0.00, 90.09, 106.5546, 0.00, 0, -849, 1000, 0 +ATT, 0.00, 70.75, 0.00, -19.53, 0.00, 243.04, 253.04 +MOT, 1521, 1536, 1950, 1504 +NTUN, 606.93, 1.94, 1884.027, 971.0889, 444.4364, 229.0770, -414.4949, 276.3171, 979.5334, 30.23489, 35.00, 21.96 +DU32, 7, 270713 +CURR, 1000, 439048, 1461, 4030, 4897, 819.2295 +GPS, 3, 109310000, 1774, 10, 1.65, -39.4896763, 176.7501331, 86.09, 132.94, 6.44, 118.10, 5.070000, 163076 +CTUN, 605, 0.00, 90.30, 106.5332, 0.00, 0, -817, 1000, 0 +ATT, 0.00, 45.90, 0.00, -18.63, 0.00, 231.19, 241.19 +MOT, 1262, 1349, 1608, 1127 +NTUN, 607.17, 1.94, 1845.895, 871.6846, 452.1232, 213.5056, -297.8584, 137.5289, 971.3177, 130.1608, 35.00, 32.56 +CTUN, 605, 0.00, 87.98, 106.5121, 0.00, 0, -728, 1000, 0 +ATT, 0.00, 16.58, 0.00, -23.51, 0.00, 219.50, 229.50 +MOT, 1746, 1752, 1950, 1319 +NTUN, 607.54, 1.94, 1782.055, 791.4746, 456.9581, 202.9515, -276.7377, 24.07106, 939.9755, 277.2110, 23.98, 35.00 +GPS, 3, 109310200, 1774, 10, 1.65, -39.4896742, 176.7501411, 84.90, 131.82, 3.90, 110.38, 5.240000, 163276 +CTUN, 605, 0.00, 85.42, 106.4909, 0.00, 0, -622, 1000, 0 +ATT, 0.00, 0.41, 0.00, -36.29, 0.00, 213.36, 223.36 +MOT, 1950, 1542, 1866, 1241 +NTUN, 607.92, 1.94, 1709.406, 724.8564, 460.3244, 195.1959, -341.9768, -69.13911, 904.0232, 378.3414, 11.01, 35.00 +CTUN, 605, 0.00, 84.64, 106.4697, 0.00, 0, -555, 1000, 0 +ATT, 0.00, -4.20, 0.00, -56.06, 0.00, 213.49, 222.36 +MOT, 1950, 1429, 1724, 1432 +NTUN, 608.27, 1.94, 1629.340, 679.0381, 461.5237, 192.3430, -444.7347, -147.1507, 869.9585, 451.1898, 3.42, 35.00 +GPS, 3, 109310400, 1774, 10, 1.65, -39.4896677, 176.7501417, 83.75, 130.59, 3.04, 55.12, 5.470000, 163476 +CTUN, 605, 0.00, 83.32, 106.4486, 0.00, 0, -539, 1000, 0 +ATT, 0.00, 3.95, 0.00, -71.79, 0.00, 212.72, 222.36 +MOT, 1950, 1573, 1683, 1616 +NTUN, 608.51, 1.94, 1555.582, 644.0059, 461.9752, 191.2562, -565.5382, -247.5177, 856.0806, 476.9970, 2.21, 35.00 +CTUN, 605, 0.00, 82.25, 106.4274, 0.00, -143, -575, 857, 0 +ATT, 0.00, 35.61, 0.00, -77.92, 0.00, 191.60, 201.60 +MOT, 1950, 1201, 1490, 1922 +NTUN, 608.64, 1.94, 1485.770, 631.9170, 460.1136, 195.6923, -668.8723, -366.3332, 826.5912, 526.4476, -1.73, 35.00 +GPS, 3, 109310600, 1774, 10, 1.65, -39.4896633, 176.7501375, 82.48, 129.51, 3.00, 26.92, 5.390000, 163676 +CTUN, 603, 0.00, 83.34, 106.4063, 0.00, -104, -639, 896, 0 +ATT, 0.00, 65.22, 0.00, -75.94, 0.00, 169.05, 179.05 +MOT, 1398, 1362, 1585, 1950 +NTUN, 608.63, 1.94, 1425.313, 634.7881, 456.7491, 203.4213, -734.4034, -489.1974, 799.2764, 567.0601, -7.63, 35.00 +CTUN, 605, 0.00, 83.85, 106.3851, 0.00, 0, -690, 1000, 0 +ATT, 0.00, 46.78, 0.00, -64.99, 0.00, 193.42, 183.42 +MOT, 1242, 1165, 1127, 1740 +NTUN, 608.48, 1.94, 1375.316, 660.3027, 450.7422, 216.4057, -777.3533, -618.1238, 756.4160, 623.0849, -11.52, 35.00 +GPS, 3, 109310800, 1774, 10, 1.65, -39.4896620, 176.7501314, 81.17, 128.19, 2.84, 3.17, 5.560000, 163876 +CTUN, 605, 0.00, 83.17, 106.3637, 0.00, 0, -702, 1000, 0 +ATT, 0.00, 29.83, 0.00, -35.55, 0.00, 218.00, 208.00 +MOT, 1384, 1537, 1391, 1950 +NTUN, 608.24, 1.94, 1330.965, 701.5156, 442.3210, 233.1355, -765.3212, -705.0020, 715.1798, 670.0133, -9.03, 35.00 +CTUN, 605, 0.00, 81.95, 106.3426, 0.00, 0, -698, 1000, 0 +ATT, 0.00, 26.94, 0.00, 0.47, 0.00, 230.69, 220.69 +MOT, 1456, 1605, 1573, 1950 +NTUN, 607.93, 1.94, 1294.566, 758.9854, 431.3342, 252.8849, -703.9335, -750.1877, 672.3566, 712.9774, -1.48, 35.00 +DU32, 7, 270713 +CURR, 1000, 448843, 1453, 2867, 4918, 830.6562 +PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 +GPS, 3, 109311000, 1774, 10, 1.65, -39.4896658, 176.7501195, 79.89, 126.74, 4.48, 287.18, 5.870000, 164077 +CTUN, 605, 0.00, 82.14, 106.3214, 0.00, 0, -682, 1000, 0 +ATT, 0.00, 26.42, 0.00, 35.08, 0.00, 241.34, 231.34 +MOT, 1515, 1950, 1456, 1812 +NTUN, 607.65, 1.94, 1255.785, 824.0361, 418.0351, 274.3113, -622.4413, -737.4474, 630.1533, 750.5377, 6.08, 35.00 +CTUN, 605, 0.00, 82.21, 106.3003, 0.00, 0, -697, 1000, 0 +ATT, 0.00, 20.98, 0.00, 64.36, 0.00, 246.67, 236.87 +MOT, 1342, 1950, 1403, 1166 +NTUN, 607.39, 1.94, 1216.176, 895.3906, 402.6447, 296.4409, -533.7360, -674.2542, 593.5552, 779.8027, 7.89, 35.00 +GPS, 3, 109311200, 1774, 10, 1.65, -39.4896711, 176.7500995, 78.69, 125.44, 7.52, 255.84, 6.010000, 164277 +CTUN, 605, 0.00, 81.75, 106.2791, 0.00, -24, -728, 976, 0 +ATT, 0.00, -21.52, 0.00, 75.89, 0.00, 220.14, 230.14 +MOT, 1441, 1950, 1706, 1253 +NTUN, 607.22, 1.94, 1169.469, 963.7676, 385.8557, 317.9865, -466.3108, -592.7849, 569.4946, 797.5436, 1.26, 35.00 +CTUN, 605, 0.00, 81.48, 106.2580, 0.00, 0, -778, 1000, 0 +ATT, 0.00, -55.70, 0.00, 69.05, 0.00, 200.50, 210.16 +MOT, 1643, 1605, 1950, 1565 +NTUN, 607.09, 1.94, 1118.109, 1031.055, 367.5731, 338.9543, -421.4198, -494.7960, 552.7898, 809.2115, -8.46, 35.00 +GPS, 3, 109311400, 1774, 10, 1.65, -39.4896740, 176.7500796, 77.44, 124.37, 8.46, 259.08, 5.920000, 164477 +CTUN, 605, 0.00, 80.55, 106.2368, 0.00, 0, -811, 1000, 0 +ATT, 0.00, -50.69, 0.00, 54.61, 0.00, 218.26, 210.16 +MOT, 1395, 1445, 1748, 1127 +NTUN, 607.03, 1.93, 1061.949, 1090.884, 348.7701, 358.2728, -415.6103, -378.2093, 555.5469, 807.3213, -12.06, 35.00 +CTUN, 605, 0.00, 78.83, 106.2154, 0.00, 0, -825, 1000, 0 +ATT, 0.00, -44.42, 0.00, 31.61, 0.00, 241.23, 231.23 +MOT, 1590, 1587, 1851, 1127 +NTUN, 607.01, 1.93, 1001.320, 1139.513, 330.0443, 375.5938, -453.1321, -276.1216, 582.6448, 787.9880, -2.68, 35.00 +GPS, 3, 109311600, 1774, 9, 2.43, -39.4896736, 176.7500601, 76.02, 123.39, 8.41, 268.09, 5.780000, 164677 +CTUN, 602, 0.00, 77.66, 106.1943, 0.00, 0, -800, 1000, 0 +ATT, 0.00, -45.63, 0.00, 10.16, 0.00, 262.46, 252.46 +MOT, 1739, 1668, 1950, 1206 +NTUN, 606.98, 1.93, 942.5625, 1177.617, 312.4422, 390.3586, -544.3233, -210.9509, 629.4567, 751.1219, 19.23, 35.00 +CTUN, 605, 0.00, 77.61, 106.1731, 0.00, 0, -742, 1000, 0 +ATT, 0.00, -49.22, 0.00, -3.08, 0.00, 283.43, 273.43 +MOT, 1862, 1775, 1950, 1498 +NTUN, 606.90, 1.93, 887.9961, 1205.226, 296.5854, 402.5383, -659.9333, -234.5763, 681.9404, 703.8162, 35.00, 34.24 +GPS, 3, 109311800, 1774, 9, 2.43, -39.4896723, 176.7500419, 74.64, 122.63, 7.83, 271.41, 5.430000, 164878 +CTUN, 605, 0.00, 79.02, 106.1520, 0.00, 0, -686, 1000, 0 +ATT, 0.00, -52.93, 0.00, -8.56, 0.00, 304.13, 294.13 +MOT, 1427, 1644, 1950, 1363 +NTUN, 606.69, 1.93, 843.4688, 1231.235, 282.5803, 412.4905, -778.5619, -330.3637, 710.7822, 674.6768, 35.00, 18.76 +CTUN, 605, 0.00, 77.34, 106.1308, 0.00, 0, -645, 1000, 0 +ATT, 0.00, -57.02, 0.00, -10.19, 0.00, 325.27, 315.27 +MOT, 1606, 1326, 1950, 1677 +NTUN, 606.36, 1.93, 810.7656, 1263.882, 269.9711, 420.8511, -833.0995, -437.2181, 714.6117, 670.6191, 35.00, -1.34 +DU32, 7, 270713 +CURR, 1000, 458843, 1453, 4798, 4876, 842.8516 +GPS, 3, 109312000, 1774, 10, 1.65, -39.4896707, 176.7500251, 73.67, 122.50, 6.94, 268.68, 4.560000, 165078 +CTUN, 605, 0.00, 75.98, 106.1096, 0.00, 0, -642, 1000, 0 +ATT, 0.00, -53.08, 0.00, -11.13, 0.00, 343.07, 333.07 +MOT, 1466, 1450, 1946, 1950 +NTUN, 605.95, 1.93, 786.6641, 1306.694, 257.8857, 428.3631, -838.8315, -531.6833, 697.0085, 688.8970, 35.00, -19.35 +CTUN, 605, 0.00, 76.13, 106.0885, 0.00, 0, -639, 1000, 0 +ATT, 0.00, -38.05, 0.00, -11.96, 0.00, 354.45, 344.45 +MOT, 1318, 1343, 1633, 1950 +NTUN, 605.51, 1.93, 766.1250, 1362.041, 245.1250, 435.7909, -816.2412, -604.8326, 666.1210, 718.8066, 35.00, -28.08 +GPS, 3, 109312200, 1774, 10, 1.65, -39.4896711, 176.7500076, 72.62, 122.93, 6.98, 264.08, 3.390000, 165279 +CTUN, 605, 0.00, 75.26, 106.0671, 0.00, 0, -625, 1000, 0 +ATT, 0.00, -13.01, 0.00, -9.41, 0.00, 358.06, 348.06 +MOT, 1142, 1262, 1178, 1950 +NTUN, 605.06, 1.93, 743.8320, 1425.857, 231.2601, 443.3044, -791.2646, -631.1121, 635.2730, 746.2092, 35.00, -31.48 +CTUN, 605, 0.00, 75.17, 106.0462, 0.00, 0, -609, 1000, 0 +ATT, 0.00, 20.49, 0.00, 2.09, 0.00, 359.04, 349.04 +MOT, 1573, 1402, 1127, 1806 +NTUN, 604.61, 1.93, 721.6445, 1500.656, 216.6899, 450.6057, -768.2755, -615.0052, 614.7167, 763.2322, 35.00, -31.17 +GPS, 3, 109312400, 1774, 10, 1.65, -39.4896769, 176.7499949, 71.64, 121.44, 6.51, 257.75, 4.050000, 165479 +CTUN, 605, 0.00, 75.10, 106.0248, 0.00, 0, -618, 1000, 0 +ATT, 0.00, 52.31, 0.00, 12.12, 0.00, 3.38, 353.38 +MOT, 1807, 1416, 1127, 1591 +NTUN, 604.17, 1.93, 696.7266, 1576.664, 202.0967, 457.3367, -758.2792, -553.6387, 612.1394, 765.3007, 35.00, -32.34 +CTUN, 605, 0.00, 74.13, 106.0037, 0.00, 0, -656, 1000, 0 +ATT, 0.00, 76.02, 0.00, 13.79, 0.00, 3.64, 355.01 +MOT, 1950, 1384, 1296, 1315 +NTUN, 603.74, 1.93, 673.8086, 1648.731, 189.1547, 462.8396, -743.1379, -476.3700, 627.7534, 752.5462, 34.54, -35.00 +GPS, 3, 109312600, 1774, 10, 1.65, -39.4896827, 176.7499783, 70.64, 120.10, 7.70, 253.32, 4.450000, 165680 +CTUN, 605, 0.00, 73.00, 105.9825, 0.00, -348, -713, 652, 0 +ATT, 0.00, 80.47, 0.00, 11.49, 0.00, 354.37, 355.01 +MOT, 1950, 1567, 1443, 1302 +NTUN, 603.34, 1.93, 650.3672, 1713.130, 177.4605, 467.4482, -717.2687, -393.5936, 644.9492, 737.8621, 35.00, -33.20 +CTUN, 603, 0.00, 72.86, 105.9613, 0.00, -110, -777, 890, 0 +ATT, 0.00, 75.78, 0.00, 6.11, 0.00, 340.49, 350.49 +MOT, 1950, 1590, 1345, 1371 +NTUN, 602.99, 1.93, 624.6563, 1769.155, 166.4689, 471.4744, -671.6952, -314.4693, 657.0335, 727.1224, 35.00, -26.32 +GPS, 3, 109312800, 1774, 10, 1.65, -39.4896876, 176.7499596, 69.33, 117.33, 8.91, 267.03, 6.020000, 165880 +CTUN, 602, 0.00, 72.79, 105.9402, 0.00, 0, -831, 1000, 0 +ATT, 0.00, 69.91, 0.00, -3.08, 0.00, 326.59, 336.59 +MOT, 1950, 1506, 1672, 1562 +NTUN, 602.72, 1.93, 595.0430, 1816.809, 155.6261, 475.1637, -598.9000, -241.9769, 660.4778, 723.9952, 35.00, -15.48 +CTUN, 605, 0.00, 72.62, 105.9190, 0.00, 0, -865, 1000, 0 +ATT, 0.00, 66.39, 0.00, -13.04, 0.00, 312.28, 322.28 +MOT, 1906, 1638, 1950, 1812 +NTUN, 602.55, 1.93, 558.7539, 1855.866, 144.1458, 478.7713, -483.5654, -175.4013, 647.9259, 735.2496, 35.00, -0.57 +DU32, 7, 270713 +CURR, 1000, 468317, 1383, 6036, 4855, 852.1169 +GPS, 3, 109313000, 1774, 10, 1.65, -39.4896916, 176.7499407, 67.93, 115.96, 8.49, 259.32, 6.120000, 166080 +CTUN, 605, 0.00, 72.77, 105.8977, 0.00, 0, -872, 1000, 0 +ATT, 0.00, 59.04, 0.00, -23.23, 0.00, 296.11, 306.11 +MOT, 1225, 1147, 1520, 1127 +NTUN, 602.51, 1.93, 512.0898, 1887.287, 130.9339, 482.5518, -347.1010, -163.9697, 606.5880, 769.7084, 35.00, 16.16 +CTUN, 605, 0.00, 72.46, 105.8765, 0.00, 0, -865, 1000, 0 +ATT, 0.00, 45.00, 0.00, -36.80, 0.00, 278.81, 288.81 +MOT, 1336, 1427, 1950, 1469 +NTUN, 602.61, 1.93, 452.0703, 1914.758, 114.8903, 486.6212, -213.4912, -209.1951, 513.0965, 834.9443, 32.77, 33.78 +GPS, 3, 109313200, 1774, 10, 1.65, -39.4896968, 176.7499274, 66.66, 114.67, 6.75, 249.86, 6.200000, 166281 +CTUN, 605, 0.00, 70.36, 105.8553, 0.00, 0, -843, 1000, 0 +ATT, 0.00, 26.57, 0.00, -48.73, 0.00, 271.57, 281.57 +MOT, 1318, 1350, 1950, 1159 +NTUN, 602.82, 1.93, 378.5000, 1944.392, 95.53792, 490.7877, -111.7616, -315.1477, 383.0670, 902.0309, 18.50, 35.00 +CTUN, 605, 0.00, 69.22, 105.8342, 0.00, 0, -839, 1000, 0 +ATT, 0.00, 4.41, 0.00, -60.76, 0.00, 274.02, 280.88 +MOT, 1615, 1571, 1950, 1466 +NTUN, 603.09, 1.92, 294.5039, 1980.272, 73.55052, 494.5608, -46.79864, -457.0046, 256.7998, 945.7557, 9.07, 35.00 +GPS, 3, 109313400, 1774, 10, 1.65, -39.4897006, 176.7499218, 65.30, 113.27, 3.72, 247.96, 6.340000, 166481 +CTUN, 605, 0.00, 68.16, 105.8130, 0.00, 0, -849, 1000, 0 +ATT, 0.00, -20.23, 0.00, -69.57, 0.00, 290.99, 280.99 +MOT, 1841, 1624, 1950, 1509 +NTUN, 603.39, 1.92, 202.9414, 2028.521, 49.77356, 497.5164, -9.904141, -634.7659, 167.9452, 965.5021, 8.42, 35.00 +CTUN, 605, 0.00, 65.90, 105.7919, 0.00, 0, -880, 1000, 0 +ATT, 0.00, -58.28, 0.00, -72.63, 0.00, 325.61, 315.61 +MOT, 1437, 1950, 1616, 1321 +NTUN, 603.67, 1.92, 107.9844, 2088.087, 25.82274, 499.3327, -2.786196, -832.8705, 117.6979, 972.9066, 11.51, 35.00 +GPS, 3, 109313600, 1774, 10, 1.65, -39.4896986, 176.7499143, 63.71, 112.40, 3.40, 247.96, 6.030000, 166681 +CTUN, 605, 0.00, 65.82, 105.7707, 0.00, 0, -921, 1000, 0 +ATT, 0.00, -63.35, 0.00, -64.38, 0.00, 322.08, 320.93 +MOT, 1127, 1474, 1215, 1148 +NTUN, 603.91, 1.92, 11.57422, 2165.568, 2.672290, 499.9929, -25.88333, -1011.334, 95.63342, 975.3226, 17.82, 21.86 +CTUN, 605, 0.00, 65.16, 105.7493, 0.00, 0, -939, 1000, 0 +ATT, 0.00, -46.29, 0.00, -43.05, 0.00, 290.50, 300.50 +MOT, 1237, 1950, 1229, 1298 +NTUN, 604.11, 1.92, -85.27734, 2262.265, -18.83440, 499.6451, -74.46530, -1122.122, 101.2559, 974.7550, 20.57, 35.00 +GPS, 3, 109313800, 1774, 10, 1.65, -39.4896948, 176.7499005, 61.97, 111.52, 5.94, 287.51, 5.750000, 166881 +CTUN, 605, 0.00, 64.30, 105.7282, 0.00, 0, -933, 1000, 0 +ATT, 0.00, -39.60, 0.00, -10.08, 0.00, 266.54, 276.54 +MOT, 1634, 1950, 1500, 1525 +NTUN, 604.21, 1.92, -177.9492, 2372.841, -37.39208, 498.5999, -138.1259, -1155.972, 126.5079, 971.8002, 12.91, 35.00 +CTUN, 605, 0.00, 62.61, 105.7070, 0.00, 0, -907, 1000, 0 +ATT, 0.00, -43.62, 0.00, 21.97, 0.00, 246.53, 256.53 +MOT, 1237, 1950, 1522, 1514 +NTUN, 604.24, 1.92, -262.7969, 2493.957, -52.39663, 497.2470, -199.2726, -1109.896, 165.1311, 965.9874, -3.54, 35.00 +DU32, 7, 270713 +CURR, 1000, 478317, 1423, 3614, 4940, 861.0620 +GPS, 3, 109314000, 1774, 10, 1.65, -39.4896937, 176.7498824, 60.25, 109.33, 8.26, 285.70, 6.580000, 167082 +CTUN, 605, 0.00, 62.24, 105.6859, 0.00, 0, -909, 1000, 0 +ATT, 0.00, -57.78, 0.00, 41.48, 0.00, 224.69, 234.69 +MOT, 1572, 1950, 1904, 1706 +NTUN, 604.19, 1.92, -340.5195, 2613.760, -64.59393, 495.8101, -224.6234, -999.6001, 204.2917, 958.4701, -17.37, 35.00 +CTUN, 605, 0.00, 63.41, 105.6647, 0.00, 0, -950, 1000, 0 +ATT, 0.00, -72.97, 0.00, 52.48, 0.00, 201.39, 211.39 +MOT, 1414, 1564, 1950, 1756 +NTUN, 604.09, 1.92, -406.8984, 2726.511, -73.80157, 494.5233, -223.7670, -886.4194, 235.3489, 951.3206, -24.81, 35.00 +GPS, 3, 109314200, 1774, 10, 1.65, -39.4896932, 176.7498514, 58.56, 108.76, 12.24, 272.06, 5.890000, 167282 +CTUN, 605, 0.00, 63.08, 105.6436, 0.00, 0, -992, 1000, 0 +ATT, 0.00, -66.92, 0.00, 59.24, 0.00, 198.74, 205.86 +MOT, 1235, 1359, 1950, 1685 +NTUN, 603.98, 1.91, -470.6445, 2828.002, -82.08255, 493.2164, -210.5075, -769.7216, 248.9199, 947.8602, -25.45, 26.99 +CTUN, 603, 0.00, 62.47, 105.6224, 0.00, 0, -1029, 1000, 0 +ATT, 0.00, -40.65, 0.00, 58.60, 0.00, 217.78, 207.78 +MOT, 1397, 1328, 1950, 1754 +NTUN, 603.86, 1.91, -528.5977, 2921.806, -89.01240, 492.0130, -183.8832, -674.7067, 259.8592, 944.9197, -20.17, 34.01 +GPS, 3, 109314400, 1774, 9, 1.68, -39.4897001, 176.7498359, 56.93, 107.33, 8.32, 250.19, 6.060000, 167482 +CTUN, 605, 0.00, 61.32, 105.6010, 0.00, 0, -1046, 1000, 0 +ATT, 0.00, -16.93, 0.00, 47.69, 0.00, 236.34, 226.34 +MOT, 1634, 1458, 1950, 1815 +NTUN, 603.75, 1.91, -587.6953, 3006.146, -95.93289, 490.7106, -154.2102, -585.5060, 253.4210, 946.6666, -14.86, 35.00 +CTUN, 605, 0.00, 59.68, 105.5799, 0.00, 0, -1010, 1000, 0 +ATT, 0.00, -9.03, 0.00, 27.89, 0.00, 247.61, 237.61 +MOT, 1410, 1128, 1771, 1127 +NTUN, 603.63, 1.91, -638.0977, 3067.631, -101.8254, 489.5218, -137.2714, -510.2572, 254.0032, 946.5106, -9.44, 35.00 +GPS, 3, 109314600, 1774, 9, 1.68, -39.4897084, 176.7498265, 55.25, 105.73, 6.34, 233.39, 6.400000, 167682 +CTUN, 605, 0.00, 58.96, 105.5587, 0.00, 0, -933, 1000, 0 +ATT, 0.00, -15.28, 0.00, 1.06, 0.00, 258.04, 248.04 +MOT, 1441, 1451, 1917, 1127 +NTUN, 603.50, 1.91, -687.9063, 3117.163, -107.7492, 488.2521, -157.9182, -476.4375, 255.5554, 946.0927, -2.59, 35.00 +CTUN, 605, 0.00, 57.75, 105.5376, 0.00, 0, -844, 1000, 0 +ATT, 0.00, -27.62, 0.00, -15.39, 0.00, 271.57, 261.57 +MOT, 1378, 1587, 1950, 1161 +NTUN, 603.31, 1.91, -729.4063, 3147.284, -112.8867, 487.0899, -211.5943, -505.4050, 278.3556, 939.6373, 10.32, 35.00 +GPS, 3, 109314800, 1774, 10, 1.65, -39.4897172, 176.7498222, 53.81, 104.08, 4.91, 213.51, 6.680000, 167883 +CTUN, 605, 0.00, 56.52, 105.5164, 0.00, 0, -772, 1000, 0 +ATT, 0.00, -39.29, 0.00, -25.08, 0.00, 290.99, 280.99 +MOT, 1667, 1633, 1950, 1456 +NTUN, 603.04, 1.91, -764.7227, 3173.921, -117.1182, 486.0898, -276.8117, -580.7421, 309.5137, 929.8394, 24.41, 35.00 +CTUN, 603, 0.00, 55.59, 105.4953, 0.00, 0, -733, 1000, 0 +ATT, 0.00, -51.23, 0.00, -27.83, 0.00, 313.29, 303.29 +MOT, 1622, 1668, 1950, 1393 +NTUN, 602.67, 1.91, -787.5508, 3195.681, -119.6415, 485.4749, -329.3771, -681.7704, 339.6435, 919.2618, 35.00, 31.40 +DU32, 7, 270713 +CURR, 1000, 488317, 1404, 5819, 4940, 871.8691 +GPS, 3, 109315000, 1774, 10, 1.65, -39.4897267, 176.7498229, 52.53, 102.38, 4.49, 188.60, 6.840000, 168083 +CTUN, 605, 0.00, 56.27, 105.4739, 0.00, 0, -734, 1000, 0 +ATT, 0.00, -61.25, 0.00, -22.66, 0.00, 333.85, 323.85 +MOT, 1689, 1743, 1950, 1664 +NTUN, 602.20, 1.91, -803.1836, 3223.962, -120.8702, 485.1705, -364.4174, -797.0923, 350.0180, 915.3619, 35.00, 14.33 +CTUN, 605, 0.00, 56.44, 105.4529, 0.00, 0, -739, 1000, 0 +ATT, 0.00, -63.67, 0.00, -13.66, 0.00, 350.91, 340.91 +MOT, 1199, 1532, 1950, 1577 +NTUN, 601.64, 1.91, -807.2891, 3254.962, -120.3623, 485.2968, -382.0041, -922.4053, 351.5960, 914.7569, 35.00, -3.50 +GPS, 3, 109315200, 1774, 10, 1.65, -39.4897369, 176.7498195, 51.40, 101.30, 5.62, 195.72, 6.480000, 168283 +CTUN, 605, 0.00, 55.61, 105.4316, 0.00, 0, -746, 1000, 0 +ATT, 0.00, -58.13, 0.00, -2.59, 0.10, 0.60, 350.60 +MOT, 1369, 1354, 1496, 1950 +NTUN, 601.01, 1.91, -808.2148, 3296.178, -119.0716, 485.6150, -394.2592, -1021.971, 340.1804, 919.0632, 35.00, -16.74 +CTUN, 605, 0.00, 54.11, 105.4104, 0.00, 0, -732, 1000, 0 +ATT, 0.00, -35.25, 0.00, 11.25, 0.00, 3.62, 353.62 +MOT, 1251, 1266, 1290, 1950 +NTUN, 600.31, 1.91, -801.4766, 3347.944, -116.4077, 486.2605, -413.2569, -1079.439, 336.0268, 920.5900, 35.00, -20.76 +GPS, 3, 109315400, 1774, 10, 1.65, -39.4897484, 176.7498113, 50.29, 100.20, 7.03, 209.92, 6.200000, 168483 +CTUN, 605, 0.00, 53.52, 105.3893, 0.00, 0, -722, 1000, 0 +ATT, 0.00, 0.63, 0.00, 19.88, 0.00, 10.90, 0.90 +MOT, 1552, 1199, 1557, 1950 +NTUN, 599.55, 1.91, -791.4531, 3407.524, -113.1219, 487.0353, -449.6306, -1077.428, 343.4716, 917.8384, 35.00, -24.67 +CTUN, 605, 0.00, 53.03, 105.3681, 0.00, 0, -711, 1000, 0 +ATT, 0.00, 38.28, 0.00, 14.85, 0.00, 18.14, 8.14 +MOT, 1775, 1349, 1559, 1950 +NTUN, 598.72, 1.91, -774.2852, 3472.167, -108.8258, 488.0132, -497.3428, -1025.481, 364.1419, 909.8356, 35.00, -30.96 +GPS, 3, 109315600, 1774, 10, 1.65, -39.4897603, 176.7497979, 49.15, 99.16, 8.55, 222.10, 5.920000, 168684 +CTUN, 605, 0.00, 53.88, 105.3469, 0.00, 0, -716, 1000, 0 +ATT, 0.00, 62.23, 0.00, 6.41, 0.00, 27.85, 17.85 +MOT, 1676, 1655, 1458, 1950 +NTUN, 597.84, 1.91, -751.6563, 3534.305, -104.0110, 489.0621, -561.7349, -941.2330, 402.0710, 893.7220, 34.52, -35.00 +CTUN, 605, 0.00, 52.26, 105.3258, 0.00, 0, -738, 1000, 0 +ATT, 0.00, 66.10, 0.00, -4.45, 0.20, 43.26, 33.26 +MOT, 1531, 1950, 1917, 1908 +NTUN, 596.90, 1.91, -721.1758, 3591.646, -98.43160, 490.2155, -634.7596, -842.0714, 446.2993, 872.4774, 24.78, -35.00 +GPS, 3, 109315800, 1774, 9, 1.67, -39.4897725, 176.7497828, 48.08, 98.06, 9.25, 224.63, 5.780000, 168884 +CTUN, 605, 0.00, 53.36, 105.3044, 0.00, 0, -731, 1000, 0 +ATT, 0.00, 44.44, 0.00, -8.44, 0.00, 63.90, 53.90 +MOT, 1127, 1888, 1631, 1921 +NTUN, 595.90, 1.91, -684.1641, 3640.231, -92.35560, 491.3965, -703.5776, -775.3124, 497.4088, 844.3841, 6.55, -35.00 +CTUN, 605, 0.00, 53.07, 105.2833, 0.00, 0, -698, 1000, 0 +ATT, 0.00, 16.88, 0.00, 7.47, 0.00, 86.38, 76.38 +MOT, 1127, 1745, 1520, 1857 +NTUN, 594.85, 1.91, -638.5625, 3679.796, -85.48840, 492.6375, -749.6603, -774.3523, 536.8378, 819.8812, -17.67, -35.00 +DU32, 7, 270713 +CURR, 1000, 498317, 1395, 5134, 4876, 883.6629 +GPS, 3, 109316000, 1774, 9, 1.67, -39.4897881, 176.7497707, 47.19, 96.93, 9.72, 215.27, 5.640000, 169084 +CTUN, 605, 0.00, 50.69, 105.2621, 0.00, 0, -627, 1000, 0 +ATT, 0.00, -4.13, 0.00, 30.73, 0.00, 100.13, 90.13 +MOT, 1167, 1931, 1884, 1950 +NTUN, 593.74, 1.91, -587.2344, 3716.201, -78.04169, 493.8719, -738.5366, -817.5733, 551.8777, 809.8340, -30.57, -35.00 +CTUN, 605, 0.00, 50.27, 105.2409, 0.00, 0, -616, 1000, 0 +ATT, 0.00, -25.72, 0.00, 52.73, 0.00, 104.24, 94.38 +MOT, 1127, 1734, 1889, 1600 +NTUN, 592.64, 1.91, -531.0781, 3750.084, -70.10928, 495.0603, -679.9373, -868.9425, 536.9702, 819.7945, -28.33, -34.36 +GPS, 3, 109316200, 1774, 9, 1.67, -39.4898048, 176.7497611, 46.31, 96.12, 10.10, 207.59, 5.210000, 169285 +CTUN, 605, 0.00, 50.28, 105.2198, 0.00, 0, -644, 1000, 0 +ATT, 0.00, -52.22, 0.00, 65.93, 0.10, 101.14, 94.38 +MOT, 1127, 1442, 1716, 1264 +NTUN, 591.58, 1.91, -478.3555, 3787.827, -62.64620, 496.0599, -599.8033, -889.8303, 506.2943, 839.0864, -18.88, -35.00 +CTUN, 605, 0.00, 50.48, 105.1986, 0.00, 0, -691, 1000, 0 +ATT, 0.00, -57.02, 0.00, 68.46, 0.10, 112.21, 102.21 +MOT, 1445, 1326, 1950, 1547 +NTUN, 590.59, 1.91, -430.9570, 3824.496, -55.98735, 496.8555, -502.7559, -900.1999, 472.1385, 858.7697, -13.85, -35.00 +GPS, 3, 109316400, 1774, 10, 1.65, -39.4898201, 176.7497497, 45.35, 95.32, 9.89, 210.31, 5.000000, 169485 +CTUN, 605, 0.00, 49.13, 105.1775, 0.00, 0, -723, 1000, 0 +ATT, 0.00, -31.17, 0.00, 53.68, 0.00, 147.22, 137.22 +MOT, 1589, 1156, 1950, 1642 +NTUN, 589.71, 1.91, -392.4063, 3861.666, -50.54759, 497.4384, -409.1667, -879.8073, 432.9793, 879.1638, -21.96, -21.52 +CTUN, 605, 0.00, 47.92, 105.1563, 0.00, 0, -728, 1000, 0 +ATT, 0.00, -22.22, 0.00, 21.44, 0.00, 166.43, 156.43 +MOT, 1586, 1127, 1862, 1342 +NTUN, 588.94, 1.90, -365.9844, 3899.146, -46.72598, 497.8119, -344.7780, -828.0176, 397.1253, 895.9305, -35.00, 3.11 +GPS, 3, 109316600, 1774, 10, 1.65, -39.4898329, 176.7497365, 44.24, 94.25, 9.16, 218.20, 5.170000, 169685 +CTUN, 605, 0.00, 46.96, 105.1349, 0.00, 0, -701, 1000, 0 +ATT, 0.00, -29.75, 0.00, -16.05, 0.00, 179.94, 169.94 +MOT, 1688, 1456, 1840, 1127 +NTUN, 588.26, 1.90, -348.4688, 3933.309, -44.12433, 498.0493, -348.9094, -754.9597, 379.3677, 903.5930, -35.00, 14.95 +CTUN, 605, 0.00, 47.12, 105.1138, 0.00, 0, -707, 1000, 0 +ATT, 0.00, -57.09, 0.00, -42.40, 0.00, 206.67, 196.67 +MOT, 1331, 1849, 1589, 1127 +NTUN, 587.62, 1.90, -339.3477, 3963.896, -42.64882, 498.1778, -397.3857, -680.9581, 396.8342, 896.0595, -34.74, 29.78 +GPS, 3, 109316800, 1774, 10, 1.65, -39.4898420, 176.7497237, 43.09, 93.02, 7.63, 226.59, 5.440000, 169885 +CTUN, 605, 0.00, 47.34, 105.0926, 0.00, -484, -750, 516, 0 +ATT, 0.00, -87.29, 0.00, -43.80, 0.10, 232.78, 222.78 +MOT, 1353, 1587, 1127, 1301 +NTUN, 586.97, 1.90, -328.3359, 3987.716, -41.02958, 498.3137, -478.2703, -594.6638, 440.7399, 875.2990, -14.34, 35.00 +CTUN, 605, 0.00, 46.22, 105.0715, 0.00, -806, -798, 194, 0 +ATT, 0.00, -86.92, 0.00, -37.51, 0.00, 232.15, 225.73 +MOT, 1310, 1671, 1127, 1282 +NTUN, 586.32, 1.90, -317.4609, 4003.764, -39.52127, 498.4356, -553.8174, -507.5789, 497.1852, 844.5158, -2.87, 35.00 +GPS, 3, 109317000, 1774, 9, 1.67, -39.4898493, 176.7497129, 42.01, 91.88, 6.39, 229.72, 5.510000, 170066 +DU32, 7, 270713 +CURR, 718, 508165, 1517, 1571, 4962, 894.5137 +CTUN, 603, 0.00, 45.37, 105.0503, 0.00, 0, -850, 1000, 0 +ATT, 0.00, -71.18, 0.00, -27.38, 0.20, 217.50, 225.73 +MOT, 1471, 1950, 1316, 1381 +NTUN, 585.63, 1.90, -300.2578, 4011.029, -37.32458, 498.6049, -621.2233, -408.4954, 553.1685, 808.9528, -8.58, 35.00 +CTUN, 605, 0.00, 44.89, 105.0292, 0.00, 0, -874, 1000, 0 +ATT, 0.00, -55.77, 0.00, -9.68, 0.00, 201.56, 211.56 +MOT, 1746, 1950, 1430, 1676 +NTUN, 584.92, 1.90, -280.2734, 4006.371, -34.89319, 498.7810, -660.2535, -289.0837, 608.8859, 767.8918, -19.57, 35.00 +GPS, 3, 109317200, 1774, 10, 1.65, -39.4898573, 176.7497040, 40.46, 90.69, 5.92, 224.56, 5.590000, 170285 +CTUN, 605, 0.00, 43.00, 105.0078, 0.00, 0, -857, 1000, 0 +ATT, 0.00, -48.16, 0.00, 15.49, 0.00, 186.46, 196.46 +MOT, 1502, 1950, 1589, 1812 +NTUN, 584.21, 1.90, -255.3281, 3990.449, -31.92711, 498.9796, -650.1251, -138.5498, 661.5543, 723.0118, -28.95, 35.00 +CTUN, 605, 0.00, 42.64, 104.9866, 0.00, 0, -834, 1000, 0 +ATT, 0.00, -50.06, 0.00, 42.80, 0.00, 169.36, 179.36 +MOT, 1219, 1369, 1353, 1950 +NTUN, 583.55, 1.90, -228.8906, 3959.973, -28.85237, 499.1668, -561.3519, -19.34876, 701.3600, 684.4663, -31.94, 34.96 +GPS, 3, 109317400, 1774, 10, 1.65, -39.4898688, 176.7496989, 39.00, 89.29, 6.09, 208.24, 5.850000, 170486 +CTUN, 605, 0.00, 43.53, 104.9655, 0.00, 0, -846, 1000, 0 +ATT, 0.00, -51.26, 0.00, 66.16, 0.00, 150.13, 160.13 +MOT, 1288, 1443, 1578, 1950 +NTUN, 582.99, 1.91, -208.5508, 3915.988, -26.59044, 499.2924, -445.7025, 45.90363, 704.6873, 681.0402, -27.18, 23.20 +CTUN, 605, 0.00, 42.66, 104.9445, 0.00, -230, -879, 770, 0 +ATT, 0.00, -29.81, 0.00, 81.30, 0.00, 151.30, 154.93 +MOT, 1429, 1222, 1424, 1950 +NTUN, 582.55, 1.91, -195.8594, 3862.616, -25.32067, 499.3585, -301.6018, 68.31187, 675.5894, 709.9147, -14.51, 8.41 +GPS, 3, 109317600, 1774, 10, 1.65, -39.4898794, 176.7496994, 37.64, 87.85, 5.38, 186.65, 6.090000, 170686 +CTUN, 602, 0.00, 42.02, 104.9232, 0.00, -400, -927, 600, 0 +ATT, 0.00, 53.27, 0.00, 80.05, 0.00, 214.56, 204.56 +MOT, 1950, 1460, 1525, 1659 +NTUN, 582.27, 1.91, -197.0469, 3804.762, -25.86012, 499.3308, -159.5049, 44.14635, 599.1960, 775.4767, -4.15, 35.00 +CTUN, 605, 0.00, 40.49, 104.9020, 0.00, 0, -971, 1000, 0 +ATT, 0.00, 51.87, 0.00, 67.07, 0.00, 199.87, 205.78 +MOT, 1636, 1127, 1280, 1336 +NTUN, 582.14, 1.91, -214.0938, 3745.626, -28.53260, 499.1852, -13.87545, -34.70837, 471.7656, 858.9745, -7.26, 35.00 +GPS, 3, 109317800, 1774, 10, 1.65, -39.4898862, 176.7497014, 36.08, 86.56, 3.95, 181.95, 6.250000, 170886 +CTUN, 603, 0.00, 38.98, 104.8951, 0.00, 0, -978, 1000, 0 +ATT, 0.00, 38.66, 0.00, 43.48, 0.00, 178.02, 188.02 +MOT, 1950, 1492, 1813, 1544 +NTUN, 582.17, 1.91, -213.9609, 3700.147, -28.86427, 499.1662, 102.9985, -134.6166, 340.2846, 919.0247, -26.33, 24.81 +CTUN, 605, 0.00, 37.49, 104.8919, 0.00, 0, -939, 1000, 0 +ATT, 0.00, 28.70, 0.00, 15.82, 0.00, 165.22, 175.22 +MOT, 1915, 1583, 1950, 1525 +NTUN, 582.32, 1.91, -225.4570, 3668.210, -30.67332, 499.0583, 152.5185, -222.9875, 200.1464, 959.3442, -35.00, 2.76 +GPS, 3, 109318000, 1774, 10, 1.65, -39.4898892, 176.7497034, 34.39, 85.03, 2.05, 176.26, 6.600000, 171086 +DU32, 7, 270713 +CURR, 1000, 517665, 1423, 3441, 4855, 904.8021 +CTUN, 605, 0.00, 36.15, 104.8899, 0.00, 0, -864, 1000, 0 +ATT, 0.00, 16.35, 0.00, -14.67, 0.00, 158.94, 168.94 +MOT, 1851, 1466, 1950, 1618 +NTUN, 582.52, 1.91, -243.6797, 3647.422, -33.33007, 498.8879, 126.4590, -260.0151, 144.4410, 969.2971, -35.00, -10.13 +CTUN, 605, 0.00, 34.92, 104.8870, 0.00, 0, -812, 1000, 0 +ATT, 0.00, 0.90, 0.00, -43.24, 0.00, 161.59, 168.62 +MOT, 1775, 1195, 1950, 1414 +NTUN, 582.73, 1.91, -270.8086, 3637.662, -37.12017, 498.6202, 54.34202, -237.1867, 153.6583, 967.8787, -35.00, -11.82 +GPS, 3, 109318200, 1774, 10, 1.65, -39.4898868, 176.7497042, 32.82, 83.15, 0.94, 125.83, 7.120000, 171287 +CTUN, 605, 0.00, 34.67, 104.8833, 0.00, 0, -810, 1000, 0 +ATT, 0.00, -29.17, 0.00, -63.70, 0.00, 183.24, 173.24 +MOT, 1592, 1697, 1950, 1580 +NTUN, 582.88, 1.91, -295.9844, 3628.951, -40.64602, 498.3452, -39.73892, -175.2156, 216.5663, 955.7715, -29.38, 1.37 +CTUN, 603, 0.00, 34.15, 104.8788, 0.00, 0, -840, 1000, 0 +ATT, 0.00, -71.96, 0.00, -63.22, 0.10, 218.48, 208.48 +MOT, 1485, 1950, 1571, 1545 +NTUN, 582.98, 1.91, -320.2461, 3621.730, -44.03992, 498.0567, -155.1628, -85.28500, 313.3511, 928.5532, -16.96, 33.65 +GPS, 3, 109318400, 1774, 10, 1.65, -39.4898841, 176.7497026, 31.26, 81.51, 1.91, 359.83, 7.260000, 171487 +CTUN, 605, 0.00, 33.52, 104.8734, 0.00, -222, -876, 778, 0 +ATT, 0.00, -78.13, 0.00, -51.67, 0.00, 218.88, 212.89 +MOT, 1471, 1950, 1570, 1431 +NTUN, 582.98, 1.91, -336.8594, 3607.447, -46.48720, 497.8342, -257.3848, 24.19129, 439.8322, 875.7554, -10.56, 35.00 +CTUN, 605, 0.00, 32.98, 104.8671, 0.00, 0, -899, 1000, 0 +ATT, 0.00, -69.72, 0.00, -36.59, 0.10, 203.46, 212.89 +MOT, 1595, 1950, 1518, 1610 +NTUN, 582.90, 1.91, -343.8203, 3586.680, -47.71146, 497.7184, -330.9182, 131.2106, 567.1309, 799.2261, -15.37, 35.00 +GPS, 3, 109318600, 1774, 10, 1.65, -39.4898832, 176.7497012, 29.63, 79.76, 1.35, 348.29, 7.500000, 171687 +CTUN, 605, 0.00, 34.57, 104.8600, 0.00, 0, -899, 1000, 0 +ATT, 0.00, -58.71, 0.00, -15.95, 0.00, 188.09, 198.09 +MOT, 1736, 1950, 1606, 1725 +NTUN, 582.75, 1.91, -344.0703, 3555.748, -48.15734, 497.6754, -364.1504, 266.6606, 666.7737, 718.2010, -25.05, 35.00 +CTUN, 605, 0.00, 33.79, 104.8521, 0.00, 0, -846, 1000, 0 +ATT, 0.00, -53.95, 0.00, 10.23, 0.10, 173.89, 183.89 +MOT, 1464, 1950, 1594, 1814 +NTUN, 582.58, 1.91, -336.6211, 3512.274, -47.70208, 497.7193, -324.5786, 410.2761, 725.5526, 604.4388, -31.09, 35.00 +GPS, 3, 109318800, 1774, 10, 1.65, -39.4898869, 176.7497020, 28.33, 78.07, 1.22, 275.60, 7.670000, 171888 +CTUN, 605, 0.00, 33.14, 104.8432, 0.00, 0, -820, 1000, 0 +ATT, 0.00, -57.91, 0.00, 39.62, 0.00, 155.69, 165.69 +MOT, 1127, 1505, 1377, 1905 +NTUN, 582.46, 1.91, -330.7813, 3453.834, -47.66798, 497.7226, -220.5487, 493.2523, 662.3376, 469.0323, -29.70, 28.36 +CTUN, 605, 0.00, 32.13, 104.8336, 0.00, 0, -835, 1000, 0 +ATT, 0.00, -70.96, 0.00, 66.57, 0.20, 122.57, 132.57 +MOT, 1352, 1293, 1646, 1950 +NTUN, 582.42, 1.91, -329.0781, 3382.540, -48.41506, 497.6505, -94.65003, 521.6314, 538.5292, 391.2786, -20.94, 10.66 +GPS, 3, 109319000, 1774, 10, 1.65, -39.4898919, 176.7497083, 27.10, 76.30, 2.97, 136.94, 7.840000, 172088 +DU32, 7, 270713 +CURR, 130, 526569, 1442, 3923, 4940, 917.0999 +CTUN, 605, 0.00, 30.61, 104.8296, 0.00, -870, -886, 130, 0 +ATT, 0.00, -124.41, 0.00, 77.45, 0.00, 41.91, 51.91 +MOT, 1298, 1127, 1310, 1309 +NTUN, 582.50, 1.91, -325.1836, 3309.187, -48.89795, 497.6032, 29.95437, 489.2549, 413.1711, 377.5279, -6.19, -20.73 +CTUN, 605, 0.00, 28.56, 104.8296, 0.00, -870, -970, 130, 0 +ATT, 0.00, -156.17, 0.00, 69.94, 0.20, 336.75, 346.75 +MOT, 1270, 1127, 1312, 1335 +NTUN, 582.68, 1.91, -323.0078, 3236.811, -49.64940, 497.5288, 107.3899, 415.2329, 288.4855, 417.2560, 6.43, -16.93 +GPS, 3, 109319200, 1774, 10, 1.65, -39.4898939, 176.7497179, 25.44, 74.55, 3.80, 107.48, 7.980000, 172288 +CTUN, 605, 0.00, 28.41, 104.8296, 0.00, -870, -1076, 130, 0 +ATT, 0.00, -152.71, 0.00, 64.34, 0.10, 306.18, 316.18 +MOT, 1246, 1127, 1321, 1351 +NTUN, 582.93, 1.91, -330.1250, 3169.952, -51.79088, 497.3105, 130.2088, 315.1689, 197.5852, 499.8165, 11.68, 10.15 +CTUN, 605, 0.00, 26.93, 104.8296, 0.00, -870, -1184, 130, 0 +ATT, 0.00, -143.37, 0.00, 64.05, 0.00, 285.85, 295.85 +MOT, 1189, 1127, 1407, 1321 +NTUN, 583.20, 1.91, -346.3438, 3112.051, -55.30414, 496.9320, 105.0052, 223.1819, 158.8674, 597.2155, 10.22, 25.76 +GPS, 3, 109319400, 1774, 9, 1.69, -39.4898906, 176.7497254, 23.54, 73.12, 3.50, 69.99, 7.880000, 172469 +CTUN, 603, 0.00, 25.45, 104.8296, 0.00, -870, -1285, 130, 0 +ATT, 0.00, -134.80, 0.00, 68.73, 0.00, 272.62, 282.62 +MOT, 1196, 1127, 1409, 1313 +NTUN, 583.48, 1.91, -363.0430, 3063.878, -58.83408, 496.5265, 47.20593, 146.1634, 180.0501, 684.9847, 6.67, 33.58 +CTUN, 605, 0.00, 24.75, 104.8287, 0.00, -870, -1369, 130, 0 +ATT, 0.00, -123.07, 0.00, 75.90, 0.00, 267.98, 277.98 +MOT, 1185, 1127, 1396, 1337 +NTUN, 583.72, 1.91, -387.3164, 3031.032, -63.37650, 495.9671, -31.08433, 89.92115, 221.5758, 756.4064, 3.74, 35.00 +GPS, 3, 109319600, 1774, 9, 1.69, -39.4898887, 176.7497350, 20.99, 71.82, 4.06, 73.14, 7.690000, 172669 +CTUN, 603, 0.00, 23.27, 104.8270, 0.00, -870, -1444, 130, 0 +ATT, 0.00, -103.68, 0.00, 82.87, 0.10, 273.91, 277.95 +MOT, 1127, 1202, 1391, 1324 +NTUN, 583.86, 1.91, -406.4375, 3004.272, -67.03259, 495.4863, -122.1843, 49.74189, 306.4391, 811.1913, 3.09, 35.00 +CTUN, 605, 0.00, 21.79, 104.8245, 0.00, -681, -1500, 319, 0 +ATT, 0.00, -20.31, 0.00, 86.49, 0.00, 345.36, 335.36 +MOT, 1127, 1384, 1287, 1653 +NTUN, 583.90, 1.91, -418.7969, 2987.503, -69.41275, 495.1584, -216.8283, 36.10131, 412.1984, 845.7218, 3.00, 32.66 +GPS, 3, 109319800, 1774, 9, 1.69, -39.4898841, 176.7497436, 17.85, 69.48, 4.24, 56.43, 8.420000, 172889 +CTUN, 605, 0.00, 20.55, 104.8211, 0.00, -86, -1536, 914, 0 +ATT, 0.00, 19.25, 0.00, 72.34, 0.00, 13.11, 3.71 +MOT, 1950, 1725, 1860, 1742 +NTUN, 583.84, 1.91, -423.7852, 2972.631, -70.56766, 494.9951, -319.7787, 44.03148, 513.2307, 834.8619, 5.90, -34.64 +CTUN, 602, 0.00, 18.71, 104.8169, 0.00, 0, -1511, 1000, 0 +ATT, 0.00, 17.52, 0.00, 43.04, 0.00, 5.96, 3.71 +MOT, 1749, 1547, 1950, 1330 +NTUN, 583.66, 1.91, -420.6367, 2959.340, -70.36213, 495.0244, -442.3090, 87.97829, 605.9703, 770.1948, 18.51, -35.00 +GPS, 3, 109320000, 1774, 9, 1.69, -39.4898802, 176.7497476, 14.94, 66.81, 3.08, 40.35, 9.290000, 173089 +DU32, 7, 270713 +CURR, 1000, 530330, 1411, 5401, 4940, 923.9536 +CTUN, 602, 0.00, 12.01, 104.8118, 0.00, 0, -1370, 1000, 0 +ATT, 0.00, 3.98, 0.00, 19.65, 0.00, 12.77, 3.71 +MOT, 1127, 1127, 1127, 1127 +NTUN, 583.40, 1.91, -407.1758, 2943.127, -68.52136, 495.2826, -217.9949, 130.4473, 698.4833, 687.4017, 30.89, -35.00 +CTUN, 602, 0.00, 16.29, 104.8058, 0.00, 0, -1099, 1000, 0 +ATT, 0.00, 27.53, 0.00, 41.08, 0.00, 32.75, 22.75 +MOT, 1557, 1950, 1237, 1706 +NTUN, 583.32, 1.91, -395.9023, 2922.984, -67.10950, 495.4758, -269.3336, 54.61310, 554.1663, 808.2697, 21.32, -35.00 +GPS, 3, 109320200, 1774, 10, 1.65, -39.4898799, 176.7497487, 12.39, 62.55, 1.34, 40.35, 11.25000, 173289 +CTUN, 603, 0.00, 13.09, 104.7990, 0.00, 0, -1222, 1000, 0 +ATT, 0.00, 56.87, 0.00, 69.99, 0.00, 67.22, 57.22 +MOT, 1679, 1820, 1127, 1846 +NTUN, 583.21, 1.91, -402.2344, 2908.717, -68.49114, 495.2867, -287.6187, 45.52937, 565.9678, 800.0502, 8.15, -35.00 +CTUN, 578, 0.00, 14.35, 104.7914, 0.00, -870, -1346, 130, 0 +ATT, 0.00, 156.63, 0.00, 46.04, 0.00, 184.67, 174.67 +MOT, 1127, 1544, 1130, 1239 +NTUN, 583.07, 1.91, -404.6875, 2895.879, -69.20055, 495.1881, -265.8089, 33.26227, 575.4553, 793.2537, -18.20, 5.31 +GPS, 3, 109320400, 1774, 10, 1.65, -39.4898699, 176.7497426, 9.81, 60.61, 4.97, 332.53, 10.88000, 173490 +CTUN, 578, 0.00, 14.08, 104.7829, 0.00, -870, -1480, 130, 0 +ATT, 0.00, 149.77, 0.00, -9.02, 0.00, 220.06, 210.06 +MOT, 1278, 1278, 1127, 1361 +NTUN, 583.01, 1.91, -408.4961, 2884.354, -70.11276, 495.0598, -193.7366, 50.85666, 545.6195, 814.0635, -27.99, 35.00 +CTUN, 576, 0.00, 13.74, 104.7736, 0.00, -870, -1531, 130, 0 +ATT, 0.00, 128.29, 0.00, -38.60, 0.10, 257.41, 247.41 +MOT, 1336, 1127, 1291, 1291 +NTUN, 583.11, 1.91, -433.0000, 2878.462, -74.37697, 494.4371, -134.0334, 52.91002, 465.3579, 815.7729, 2.34, 35.00 +GPS, 3, 109320600, 1774, 8, 1.71, -39.4898611, 176.7497365, 7.45, 58.98, 5.57, 327.83, 10.30000, 173671 +CTUN, 571, 0.00, 13.44, 104.7633, 0.00, -870, -1314, 130, 0 +ATT, 0.00, 107.77, 0.00, -27.55, 0.00, 264.84, 254.84 +MOT, 1127, 1293, 1196, 1428 +NTUN, 583.33, 1.91, -467.5547, 2870.396, -80.38484, 493.4960, -150.9770, 91.86915, 396.5161, 818.6819, 14.44, 35.00 +CTUN, 516, 0.00, 13.21, 104.7523, 0.00, -870, -1411, 130, 0 +ATT, 0.00, 89.02, 0.00, -11.54, 0.00, 279.99, 269.99 +MOT, 1370, 1298, 1127, 1343 +NTUN, 583.61, 1.91, -522.3203, 2868.453, -89.57277, 491.9113, -108.6711, 131.2928, 367.1207, 759.1534, 19.66, 35.00 +GPS, 3, 109320800, 1774, 8, 1.71, -39.4898528, 176.7497325, 5.04, 57.83, 5.13, 327.83, 9.530000, 173891 +CTUN, 513, 0.00, 13.44, 104.7405, 0.00, -236, -1411, 764, 0 +ATT, 0.00, 74.86, 0.00, 10.78, 0.00, 286.88, 277.84 +MOT, 1876, 1735, 1946, 1127 +NTUN, 583.97, 1.91, -580.3281, 2861.337, -99.38505, 490.0230, -44.62383, 86.11898, 301.8772, 736.1172, 26.90, 32.36 +CTUN, 432, 0.00, 13.31, 104.7328, 0.00, 0, -1353, 1000, 0 +ATT, 0.00, 59.63, 0.00, 18.71, 0.41, 281.12, 277.90 +MOT, 1645, 1253, 1439, 1950 +NTUN, 584.42, 1.91, -639.1797, 2860.326, -109.0425, 487.9649, 87.15263, 70.60261, 215.4250, 786.4186, 20.37, 35.00 +PM, 0, 0, 0, 1000, 10316, 0, 0, 0, 0 +GPS, 3, 109321000, 1774, 9, 1.67, -39.4898373, 176.7497253, 3.11, 57.51, 7.34, 339.61, 8.290000, 174091 +DU32, 7, 270713 +CURR, 1000, 535491, 1450, 4023, 4897, 933.4984 +CTUN, 346, 0.00, 13.38, 104.7305, 0.00, 0, -1329, 1000, 0 +ATT, 0.00, 63.36, 0.00, 19.05, 0.10, 281.53, 277.92 +MOT, 1662, 1153, 1437, 1950 +NTUN, 585.06, 1.91, -697.1680, 2866.962, -118.1436, 485.8416, 181.4631, 95.10277, 62.98926, 785.7671, 11.68, 35.00 +CTUN, 361, 0.00, 13.35, 104.7305, 0.00, 0, -1320, 1000, 0 +ATT, 0.00, 74.62, 0.00, 18.27, 5.50, 282.69, 278.77 +MOT, 1658, 1127, 1441, 1946 +NTUN, 585.86, 1.91, -773.5469, 2876.895, -129.8300, 482.8501, 252.5412, 110.8882, -73.86363, 755.0845, 4.72, 35.00 +GPS, 3, 109321200, 1774, 9, 1.67, -39.4898250, 176.7497155, 1.52, 57.56, 7.69, 335.81, 7.080000, 174291 +CTUN, 393, 0.00, 13.39, 104.7305, 0.00, -638, -1315, 362, 0 +ATT, 0.00, 89.11, 0.00, 16.41, 0.00, 283.46, 279.63 +MOT, 1303, 1127, 1220, 1508 +NTUN, 586.74, 1.91, -860.4023, 2886.216, -142.8418, 479.1620, 326.0185, 115.1317, -188.8293, 728.4844, -0.99, 35.00 +CTUN, 393, 0.00, 13.40, 104.7305, 0.00, -870, -1325, 130, 0 +ATT, 0.00, 107.02, 0.00, 12.89, 0.00, 283.20, 279.63 +MOT, 1288, 1127, 1206, 1423 +NTUN, 587.72, 1.91, -958.1953, 2900.364, -156.8474, 474.7619, 393.6312, 122.5968, -316.4713, 714.5547, -7.73, 35.00 +GPS, 3, 109321400, 1774, 9, 1.67, -39.4898185, 176.7497104, 0.12, 57.75, 5.62, 336.57, 5.980000, 174491 +CTUN, 393, 0.00, 13.46, 104.7305, 0.00, -870, -1339, 130, 0 +ATT, 0.00, 129.17, 0.00, 12.32, 0.00, 281.79, 279.63 +MOT, 1307, 1127, 1178, 1433 +NTUN, 588.74, 1.91, -1064.195, 2915.609, -171.4368, 469.6908, 452.5079, 123.2390, -430.4493, 694.7907, -15.16, 35.00 +CTUN, 389, 0.00, 13.31, 104.7305, 0.00, -870, -1368, 130, 0 +ATT, 0.00, 157.18, 0.00, 14.65, 0.00, 281.10, 279.63 +MOT, 1351, 1127, 1149, 1418 +NTUN, 589.78, 1.91, -1171.824, 2931.477, -185.5907, 464.2802, 480.2729, 117.1170, -528.5390, 685.8939, -20.60, 35.00 +GPS, 3, 109321600, 1774, 9, 1.67, -39.4898096, 176.7497037, -1.19, 58.71, 5.60, 337.09, 4.490000, 174692 +CTUN, 272, 0.00, 13.20, 104.7305, 0.00, -870, -1339, 130, 0 +ATT, 0.00, -175.09, 0.00, 17.35, 0.20, 281.91, 279.63 +MOT, 1197, 1396, 1324, 1127 +NTUN, 590.81, 1.91, -1282.043, 2948.089, -199.3977, 458.5200, 478.9667, 131.3042, -590.0704, 680.3981, -23.82, 35.00 +CTUN, 218, 0.00, 13.14, 104.7305, 0.00, -870, -1227, 130, 0 +ATT, 0.00, -177.48, 0.00, 20.37, 0.00, 282.11, 279.63 +MOT, 1127, 1429, 1288, 1200 +NTUN, 591.80, 1.91, -1388.422, 2965.782, -211.9930, 452.8344, 494.3753, 136.9094, -625.9529, 661.1439, -24.34, 35.00 +GPS, 3, 109321800, 1774, 8, 1.72, -39.4898085, 176.7497053, -2.08, 58.53, 2.39, 337.09, 3.990000, 174872 +CTUN, 219, 0.00, 13.21, 104.7305, 0.00, -870, -1239, 130, 0 +ATT, 0.00, 177.23, 0.00, 18.82, 0.00, 281.76, 279.63 +MOT, 1127, 1392, 1239, 1220 +NTUN, 592.72, 1.91, -1494.129, 2982.850, -223.9310, 447.0513, 541.4648, 123.1711, -688.3793, 653.1698, -27.42, 35.00 +CTUN, 217, 0.00, 13.21, 104.7305, 0.00, -870, -1218, 130, 0 +ATT, 0.00, 178.30, 0.00, 18.35, 0.00, 281.17, 279.63 +MOT, 1127, 1409, 1332, 1177 +NTUN, 593.62, 1.91, -1585.648, 2995.039, -233.9484, 441.8916, 577.6542, 129.8140, -740.9146, 641.4404, -30.09, 35.00 +GPS, 3, 109322000, 1774, 8, 1.72, -39.4898098, 176.7497048, -2.88, 58.51, 0.47, 337.09, 3.470000, 175072 +DU32, 7, 270713 +CURR, 130, 538154, 1541, 1946, 4897, 940.1125 +CTUN, 183, 0.00, 13.21, 104.7305, 0.00, -870, -1193, 130, 0 +ATT, 0.00, 178.06, 0.00, 18.67, 0.00, 280.93, 279.63 +MOT, 1127, 1385, 1307, 1226 +NTUN, 594.43, 1.91, -1681.465, 3007.260, -244.0143, 436.4138, 599.8972, 132.0768, -779.6234, 593.7906, -32.11, 35.00 +CTUN, 0, 0.00, 13.21, 104.7305, 0.00, -870, -1174, 130, 0 +ATT, 0.00, 177.62, 0.00, 18.58, -0.32, 280.91, 279.58 +MOT, 1127, 1415, 1313, 1189 +NTUN, 595.18, 1.91, -1758.500, 3016.493, -251.8157, 431.9593, 625.1893, 135.8845, -793.5139, 575.0963, -33.06, 35.00 +GPS, 3, 109322200, 1774, 8, 1.72, -39.4898109, 176.7497047, -3.49, 58.49, 0.27, 337.09, 3.010000, 175273 +CTUN, 0, 0.00, 13.24, 104.7305, 0.00, -870, -1153, 130, 0 +ATT, 0.00, 177.56, 0.00, 18.55, 0.00, 280.58, 279.58 +MOT, 1127, 1401, 1320, 1195 +NTUN, 595.86, 1.91, -1838.070, 3025.386, -259.6159, 427.3168, 640.0800, 141.0834, -818.3968, 539.0980, -34.31, 34.80 +CTUN, 0, 0.00, 13.19, 104.7305, 0.00, -870, -1130, 130, 0 +ATT, 0.00, 177.48, 0.00, 18.47, 0.00, 280.63, 279.58 +MOT, 1127, 1393, 1330, 1195 +NTUN, 596.49, 1.91, -1902.324, 3031.579, -265.7613, 423.5221, 657.5590, 145.8543, -830.9405, 519.5554, -34.88, 34.16 +GPS, 3, 109322400, 1774, 8, 1.72, -39.4898118, 176.7497048, -3.95, 58.50, 0.45, 337.09, 2.630000, 175473 +CTUN, 0, 0.00, 13.19, 104.7305, 0.00, -870, -1108, 130, 0 +ATT, 0.00, 177.44, 0.00, 18.47, -3.25, 280.47, 279.36 +MOT, 1127, 1397, 1318, 1202 +NTUN, 597.05, 1.91, -1968.113, 3037.303, -271.8982, 419.6086, 668.7850, 150.6082, -848.7465, 489.9279, -35.00, 33.04 +CTUN, 0, 0.00, 13.07, 104.7305, 0.00, -870, -1085, 130, 0 +ATT, 0.00, 177.35, 0.00, 18.59, -28.73, 280.29, 276.31 +MOT, 1183, 1472, 1262, 1127 +NTUN, 597.57, 1.91, -2021.555, 3040.794, -276.8151, 416.3813, 679.1684, 155.3190, -858.4435, 472.7311, -35.00, 32.24 +GPS, 3, 109322600, 1774, 8, 1.72, -39.4898126, 176.7497049, -4.26, 58.56, 0.52, 337.09, 2.270000, 175673 +CTUN, 0, 0.00, 13.14, 104.7305, 0.00, -870, -1064, 130, 0 +ATT, 0.00, 177.26, 0.00, 18.49, -45.10, 279.72, 269.72 +MOT, 1243, 1434, 1240, 1127 +NTUN, 598.04, 1.91, -2076.004, 3043.749, -281.7352, 413.0681, 684.3371, 160.6293, -871.5123, 448.1811, -35.00, 31.19 +CTUN, 0, 0.00, 13.27, 104.7305, 0.00, -870, -1039, 130, 0 +ATT, 0.00, 177.16, 0.00, 18.49, -45.10, 279.54, 269.54 +MOT, 1251, 1429, 1237, 1127 +NTUN, 598.46, 1.91, -2119.199, 3044.838, -285.6277, 410.3862, 689.5823, 165.5170, -878.7162, 433.8868, -35.00, 30.51 +GPS, 3, 109322800, 1774, 8, 1.72, -39.4898135, 176.7497050, -4.45, 58.58, 0.49, 337.09, 1.980000, 175893 +CTUN, 0, 0.00, 13.16, 104.7305, 0.00, -870, -1016, 130, 0 +ATT, 0.00, 177.30, 0.00, 18.49, -45.00, 279.53, 269.53 +MOT, 1238, 1460, 1218, 1127 +NTUN, 598.86, 1.91, -2162.938, 3045.476, -289.5188, 407.6504, 693.5057, 169.4538, -888.1757, 414.1785, -35.00, 29.46 +CTUN, 0, 0.00, 13.22, 104.7305, 0.00, -870, -992, 130, 0 +ATT, 0.00, 177.10, 0.00, 18.43, -45.10, 279.21, 269.21 +MOT, 1251, 1432, 1235, 1127 +NTUN, 599.20, 1.91, -2199.230, 3044.573, -292.7778, 405.3161, 694.2765, 175.4252, -894.5173, 400.2984, -35.00, 28.81 +GPS, 3, 109323000, 1774, 8, 1.72, -39.4898144, 176.7497054, -4.50, 58.63, 0.52, 337.09, 1.720000, 176074 +DU32, 7, 270713 +CURR, 130, 539454, 1467, 3743, 4962, 948.4289 +CTUN, 0, 0.00, 13.15, 104.7305, 0.00, -870, -968, 130, 0 +ATT, 0.00, 177.02, 0.00, 18.27, -45.10, 279.03, 269.03 +MOT, 1253, 1423, 1241, 1127 +NTUN, 599.48, 1.91, -2233.727, 3042.855, -295.8798, 403.0572, 691.2303, 181.1217, -901.3269, 384.7205, -35.00, 28.13 +CTUN, 0, 0.00, 13.08, 104.7305, 0.00, -870, -944, 130, 0 +ATT, 0.00, 176.97, 0.00, 18.44, -45.00, 278.96, 268.96 +MOT, 1241, 1459, 1216, 1127 +NTUN, 599.73, 1.91, -2258.535, 3040.441, -298.1553, 401.3769, 689.3187, 184.6811, -901.6480, 383.9673, -35.00, 27.88 +GPS, 3, 109323200, 1774, 8, 1.72, -39.4898154, 176.7497055, -4.45, 58.54, 0.44, 337.09, 1.570000, 176274 +CTUN, 0, 0.00, 13.05, 104.7305, 0.00, -870, -921, 130, 0 +ATT, 0.00, 177.03, 0.00, 18.28, -45.00, 278.74, 268.74 +MOT, 1243, 1432, 1242, 1127 +NTUN, 599.93, 1.91, -2283.066, 3037.455, -300.4188, 399.6855, 682.6840, 190.4137, -902.5809, 381.7693, -35.00, 27.74 +CTUN, 0, 0.00, 13.20, 104.7305, 0.00, -870, -896, 130, 0 +ATT, 0.00, 176.87, 0.00, 18.07, -45.10, 278.25, 268.25 +MOT, 1258, 1411, 1249, 1127 +NTUN, 600.10, 1.91, -2300.137, 3034.012, -302.0659, 398.4422, 675.0828, 194.3174, -901.9727, 383.2039, -35.00, 27.71 +GPS, 3, 109323400, 1774, 8, 1.72, -39.4898165, 176.7497057, -4.31, 58.44, 0.44, 337.09, 1.450000, 176474 +CTUN, 0, 0.00, 13.05, 104.7305, 0.00, -870, -871, 130, 0 +ATT, 0.00, 176.92, 0.00, 17.98, -45.10, 277.92, 267.92 +MOT, 1243, 1440, 1233, 1127 +NTUN, 600.24, 1.91, -2316.523, 3030.189, -303.6688, 397.2220, 668.1585, 198.6399, -902.7764, 381.3068, -35.00, 27.14 +CTUN, 0, 0.00, 13.12, 104.7305, 0.00, -870, -847, 130, 0 +ATT, 0.00, 176.98, 0.00, 18.05, -45.00, 277.89, 267.89 +MOT, 1260, 1431, 1227, 1127 +NTUN, 600.34, 1.91, -2326.363, 3026.005, -304.7456, 396.3964, 658.2323, 204.1594, -901.9138, 383.3424, -35.00, 26.93 +GPS, 3, 109323600, 1774, 8, 1.73, -39.4898172, 176.7497061, -4.09, 58.49, 0.41, 337.09, 1.250000, 176675 +CTUN, 0, 0.00, 13.02, 104.7305, 0.00, -870, -823, 130, 0 +ATT, 0.00, 177.08, 0.00, 18.01, -45.10, 278.09, 268.09 +MOT, 1254, 1418, 1244, 1127 +NTUN, 600.41, 1.91, -2335.398, 3021.181, -305.7934, 395.5887, 647.0358, 208.6652, -902.3506, 382.3133, -35.00, 27.30 +CTUN, 0, 0.00, 13.03, 104.7305, 0.00, -870, -800, 130, 0 +ATT, 0.00, 177.15, 0.00, 18.04, -45.00, 278.24, 268.24 +MOT, 1238, 1433, 1247, 1127 +NTUN, 600.45, 1.91, -2339.551, 3016.187, -306.4500, 395.0803, 635.9725, 211.0752, -901.3200, 384.7365, -35.00, 27.35 +GPS, 3, 109323800, 1774, 8, 1.73, -39.4898178, 176.7497061, -3.77, 58.52, 0.28, 337.09, 1.100000, 176894 +CTUN, 0, 0.00, 12.92, 104.7305, 0.00, -870, -775, 130, 0 +ATT, 0.00, 177.19, 0.00, 17.93, -45.00, 278.16, 268.16 +MOT, 1248, 1442, 1227, 1127 +NTUN, 600.48, 1.91, -2342.578, 3010.786, -307.0402, 394.6218, 627.2982, 214.5074, -900.8243, 385.8958, -35.00, 27.49 +CTUN, 0, 0.00, 12.95, 104.7305, 0.00, -870, -750, 130, 0 +ATT, 0.00, 177.42, 0.00, 17.97, -45.00, 278.43, 268.43 +MOT, 1250, 1431, 1236, 1127 +NTUN, 600.49, 1.91, -2343.605, 3005.352, -307.4695, 394.2873, 614.8159, 218.1698, -900.0731, 387.6447, -35.00, 27.57 +GPS, 3, 109324000, 1774, 8, 1.73, -39.4898187, 176.7497066, -3.45, 58.48, 0.31, 337.09, 1.010000, 177076 +DU32, 7, 270713 +CURR, 130, 540754, 1444, 3474, 5006, 959.8994 +ERR, 12, 1 +EV, 11 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +PM, 0, 0, 1, 1000, 113914, 0, 0, 0, 0 +DU32, 7, 270425 +MODE, STABILIZE, 271 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, RTL, 271 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10273, 0, 0, 0, 0 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, RTL, 271 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, STABILIZE, 271 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, RTL, 271 +PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 +DU32, 7, 270425 +MODE, STABILIZE, 271 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, RTL, 271 +DU32, 7, 270425 +DU32, 7, 270425 +MODE, STABILIZE, 271 +DU32, 7, 270425 +DU32, 7, 270425 +PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 +DU32, 7, 270425 +DU32, 7, 270425 +DU32, 7, 270425 +EV, 18 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10260, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10317, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10206, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10305, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10226, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10257, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10293, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10287, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +PM, 0, 0, 0, 1000, 10279, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10235, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10207, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10293, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10230, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10252, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10251, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10239, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10240, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10219, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10297, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10327, 2, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10258, 2, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10318, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10218, 2, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10274, 2, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10307, 2, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10233, 2, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10285, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 1, 1000, 26884, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10231, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 5, 1000, 11978, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 46, 1000, 18406, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PARM, SYSID_MYGCS, 253.0000 +PARM, SYSID_MYGCS, 253.0000 +PARM, SYSID_MYGCS, 253.0000 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 28, 1000, 24550, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10261, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10290, 5, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10247, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10247, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PARM, SYSID_MYGCS, 253.0000 +PARM, SYSID_MYGCS, 253.0000 +PARM, SYSID_MYGCS, 253.0000 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10210, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10295, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10212, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10240, 5, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10268, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +PM, 0, 0, 0, 1000, 10278, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10299, 4, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10296, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10224, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10273, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10273, 1, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10264, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10318, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 25, 1000, 15546, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 67, 1000, 24342, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +PARM, SYSID_MYGCS, 253.0000 +PARM, SYSID_MYGCS, 253.0000 +PARM, SYSID_MYGCS, 253.0000 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 6, 1000, 25107, 4, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10321, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10285, 3, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10243, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10208, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10309, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10263, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10223, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10244, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +PM, 0, 0, 0, 1000, 10274, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10264, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10245, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10232, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10241, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +PM, 0, 0, 0, 1000, 10228, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10274, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10321, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10239, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +PM, 0, 0, 0, 1000, 10279, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10207, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10285, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +PM, 0, 0, 0, 1000, 10253, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10281, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10199, 0, 0, 0, 0 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10310, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10237, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10300, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10240, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10224, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10203, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10307, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +MODE, RTL, 271 +DU32, 7, 270937 +MODE, STABILIZE, 271 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10293, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10221, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10271, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10233, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10250, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10285, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10215, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10229, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10236, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10234, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10266, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10236, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10215, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10305, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10270, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10292, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10234, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10282, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10227, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10322, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10241, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10306, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10244, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10252, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10256, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10274, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10289, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10309, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10218, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10229, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10299, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10242, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10240, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10300, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10295, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10223, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10241, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10279, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10268, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10232, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10297, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10242, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10252, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10313, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10276, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10228, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10275, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10196, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10282, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10226, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10319, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10246, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10283, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10316, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10253, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10308, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10292, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10238, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10275, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10188, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10299, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10273, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10306, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10238, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10295, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10236, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10253, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10239, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10219, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10268, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10265, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10229, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10216, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10261, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10267, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10292, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10255, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10264, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10226, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10288, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10316, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10309, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10248, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10244, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10285, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10295, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10307, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10212, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10267, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10296, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10278, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10273, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10251, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10271, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10313, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10198, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10222, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10296, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10237, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10262, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10269, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10297, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10259, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10294, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10303, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10277, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10234, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10217, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10227, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10301, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10284, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10280, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10286, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10247, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10282, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10257, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10251, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +PM, 0, 0, 0, 1000, 10272, 0, 0, 0, 0 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 +DU32, 7, 270937 diff --git a/Tools/LogAnalyzer/logs/nan.log b/Tools/LogAnalyzer/logs/nan.log new file mode 100644 index 0000000000..40b8acc60c --- /dev/null +++ b/Tools/LogAnalyzer/logs/nan.log @@ -0,0 +1,2738 @@ +FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format +FMT, 129, 23, PARM, Nf, Name,Value +FMT, 130, 45, GPS, BIHBcLLeeEefI, Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T +FMT, 131, 31, IMU, Iffffff, TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ +FMT, 135, 31, IMU2, Iffffff, TimeMS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ +FMT, 132, 67, MSG, Z, Message +FMT, 133, 23, RCIN, Ihhhhhhhh, TimeMS,Chan1,Chan2,Chan3,Chan4,Chan5,Chan6,Chan7,Chan8 +FMT, 134, 23, RCOU, Ihhhhhhhh, TimeMS,Chan1,Chan2,Chan3,Chan4,Chan5,Chan6,Chan7,Chan8 +FMT, 25, 25, ATUN, BBfffff, Axis,TuneStep,RateMin,RateMax,RPGain,RDGain,SPGain +FMT, 26, 9, ATDE, cf, Angle,Rate +FMT, 9, 23, CURR, IhIhhhf, TimeMS,ThrOut,ThrInt,Volt,Curr,Vcc,CurrTot +FMT, 12, 20, OF, hhBccee, Dx,Dy,SQual,X,Y,Roll,Pitch +FMT, 5, 47, NTUN, Iffffffffff, TimeMS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY +FMT, 4, 33, CTUN, Ihhhffecchh, TimeMS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt +FMT, 15, 25, MAG, Ihhhhhhhhh, TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ +FMT, 27, 25, MAG2, Ihhhhhhhhh, TimeMS,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ +FMT, 6, 19, PM, BBHHIhBHB, RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr +FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng +FMT, 1, 19, ATT, IccccCC, TimeMS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw +FMT, 3, 6, MODE, Mh, Mode,ThrCrs +FMT, 10, 3, STRT, , +FMT, 13, 4, EV, B, Id +FMT, 20, 6, D16, Bh, Id,Value +FMT, 21, 6, DU16, BH, Id,Value +FMT, 22, 8, D32, Bi, Id,Value +FMT, 23, 8, DU32, BI, Id,Value +FMT, 24, 8, DFLT, Bf, Id,Value +FMT, 18, 27, CAM, IHLLeccC, GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw +FMT, 19, 5, ERR, BB, Subsys,ECode +PARM, SYSID_SW_MREV, 120 +PARM, SYSID_SW_TYPE, 10 +PARM, SYSID_THISMAV, 1 +PARM, SYSID_MYGCS, 255 +PARM, SERIAL1_BAUD, 57 +PARM, SERIAL2_BAUD, 57 +PARM, TELEM_DELAY, 0 +PARM, RTL_ALT, 1500 +PARM, SONAR_ENABLE, 0 +PARM, SONAR_TYPE, 0 +PARM, SONAR_GAIN, 0.8 +PARM, FS_BATT_ENABLE, 2 +PARM, FS_BATT_VOLTAGE, 14.5 +PARM, FS_BATT_MAH, 0 +PARM, FS_GPS_ENABLE, 2 +PARM, FS_GCS_ENABLE, 1 +PARM, GPS_HDOP_GOOD, 200 +PARM, MAG_ENABLE, 1 +PARM, FLOW_ENABLE, 0 +PARM, SUPER_SIMPLE, 0 +PARM, RTL_ALT_FINAL, 0 +PARM, RSSI_PIN, -1 +PARM, RSSI_RANGE, 5 +PARM, WP_YAW_BEHAVIOR, 2 +PARM, WP_TOTAL, 1 +PARM, WP_INDEX, 0 +PARM, CIRCLE_RADIUS, 10 +PARM, CIRCLE_RATE, 20 +PARM, RTL_LOIT_TIME, 5000 +PARM, LAND_SPEED, 50 +PARM, PILOT_VELZ_MAX, 250 +PARM, THR_MIN, 190 +PARM, THR_MAX, 1000 +PARM, FS_THR_ENABLE, 1 +PARM, FS_THR_VALUE, 975 +PARM, TRIM_THROTTLE, 424 +PARM, THR_MID, 500 +PARM, FLTMODE1, 0 +PARM, FLTMODE2, 11 +PARM, FLTMODE3, 2 +PARM, FLTMODE4, 9 +PARM, FLTMODE5, 5 +PARM, FLTMODE6, 7 +PARM, SIMPLE, 0 +PARM, LOG_BITMASK, -22530 +PARM, ESC, 0 +PARM, TUNE, 0 +PARM, TUNE_LOW, 0 +PARM, TUNE_HIGH, 1000 +PARM, FRAME, 1 +PARM, CH7_OPT, 4 +PARM, CH8_OPT, 17 +PARM, ARMING_CHECK, 1 +PARM, ANGLE_MAX, 4500 +PARM, ANGLE_RATE_MAX, 18000 +PARM, RC1_MIN, 990 +PARM, RC1_TRIM, 1509 +PARM, RC1_MAX, 2016 +PARM, RC1_REV, 1 +PARM, RC1_DZ, 30 +PARM, RC2_MIN, 993 +PARM, RC2_TRIM, 1509 +PARM, RC2_MAX, 2016 +PARM, RC2_REV, 1 +PARM, RC2_DZ, 30 +PARM, RC3_MIN, 1022 +PARM, RC3_TRIM, 1500 +PARM, RC3_MAX, 1997 +PARM, RC3_REV, 1 +PARM, RC3_DZ, 30 +PARM, RC4_MIN, 992 +PARM, RC4_TRIM, 1497 +PARM, RC4_MAX, 2017 +PARM, RC4_REV, 1 +PARM, RC4_DZ, 40 +PARM, RC5_MIN, 992 +PARM, RC5_TRIM, 1500 +PARM, RC5_MAX, 2017 +PARM, RC5_REV, 1 +PARM, RC5_DZ, 0 +PARM, RC5_FUNCTION, 0 +PARM, RC6_MIN, 992 +PARM, RC6_TRIM, 1500 +PARM, RC6_MAX, 2017 +PARM, RC6_REV, 1 +PARM, RC6_DZ, 0 +PARM, RC6_FUNCTION, 0 +PARM, RC7_MIN, 992 +PARM, RC7_TRIM, 1500 +PARM, RC7_MAX, 2017 +PARM, RC7_REV, 1 +PARM, RC7_DZ, 0 +PARM, RC7_FUNCTION, 0 +PARM, RC8_MIN, 991 +PARM, RC8_TRIM, 1500 +PARM, RC8_MAX, 2017 +PARM, RC8_REV, 1 +PARM, RC8_DZ, 0 +PARM, RC8_FUNCTION, 0 +PARM, RC9_MIN, 1100 +PARM, RC9_TRIM, 1500 +PARM, RC9_MAX, 1900 +PARM, RC9_REV, 1 +PARM, RC9_DZ, 0 +PARM, RC9_FUNCTION, 0 +PARM, RC10_MIN, 1100 +PARM, RC10_TRIM, 1500 +PARM, RC10_MAX, 1900 +PARM, RC10_REV, 1 +PARM, RC10_DZ, 0 +PARM, RC10_FUNCTION, 0 +PARM, RC11_MIN, 1100 +PARM, RC11_TRIM, 1500 +PARM, RC11_MAX, 1900 +PARM, RC11_REV, 1 +PARM, RC11_DZ, 0 +PARM, RC11_FUNCTION, 0 +PARM, RC12_MIN, 1100 +PARM, RC12_TRIM, 1500 +PARM, RC12_MAX, 1900 +PARM, RC12_REV, 1 +PARM, RC12_DZ, 0 +PARM, RC12_FUNCTION, 0 +PARM, RC_SPEED, 490 +PARM, ACRO_RP_P, 4.5 +PARM, ACRO_YAW_P, 4.5 +PARM, ACRO_BAL_ROLL, 1 +PARM, ACRO_BAL_PITCH, 1 +PARM, ACRO_TRAINER, 2 +PARM, RATE_RLL_P, 0.17 +PARM, RATE_RLL_I, 0.17 +PARM, RATE_RLL_D, 0.0125 +PARM, RATE_RLL_IMAX, 500 +PARM, RATE_PIT_P, 0.21 +PARM, RATE_PIT_I, 0.21 +PARM, RATE_PIT_D, 0.015 +PARM, RATE_PIT_IMAX, 500 +PARM, RATE_YAW_P, 0.2 +PARM, RATE_YAW_I, 0.02 +PARM, RATE_YAW_D, 0 +PARM, RATE_YAW_IMAX, 800 +PARM, LOITER_LAT_P, 1 +PARM, LOITER_LAT_I, 0.5 +PARM, LOITER_LAT_D, 0 +PARM, LOITER_LAT_IMAX, 400 +PARM, LOITER_LON_P, 1 +PARM, LOITER_LON_I, 0.5 +PARM, LOITER_LON_D, 0 +PARM, LOITER_LON_IMAX, 400 +PARM, THR_RATE_P, 3.4 +PARM, THR_RATE_I, 0 +PARM, THR_RATE_D, 0 +PARM, THR_RATE_IMAX, 300 +PARM, THR_ACCEL_P, 0.75 +PARM, THR_ACCEL_I, 1.5 +PARM, THR_ACCEL_D, 0 +PARM, THR_ACCEL_IMAX, 500 +PARM, OF_RLL_P, 2.5 +PARM, OF_RLL_I, 0.5 +PARM, OF_RLL_D, 0.12 +PARM, OF_RLL_IMAX, 100 +PARM, OF_PIT_P, 2.5 +PARM, OF_PIT_I, 0.5 +PARM, OF_PIT_D, 0.12 +PARM, OF_PIT_IMAX, 100 +PARM, STB_RLL_P, 7.59375 +PARM, STB_RLL_I, 0 +PARM, STB_RLL_IMAX, 0 +PARM, STB_PIT_P, 7.59375 +PARM, STB_PIT_I, 0 +PARM, STB_PIT_IMAX, 0 +PARM, STB_YAW_P, 4.5 +PARM, STB_YAW_I, 0 +PARM, STB_YAW_IMAX, 0 +PARM, THR_ALT_P, 1.25 +PARM, THR_ALT_I, 0 +PARM, THR_ALT_IMAX, 300 +PARM, HLD_LAT_P, 1 +PARM, HLD_LAT_I, 0 +PARM, HLD_LAT_IMAX, 0 +PARM, HLD_LON_P, 1 +PARM, HLD_LON_I, 0 +PARM, HLD_LON_IMAX, 0 +PARM, CAM_TRIGG_TYPE, 0 +PARM, CAM_DURATION, 10 +PARM, CAM_SERVO_ON, 1300 +PARM, CAM_SERVO_OFF, 1100 +PARM, CAM_TRIGG_DIST, 0 +PARM, RELAY_PIN, 54 +PARM, RELAY_PIN2, -1 +PARM, RELAY_PIN3, -1 +PARM, RELAY_PIN4, -1 +PARM, COMPASS_OFS_X, -86.91773 +PARM, COMPASS_OFS_Y, 10.53659 +PARM, COMPASS_OFS_Z, 139.6827 +PARM, COMPASS_DEC, 0 +PARM, COMPASS_LEARN, 0 +PARM, COMPASS_USE, 1 +PARM, COMPASS_AUTODEC, 1 +PARM, COMPASS_MOTCT, 1 +PARM, COMPASS_MOT_X, NaN +PARM, COMPASS_MOT_Y, NaN +PARM, COMPASS_MOT_Z, NaN +PARM, COMPASS_ORIENT, 0 +PARM, COMPASS_EXTERNAL, 1 +PARM, COMPASS_OFS2_X, 0 +PARM, COMPASS_OFS2_Y, 0 +PARM, COMPASS_OFS2_Z, 0 +PARM, COMPASS_MOT2_X, 0 +PARM, COMPASS_MOT2_Y, 0 +PARM, COMPASS_MOT2_Z, 0 +PARM, INS_PRODUCT_ID, 5 +PARM, INS_ACCSCAL_X, 1.007623 +PARM, INS_ACCSCAL_Y, 1.004452 +PARM, INS_ACCSCAL_Z, 0.9874112 +PARM, INS_ACCOFFS_X, -0.1485449 +PARM, INS_ACCOFFS_Y, -0.2596635 +PARM, INS_ACCOFFS_Z, -0.4252791 +PARM, INS_GYROFFS_X, -0.02919539 +PARM, INS_GYROFFS_Y, 0.04272092 +PARM, INS_GYROFFS_Z, -0.002589351 +PARM, INS_MPU6K_FILTER, 0 +PARM, INS_ACC2SCAL_X, 1.029834 +PARM, INS_ACC2SCAL_Y, 1.005518 +PARM, INS_ACC2SCAL_Z, 0.9937073 +PARM, INS_ACC2OFFS_X, 1.241575 +PARM, INS_ACC2OFFS_Y, 1.355125 +PARM, INS_ACC2OFFS_Z, 1.51342 +PARM, INS_GYR2OFFS_X, 0.0258936 +PARM, INS_GYR2OFFS_Y, 0.01227257 +PARM, INS_GYR2OFFS_Z, -0.003733256 +PARM, INAV_TC_XY, 2.5 +PARM, INAV_TC_Z, 6 +PARM, WPNAV_SPEED, 300 +PARM, WPNAV_RADIUS, 200 +PARM, WPNAV_SPEED_UP, 250 +PARM, WPNAV_SPEED_DN, 100 +PARM, WPNAV_LOIT_SPEED, 500 +PARM, WPNAV_ACCEL, 100 +PARM, SR0_RAW_SENS, 0 +PARM, SR0_EXT_STAT, 0 +PARM, SR0_RC_CHAN, 0 +PARM, SR0_RAW_CTRL, 0 +PARM, SR0_POSITION, 0 +PARM, SR0_EXTRA1, 0 +PARM, SR0_EXTRA2, 0 +PARM, SR0_EXTRA3, 0 +PARM, SR0_PARAMS, 0 +PARM, SR1_RAW_SENS, 2 +PARM, SR1_EXT_STAT, 2 +PARM, SR1_RC_CHAN, 2 +PARM, SR1_RAW_CTRL, 0 +PARM, SR1_POSITION, 3 +PARM, SR1_EXTRA1, 10 +PARM, SR1_EXTRA2, 10 +PARM, SR1_EXTRA3, 2 +PARM, SR1_PARAMS, 10 +PARM, SR2_RAW_SENS, 0 +PARM, SR2_EXT_STAT, 0 +PARM, SR2_RC_CHAN, 0 +PARM, SR2_RAW_CTRL, 0 +PARM, SR2_POSITION, 0 +PARM, SR2_EXTRA1, 0 +PARM, SR2_EXTRA2, 0 +PARM, SR2_EXTRA3, 0 +PARM, SR2_PARAMS, 0 +PARM, AHRS_GPS_GAIN, 1 +PARM, AHRS_GPS_USE, 1 +PARM, AHRS_YAW_P, 0.1 +PARM, AHRS_RP_P, 0.1 +PARM, AHRS_WIND_MAX, 0 +PARM, AHRS_TRIM_X, -0.03818516 +PARM, AHRS_TRIM_Y, 0.0007720405 +PARM, AHRS_TRIM_Z, 0 +PARM, AHRS_ORIENTATION, 0 +PARM, AHRS_COMP_BETA, 0.1 +PARM, AHRS_GPS_MINSATS, 6 +PARM, AHRS_GPS_DELAY, 1 +PARM, MNT_MODE, 0 +PARM, MNT_RETRACT_X, 0 +PARM, MNT_RETRACT_Y, 0 +PARM, MNT_RETRACT_Z, 0 +PARM, MNT_NEUTRAL_X, 0 +PARM, MNT_NEUTRAL_Y, 0 +PARM, MNT_NEUTRAL_Z, 0 +PARM, MNT_CONTROL_X, 0 +PARM, MNT_CONTROL_Y, 0 +PARM, MNT_CONTROL_Z, 0 +PARM, MNT_STAB_ROLL, 0 +PARM, MNT_STAB_TILT, 0 +PARM, MNT_STAB_PAN, 0 +PARM, MNT_RC_IN_ROLL, 0 +PARM, MNT_ANGMIN_ROL, -4500 +PARM, MNT_ANGMAX_ROL, 4500 +PARM, MNT_RC_IN_TILT, 0 +PARM, MNT_ANGMIN_TIL, -4500 +PARM, MNT_ANGMAX_TIL, 4500 +PARM, MNT_RC_IN_PAN, 0 +PARM, MNT_ANGMIN_PAN, -4500 +PARM, MNT_ANGMAX_PAN, 4500 +PARM, MNT_JSTICK_SPD, 0 +PARM, BATT_MONITOR, 4 +PARM, BATT_VOLT_PIN, 2 +PARM, BATT_CURR_PIN, 3 +PARM, BATT_VOLT_MULT, 10.39345 +PARM, BATT_AMP_PERVOLT, 18.0018 +PARM, BATT_AMP_OFFSET, 0 +PARM, BATT_CAPACITY, 8000 +PARM, BRD_PWM_COUNT, 4 +PARM, GND_ABS_PRESS, 101322.9 +PARM, GND_TEMP, 38.6347 +PARM, GND_ALT_OFFSET, 0 +PARM, SCHED_DEBUG, 0 +PARM, FENCE_ENABLE, 0 +PARM, FENCE_TYPE, 3 +PARM, FENCE_ACTION, 1 +PARM, FENCE_ALT_MAX, 100 +PARM, FENCE_RADIUS, 150 +PARM, FENCE_MARGIN, 2 +PARM, GPSGLITCH_ENABLE, 1 +PARM, GPSGLITCH_RADIUS, 200 +PARM, GPSGLITCH_ACCEL, 1000 +PARM, MOT_TCRV_ENABLE, 1 +PARM, MOT_TCRV_MIDPCT, 52 +PARM, MOT_TCRV_MAXPCT, 93 +PARM, MOT_SPIN_ARMED, 100 +PARM, RCMAP_ROLL, 1 +PARM, RCMAP_PITCH, 2 +PARM, RCMAP_THROTTLE, 3 +PARM, RCMAP_YAW, 4 +MSG, ArduCopter V3.1.1 (681dafcf) +MSG, PX4: bf42b124 NuttX: a6686464 +MSG, PX4v2 26002600 0A473234 33353231 +MODE, Stabilize, 424 +D32, 9, 18954 +CMD, 1, 0, 16, 0, 0, 0.00, 14.110576, 100.6192012 +EV, 10 +CTUN, 95890, 0, 0, 0, 0, -0.07, -0.13, 0.00, 0.00, 0, 0 +DU32, 7, 262745 +CURR, 95891, 0, 0, 1532, 53, 5302, 11.98451 +ATT, 95891, 0.00, -0.25, 0.00, 0.26, 189.54, 189.54 +RCIN, 95891, 1503, 1504, 1027, 1511, 992, 992, 993, 991 +RCOU, 95892, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 95892, 0.0003300551, 3.118068E-05, 0.0001806917, 0.04847138, 0.4273195, -9.78664 +IMU2, 95892, 0.002608102, 0.000912793, -0.001082554, 0.01101041, 0.5059863, -9.731324 +GPS, 3, 56674000, 1777, 12, 1.32, 14.1105766, 100.6191906, -0.06, -2.50, 2.48, 287.33, -1.2, 95901 +IMU, 95910, -0.0009821467, 0.0001306534, 0.000565017, 0.0440198, 0.4103907, -9.796521 +IMU2, 95910, -0.0007523485, 0.001337406, 0.003994141, 0.06996822, 0.5036547, -9.86237 +GPS, 3, 56674600, 1777, 12, 1.32, 14.1105772, 100.619181, -0.06, -0.64, 2.24, 285.51, -1.32, 95922 +IMU, 95930, -0.000161415, -6.018579E-05, -0.0009395918, 0.04602193, 0.4273452, -9.776276 +IMU2, 95930, 0.004217926, 0.004194447, 0.002743313, 0.0233587, 0.5833725, -9.837802 +IMU, 95950, -6.760471E-05, -7.643178E-05, -0.001094451, 0.04254892, 0.4280649, -9.788452 +IMU2, 95950, -0.001128796, 0.000945677, -0.003048411, 0.03911483, 0.5818061, -9.765361 +IMU, 95972, 0.0002469253, 0.000534825, 0.002132082, 0.02599005, 0.4356834, -9.82601 +IMU2, 95972, 0.003803164, 0.0007087337, 0.003556, -0.01116824, 0.542949, -9.840604 +MAG, 95980, -424, 68, 62, -86, 10, 139, 0, 0, 0 +MAG2, 95980, -282, -19, 236, 0, 0, 0, 0, 0, 0 +CTUN, 95990, 0, 0, 0, 0, -0.06, -0.16, 0.00, 0.00, 0, 0 +ATT, 95991, 0.00, -0.36, 0.00, 0.17, 189.55, 189.55 +RCIN, 95991, 1503, 1504, 1026, 1511, 992, 992, 992, 992 +RCOU, 95991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 95991, -0.0008315947, -0.0006118864, 0.005963499, 0.07896003, 0.4259605, -9.77841 +IMU2, 95991, 0.004842978, -0.005481538, 0.00072484, 0.04396272, 0.5337764, -9.792355 +IMU, 96010, 0.001237309, -0.0001293421, -0.00771925, 0.0662415, 0.3264562, -9.784401 +IMU2, 96010, 0.001461238, -0.0009936234, -0.01617744, -0.06194246, 0.4550481, -9.752249 +IMU, 96030, -0.002142342, 0.001001354, -0.008340571, 0.05505657, 0.4283919, -9.779114 +IMU2, 96030, -0.01055922, -0.004093088, -0.007808299, 0.03303206, 0.538103, -9.692242 +GPS, 3, 56674600, 1777, 12, 1.32, 14.1105816, 100.6191549, -0.06, 2.17, 1.46, 282.10, -0.83, 96040 +ERR, 11, 2 +IMU, 96050, -0.004749874, 0.0003456436, 0.01313075, 0.002824038, 0.5241867, -9.799286 +IMU2, 96050, -0.004449332, -0.002830722, 0.01737293, 0.009243131, 0.6920582, -9.899565 +IMU, 96072, 0.002289375, -0.001058813, 0.01578502, -0.07158111, 0.3150902, -9.819265 +IMU2, 96072, 0.00346932, 0.00190183, 0.01440532, -0.07286, 0.4307256, -9.8231 +MAG, 96080, -421, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 96080, -282, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 96090, 0, 0, 0, 0, -0.07, -0.05, 0.00, 0.00, 0, 0 +ATT, 96090, 0.00, -0.72, 0.00, 0.03, 189.56, 189.56 +RCIN, 96090, 1503, 1504, 1028, 1510, 992, 992, 993, 992 +RCOU, 96090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96090, 0.007769374, 0.0009308942, -0.009168896, 0.0798659, 0.2679565, -9.804682 +IMU2, 96090, 4.541129E-05, 0.006001366, -0.01480796, -0.006455779, 0.3996272, -9.673789 +IMU, 96110, 0.004985156, -0.0009177215, -0.03779056, 0.04090804, 0.3486167, -9.743791 +IMU2, 96110, 0.00167701, -0.004181587, -0.03855282, -0.05323422, 0.5076005, -9.704834 +IMU, 96130, -0.005907046, 0.003225658, -0.01630748, 0.1314111, 0.7609013, -9.784241 +IMU2, 96130, 0.001601823, -0.001916378, -0.01041552, 0.1980277, 0.8447663, -9.880936 +IMU, 96150, -0.003933067, -0.004371688, 0.04936252, 0.0616512, 0.7023131, -9.787696 +IMU2, 96150, -0.002243515, -0.01160467, 0.06378991, 0.05199289, 0.8151442, -9.879122 +IMU, 96171, -0.005486319, -0.002939925, 0.03323961, 0.02296093, 0.06476419, -9.768613 +IMU2, 96171, -0.01082261, -0.001405461, 0.02306527, -0.01437461, 0.2381511, -9.749377 +MAG, 96180, -422, 68, 60, -86, 10, 139, 0, 0, 0 +MAG2, 96180, -281, -24, 236, 0, 0, 0, 0, 0, 0 +CTUN, 96190, 0, 0, 0, 0, -0.07, -0.18, 0.00, 0.00, 0, 0 +ATT, 96190, 0.00, -1.14, 0.00, -0.07, 189.56, 189.56 +RCIN, 96190, 1504, 1504, 1027, 1512, 992, 993, 992, 992 +RCOU, 96191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96191, -0.01289027, 0.0009174868, -0.03333784, 0.1448201, 0.335862, -9.83723 +IMU2, 96191, -0.020836, -0.00825828, -0.02822849, 0.0853008, 0.5176723, -9.858112 +IMU, 96210, 0.007586712, -0.004972283, -0.0214536, -0.07948971, 0.2940454, -9.785866 +IMU2, 96210, 0.0001347847, -0.01232551, -0.01955692, -0.0005649328, 0.3652067, -9.555433 +IMU, 96231, 0.0061219, -0.006054558, -0.02386739, 0.1147051, 0.4197633, -9.767506 +IMU2, 96231, 0.003793795, -0.004731293, -0.02264143, 0.06776845, 0.5277125, -9.896957 +GPS, 3, 56676400, 1777, 9, 2.54, 14.1105813, 100.6191541, -0.07, 2.17, 1.46, 281.11, -0.66, 96240 +IMU, 96250, 0.006261809, -0.003656689, -0.01636885, 0.1411799, 0.4571569, -9.818777 +IMU2, 96250, 0.009787668, 8.29529E-06, -0.01610763, 0.1387742, 0.5273286, -9.693589 +IMU, 96271, 0.003390335, -0.007922072, 0.03235325, 0.1007699, 0.7760391, -9.726461 +IMU2, 96271, 0.008752227, -0.009106061, 0.04324618, 0.1649549, 0.8947295, -9.715615 +MAG, 96280, -423, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 96280, -280, -22, 232, 0, 0, 0, 0, 0, 0 +CTUN, 96290, 0, 0, 0, 0, -0.07, 0.01, 0.00, 0.00, 0, 0 +ATT, 96291, 0.00, -1.39, 0.00, -0.17, 189.57, 189.57 +RCIN, 96291, 1504, 1504, 1026, 1510, 993, 992, 992, 992 +RCOU, 96291, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96291, 0.00184443, -0.00319149, 0.05981512, -0.02441043, 0.3726792, -9.862672 +IMU2, 96291, -0.003412087, 0.0002293773, 0.06990407, -0.01329339, 0.5231104, -9.854074 +IMU, 96310, -0.009164764, 0.003327772, 0.01653023, -0.1067433, 0.1251355, -9.812826 +IMU2, 96310, -0.01669094, -0.001387345, 0.005929334, -0.1572839, 0.3345186, -9.855619 +IMU, 96331, -0.007992258, 0.005826924, -0.04646493, -0.10435, 0.3003148, -9.850533 +IMU2, 96331, -0.006297782, 0.01708363, -0.04402058, -0.1613911, 0.4906119, -9.742288 +IMU, 96350, 0.005633032, 0.00809212, -0.05222034, 0.05510949, 0.5099123, -9.872605 +IMU2, 96350, -0.001783293, 0.001858925, -0.04580709, 0.06330812, 0.6171741, -9.973408 +IMU, 96370, 0.007728094, 0.003459003, -0.001291914, 0.1262896, 0.5893066, -9.722572 +IMU2, 96370, 0.01139433, -0.006147399, 0.003298348, 0.1331872, 0.6886414, -9.659645 +MAG, 96380, -426, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 96380, -281, -21, 231, 0, 0, 0, 0, 0, 0 +CTUN, 96390, 0, 0, 0, 0, -0.07, 0.06, 0.00, 0.00, 0, 0 +ATT, 96391, 0.00, -1.40, 0.00, -0.16, 189.53, 189.53 +RCIN, 96391, 1504, 1503, 1027, 1510, 992, 993, 992, 992 +RCOU, 96391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96391, 0.003124423, -0.001252662, 0.04680479, 0.1801493, 0.4459013, -9.648439 +IMU2, 96391, -0.001555834, -0.01265137, 0.05117305, 0.1558603, 0.576853, -9.729488 +IMU, 96410, -0.002451932, 0.001770478, 0.04096214, 0.1554697, 0.2874705, -9.845304 +IMU2, 96410, -0.004111458, -0.01276694, 0.03968393, 0.1207542, 0.4296156, -9.72986 +IMU, 96431, -0.005783794, -0.001000792, -0.007511574, 0.08667986, 0.2805515, -9.778788 +IMU2, 96431, -0.00710074, -0.006929952, -0.02034733, 0.04881191, 0.392285, -9.707546 +GPS, 3, 56676600, 1777, 10, 2.42, 14.1105827, 100.6191504, -0.06, 2.21, 1.63, 285.46, -0.59, 96440 +IMU, 96450, -0.00469132, -0.001085028, -0.04455892, 0.04469742, 0.3999687, -9.770671 +IMU2, 96450, -0.002124147, 0.0003309026, -0.03989979, 0.02828145, 0.5773031, -9.654748 +IMU, 96471, 4.305877E-05, 0.001276877, -0.02883464, -0.02104209, 0.4989496, -9.818288 +IMU2, 96471, -0.01156176, -0.004186703, -0.0187913, 0.05143702, 0.6197199, -9.802992 +MAG, 96480, -424, 71, 59, -86, 10, 139, 0, 0, 0 +MAG2, 96480, -283, -18, 230, 0, 0, 0, 0, 0, 0 +CTUN, 96490, 0, 0, 0, 0, -0.06, -0.04, 0.00, 0.00, 0, 0 +ATT, 96490, 0.00, -1.38, 0.00, -0.14, 189.51, 189.51 +RCIN, 96490, 1503, 1504, 1027, 1510, 992, 992, 993, 992 +RCOU, 96490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96490, 0.007110998, -0.001394346, 0.01447614, -0.01856062, 0.5148976, -9.847913 +IMU2, 96490, 0.002182217, -0.003439816, 0.02349494, 0.04366529, 0.5981519, -9.932091 +IMU, 96510, 0.004182154, 0.001298204, 0.03766149, 0.01300329, 0.3850732, -9.804632 +IMU2, 96510, 0.00342395, 0.00279507, 0.03842603, -0.03860104, 0.4967276, -9.787738 +IMU, 96530, -0.004580261, 0.004862219, 0.01624249, 0.01177673, 0.3273551, -9.778834 +IMU2, 96530, -0.0007247049, 0.006628461, 0.01071892, 0.01032925, 0.4922744, -9.903612 +IMU, 96551, -0.001931647, 0.001766726, -0.02053646, 0.08351476, 0.4228689, -9.83811 +IMU2, 96551, 0.005289588, 0.003567355, -0.02488003, 0.07885301, 0.5689861, -9.785088 +IMU, 96570, -0.001845622, 0.0009451881, -0.02944209, 0.09105749, 0.5013096, -9.750097 +IMU2, 96570, -0.003928712, 0.001887301, -0.02788237, 0.1175249, 0.6173378, -9.609287 +MAG, 96580, -424, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 96580, -283, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 96590, 0, 0, 0, 0, -0.06, -0.02, 0.00, 0.00, 0, 0 +ATT, 96591, 0.00, -1.33, 0.00, -0.05, 189.52, 189.52 +RCIN, 96591, 1503, 1504, 1027, 1510, 992, 993, 992, 992 +RCOU, 96591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96591, 0.003489064, -0.002257146, -0.005040305, 0.03069181, 0.4968213, -9.741073 +IMU2, 96591, -0.002782485, -0.002130993, 0.0008914412, 0.0460701, 0.6382558, -9.79085 +IMU, 96610, 0.007351881, -0.005673118, 0.01970799, 0.01988347, 0.3840539, -9.822873 +IMU2, 96610, 0.008527316, -0.004034685, 0.02134662, 0.0173986, 0.4790342, -10.07603 +IMU, 96630, -0.005581187, 0.001584783, 0.01943239, -0.01936373, 0.2502993, -9.846452 +IMU2, 96630, -0.009639965, 3.179908E-05, 0.01830522, -0.006766796, 0.3807832, -9.856627 +GPS, 3, 56676800, 1777, 10, 2.42, 14.1105834, 100.6191477, -0.06, 2.26, 1.56, 286.82, -0.53, 96640 +ERR, 11, 0 +IMU, 96650, -0.00603793, 0.00242161, -0.004842357, 0.01011831, 0.3771327, -9.779447 +IMU2, 96650, -0.002360184, -0.002923981, -0.005364096, 0.02027547, 0.5534456, -9.682236 +IMU, 96671, 0.0007730182, -5.09806E-05, -0.02025016, 0.08237778, 0.502821, -9.806449 +IMU2, 96671, -0.005199725, 0.003919491, -0.02124717, 0.05896807, 0.634107, -9.7395 +MAG, 96680, -422, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 96680, -283, -18, 232, 0, 0, 0, 0, 0, 0 +CTUN, 96690, 0, 0, 0, 0, -0.06, -0.04, 0.00, 0.00, 0, 0 +ATT, 96690, 0.00, -1.30, 0.00, -0.01, 189.54, 189.54 +RCIN, 96690, 1503, 1504, 1026, 1511, 992, 992, 993, 991 +RCOU, 96691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96691, -0.00283567, 0.0026704, -0.006482869, 0.06044631, 0.5414412, -9.819135 +IMU2, 96691, -0.0001043342, 0.006862428, -0.001563504, 0.08333135, 0.6781532, -9.861589 +IMU, 96711, 0.01281849, -0.002039239, 0.01127663, 0.02032249, 0.4730232, -9.799807 +IMU2, 96711, 0.01142905, -0.002204303, 0.01590621, -0.04196882, 0.6395452, -9.816566 +IMU, 96730, 0.004726948, -0.002400883, 0.01041272, 0.01585931, 0.2335253, -9.764712 +IMU2, 96730, 0.003847498, 0.005314058, 0.01530278, 0.03279018, 0.3529367, -9.809809 +IMU, 96750, -0.01049428, 0.00689552, -0.002321461, 0.01237142, 0.3043614, -9.841002 +IMU2, 96750, -0.01364218, 0.001881326, -0.006212948, 0.01688194, 0.4530391, -9.871028 +IMU, 96771, -0.000380123, -0.002584144, -0.01232199, 0.07212281, 0.5097458, -9.743884 +IMU2, 96771, 0.01055465, -0.006842465, -0.01154366, 0.04865885, 0.6619164, -9.745512 +MAG, 96780, -423, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 96780, -283, -18, 234, 0, 0, 0, 0, 0, 0 +CTUN, 96790, 0, 0, 0, 0, -0.06, -0.01, 0.00, 0.00, 0, 0 +ATT, 96791, 0.00, -1.31, 0.00, -0.02, 189.55, 189.55 +RCIN, 96791, 1503, 1504, 1027, 1510, 992, 993, 992, 992 +RCOU, 96791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96791, -0.006575434, -0.003057133, -0.001626128, 0.08151996, 0.5136057, -9.824515 +IMU2, 96791, -0.009259552, -0.00375748, -0.003873657, -0.01021016, 0.6287439, -9.835629 +IMU, 96811, 0.00851687, 0.002490103, 0.01162791, 0.01664646, 0.5284026, -9.800533 +IMU2, 96811, 0.014163, -0.005624748, 0.01098242, 0.002051115, 0.6369412, -9.881124 +IMU, 96831, 0.01361982, -0.008717723, 0.004543159, -0.01405549, 0.2441867, -9.745026 +IMU2, 96831, 0.003805976, -0.005299035, 0.004648587, -0.1117901, 0.3737836, -9.664142 +GPS, 3, 56677000, 1777, 10, 2.42, 14.1105848, 100.6191447, -0.06, 2.15, 1.51, 288.96, -0.43, 96840 +IMU, 96850, -0.00913352, 0.008686036, -0.009359822, 0.02095838, 0.261115, -9.85012 +IMU2, 96850, -0.003713844, 0.01206475, -0.008668013, 0.03029907, 0.5042971, -9.791725 +IMU, 96870, -0.003417337, 0.003946174, -0.01091209, 0.0942038, 0.4717318, -9.724969 +IMU2, 96870, -0.001928607, -0.001475671, -0.007469022, 0.07926536, 0.6013764, -9.681035 +MAG, 96880, -423, 70, 59, -86, 10, 139, 0, 0, 0 +MAG2, 96880, -283, -17, 232, 0, 0, 0, 0, 0, 0 +CTUN, 96890, 0, 0, 0, 0, -0.06, -0.12, 0.00, 0.00, 0, 0 +DU32, 7, 262745 +CURR, 96890, 0, 0, 1531, 120, 5318, 12.41699 +ATT, 96891, 0.00, -1.31, 0.00, -0.01, 189.55, 189.55 +RCIN, 96891, 1503, 1503, 1027, 1510, 992, 993, 992, 992 +RCOU, 96891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96891, -0.008873323, -0.005979486, 0.006683235, 0.08344984, 0.5214467, -9.813636 +IMU2, 96891, -0.01383435, -0.004266547, 0.007532064, 0.1247317, 0.6811022, -9.791861 +IMU, 96910, 0.001903782, 0.00794046, 0.01632601, 0.002865285, 0.4668978, -9.830123 +IMU2, 96910, 0.001961466, 0.01384632, 0.0150997, 0.04291117, 0.6259702, -9.835535 +IMU, 96930, 0.01085529, -0.007577851, 0.001834584, 0.01159953, 0.2558644, -9.698481 +IMU2, 96930, 0.01087382, -0.01287242, 0.0009491602, -0.04448676, 0.3618015, -9.656192 +IMU, 96950, 0.005496226, 0.004956611, -0.01756132, 0.05717558, 0.2953855, -9.909133 +IMU2, 96950, 0.01257629, 0.01335729, -0.02116182, 0.004493713, 0.4812754, -9.97098 +IMU, 96970, -0.002357488, 0.004031543, -0.01329077, 0.109788, 0.4416046, -9.733743 +IMU2, 96970, -0.004913947, -0.002073715, -0.01493309, 0.08643305, 0.5986942, -9.778146 +MAG, 96980, -423, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 96980, -284, -18, 232, 0, 0, 0, 0, 0, 0 +CTUN, 96990, 0, 0, 0, 0, -0.06, 0.00, 0.00, 0.00, 0, 0 +ATT, 96990, 0.00, -1.32, 0.00, 0.00, 189.55, 189.55 +RCIN, 96990, 1502, 1504, 1027, 1510, 992, 993, 992, 992 +RCOU, 96991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 96991, -0.005797585, -0.01025219, 0.011181, 0.09797283, 0.6031722, -9.76777 +IMU2, 96991, -0.001103269, -0.01408836, 0.01849141, 0.1292152, 0.7495397, -9.853018 +IMU, 97010, -0.002762543, 0.003402948, 0.02171988, -0.003901362, 0.447396, -9.80054 +IMU2, 97010, 0.005727947, 0.004937749, 0.01570049, -0.009031057, 0.5919315, -9.747257 +IMU, 97031, -0.0002244562, -0.00148657, -0.0002959378, -0.05523814, 0.3133928, -9.816769 +IMU2, 97031, 0.001866937, -0.006835631, -0.006386385, -0.09397733, 0.4556978, -9.856174 +GPS, 3, 56677200, 1777, 10, 2.42, 14.110586, 100.6191426, -0.06, 1.88, 1.36, 289.61, -0.25, 97040 +IMU, 97050, -0.001316743, 0.002542656, -0.02076989, -0.005216494, 0.2735472, -9.873631 +IMU2, 97050, -0.007731609, 0.007134184, -0.02052278, 0.0165056, 0.4068105, -9.848598 +IMU, 97070, -0.0005618427, 0.001651831, -0.009784732, 0.09875646, 0.4929613, -9.760497 +IMU2, 97070, -0.00213279, 0.006941773, -0.005915055, 0.04419398, 0.575222, -9.88875 +MAG, 97081, -423, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97081, -283, -18, 232, 0, 0, 0, 0, 0, 0 +CTUN, 97090, 0, 0, 0, 0, -0.06, -0.19, 0.00, 0.00, 0, 0 +ATT, 97090, 0.00, -1.34, 0.00, 0.00, 189.56, 189.56 +RCIN, 97090, 1504, 1503, 1027, 1510, 993, 992, 992, 992 +RCOU, 97090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97090, 0.000621194, -0.003442965, 0.01464875, 0.05560463, 0.4875905, -9.800257 +IMU2, 97090, -0.001954636, -0.005002085, 0.01602529, 0.05635154, 0.6530517, -9.800668 +IMU, 97110, 0.005375147, -0.001447719, 0.01522672, 0.05506899, 0.3949506, -9.796881 +IMU2, 97110, 0.007292539, 0.007138453, 0.008088192, 0.02346647, 0.5226569, -9.835768 +IMU, 97130, -0.003421882, 0.006133106, -0.006819135, 0.03473414, 0.2560315, -9.795057 +IMU2, 97130, -0.01121635, 0.006290272, -0.006281287, 0.0530951, 0.432249, -9.725469 +IMU, 97150, -0.005152488, 2.7854E-05, -0.01590687, 0.09208527, 0.424143, -9.8036 +IMU2, 97150, -0.007455876, 0.009383619, -0.0185683, 0.1235149, 0.6226897, -9.745408 +IMU, 97170, 0.002436915, -0.002757296, -0.001423704, 0.05323859, 0.4550555, -9.808599 +IMU2, 97170, -0.00740795, 0.00149233, 0.003579131, -0.003332615, 0.6043037, -9.6862 +MAG, 97180, -424, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97180, -284, -20, 232, 0, 0, 0, 0, 0, 0 +CTUN, 97191, 0, 0, 0, 0, -0.06, -0.17, 0.00, 0.00, 0, 0 +ATT, 97191, 0.00, -1.37, 0.00, -0.01, 189.57, 189.57 +RCIN, 97191, 1504, 1503, 1027, 1510, 992, 993, 992, 992 +RCOU, 97191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97191, 0.004844621, -0.00209732, 0.01070679, -0.0001567602, 0.372945, -9.750602 +IMU2, 97191, 0.01416297, -0.001784779, 0.01289474, 0.007372856, 0.4840229, -9.700284 +IMU, 97210, 0.009540262, -0.003041979, 0.0009253937, 0.02809577, 0.2781599, -9.876833 +IMU2, 97210, 0.006674841, -0.004652936, -0.005046376, 0.02273655, 0.4008609, -9.778224 +IMU, 97231, -0.002742128, 0.003083974, -0.007732253, 0.1061789, 0.3178559, -9.699114 +IMU2, 97231, -0.004405793, 0.004041474, -0.007479691, 0.09997356, 0.4649265, -9.69242 +GPS, 3, 56677400, 1777, 10, 2.42, 14.1105872, 100.6191404, -0.07, 1.69, 1.27, 290.28, -0.12, 97240 +IMU, 97251, -0.006188916, -0.003119715, 8.542067E-05, 0.1165342, 0.4936258, -9.778388 +IMU2, 97251, 0.002224725, -0.006394583, -0.001199187, 0.1013162, 0.6235121, -9.676967 +IMU, 97270, 0.002062622, -0.001618996, 0.009207827, -0.001459494, 0.4371014, -9.819072 +IMU2, 97270, 0.002825228, -0.003099986, 0.0131735, -0.07969761, 0.5806754, -9.782886 +MAG, 97280, -421, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97280, -283, -19, 231, 0, 0, 0, 0, 0, 0 +CTUN, 97290, 0, 0, 0, 0, -0.07, -0.13, 0.00, 0.00, 0, 0 +ATT, 97290, 0.00, -1.40, 0.00, -0.03, 189.58, 189.58 +RCIN, 97290, 1503, 1504, 1027, 1511, 992, 992, 992, 992 +RCOU, 97290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97290, 0.001310268, 0.003470749, 0.0002358386, -0.006742835, 0.3258371, -9.773828 +IMU2, 97290, -0.003163798, -0.001680681, 0.0004444635, 0.05048823, 0.4200022, -9.722442 +IMU, 97310, 0.001239339, 0.002315793, -0.007981434, -0.003645644, 0.3446205, -9.853656 +IMU2, 97310, 0.002827797, 0.005124945, -0.004546103, 0.01924253, 0.4704539, -9.892382 +IMU, 97331, 0.003264913, -0.001010448, 0.002182462, 0.07923, 0.4527652, -9.758833 +IMU2, 97331, 0.007653739, 0.004429961, 0.007361482, 0.09655547, 0.5620528, -9.692983 +IMU, 97351, 0.003899293, -0.001514897, 0.01170143, 0.000472635, 0.4712112, -9.850106 +IMU2, 97351, 0.006435141, -0.001224757, 0.01446478, -0.06303561, 0.6111718, -9.880411 +IMU, 97370, 0.00715098, -0.0008460172, 0.0002020206, -0.005860507, 0.3327039, -9.801154 +IMU2, 97370, -0.003510525, 0.0002365345, -0.002387254, 0.01302636, 0.5026151, -9.716815 +MAG, 97380, -424, 71, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97380, -282, -19, 232, 0, 0, 0, 0, 0, 0 +CTUN, 97390, 0, 0, 0, 0, -0.07, -0.14, 0.00, 0.00, 0, 0 +ATT, 97390, 0.00, -1.42, 0.00, -0.03, 189.57, 189.57 +RCIN, 97390, 1503, 1504, 1027, 1510, 992, 993, 992, 992 +RCOU, 97391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97391, -0.002294945, 0.003057972, -0.01433028, 0.0317574, 0.3739161, -9.859117 +IMU2, 97391, -0.00418726, 0.00753279, -0.01576317, -0.02319002, 0.5338123, -9.892717 +IMU, 97411, -0.003039667, -0.0005792864, -0.003993779, 0.09414549, 0.517381, -9.707568 +IMU2, 97411, 0.0009250008, 0.006912384, -0.0006239698, 0.1014752, 0.6648191, -9.780729 +IMU, 97430, 0.0006349459, -0.004926875, 0.01298706, -0.0005097687, 0.5046299, -9.821255 +IMU2, 97430, 0.002703723, -0.006587907, 0.007492538, 0.003484249, 0.6625379, -9.847482 +GPS, 3, 56677600, 1777, 10, 2.42, 14.110589, 100.6191367, -0.08, 1.64, 1.30, 292.70, -0.09999999, 97440 +IMU, 97450, 0.005011598, 0.002750151, 0.009345217, 0.03325059, 0.3238256, -9.746146 +IMU2, 97450, 0.003336117, -0.001370902, -0.00179154, -0.05502188, 0.4576173, -9.835378 +IMU, 97471, -0.006962212, 0.002609845, -0.009344577, 0.05755249, 0.3489938, -9.820162 +IMU2, 97471, 0.0005834084, 0.005543303, -0.01423227, 0.006945848, 0.4552295, -9.908424 +MAG, 97480, -423, 69, 61, -86, 10, 139, 0, 0, 0 +MAG2, 97480, -283, -17, 230, 0, 0, 0, 0, 0, 0 +CTUN, 97490, 0, 0, 0, 0, -0.08, -0.10, 0.00, 0.00, 0, 0 +ATT, 97490, 0.00, -1.44, 0.00, -0.01, 189.57, 189.57 +RCIN, 97490, 1503, 1504, 1026, 1511, 992, 992, 993, 991 +RCOU, 97490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97490, -0.0003847461, 0.001866657, -0.006814853, 0.1149021, 0.4504839, -9.78954 +IMU2, 97490, -0.00833806, -0.008050945, -0.005501085, 0.1365086, 0.5351946, -9.838549 +IMU, 97510, -0.0006100107, -0.003071867, 0.008294147, 0.01884735, 0.518268, -9.805443 +IMU2, 97510, -0.001794038, -0.002207079, 0.00908378, 0.02654123, 0.615652, -9.868294 +IMU, 97530, 0.005034808, 0.0005367547, 0.006660076, 0.01240261, 0.3308756, -9.802133 +IMU2, 97530, -0.0007880107, -0.005950221, 0.007490913, -0.0004794598, 0.4790008, -9.764924 +IMU, 97550, 4.993379E-05, 0.001631759, -0.005515889, 0.001551464, 0.3100188, -9.822131 +IMU2, 97550, 0.0002679154, 0.009166986, -0.008247595, 0.007954597, 0.4588802, -9.848437 +IMU, 97570, -0.001097329, 0.001543723, -0.003427681, 0.1195249, 0.4349164, -9.778702 +IMU2, 97570, 5.022436E-05, 0.0007460024, -0.003577277, 0.1821182, 0.5214647, -9.722858 +MAG, 97580, -424, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 97580, -283, -18, 233, 0, 0, 0, 0, 0, 0 +CTUN, 97590, 0, 0, 0, 0, -0.08, -0.07, 0.00, 0.00, 0, 0 +ATT, 97590, 0.00, -1.42, 0.00, 0.00, 189.59, 189.59 +RCIN, 97590, 1503, 1504, 1027, 1510, 992, 993, 992, 992 +RCOU, 97591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97591, 0.002549829, -0.005013272, 0.006112355, -0.0317505, 0.4290596, -9.81116 +IMU2, 97591, -0.005090278, 0.001935044, 0.001076899, -0.04445004, 0.5732718, -9.971998 +IMU, 97610, 0.005793825, 0.001855414, 0.001932908, 0.04469506, 0.2760678, -9.788642 +IMU2, 97610, 0.001412252, 0.005781041, -0.006028542, 0.03358793, 0.4306233, -9.67426 +IMU, 97631, 0.0002875775, 0.0008822605, -0.010772, -0.00319317, 0.3328316, -9.811236 +IMU2, 97631, -0.002299828, -0.0005227029, -0.007375253, 0.0004868507, 0.5007907, -9.736079 +GPS, 3, 56677800, 1777, 10, 2.42, 14.1105902, 100.6191342, -0.08, 1.64, 1.21, 295.10, -0.09999999, 97640 +IMU, 97650, -0.001097286, 0.001042038, -0.001341458, 0.1576501, 0.4570506, -9.758335 +IMU2, 97650, -0.003352387, -0.003354807, 0.002213051, 0.1560448, 0.5745126, -9.608218 +IMU, 97670, 0.00893461, -0.004390884, 0.01106527, -0.0292992, 0.4447888, -9.817816 +IMU2, 97670, 0.005899452, -0.002264823, 0.01050602, -0.09437013, 0.5346063, -9.735309 +MAG, 97680, -423, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97680, -283, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 97690, 0, 0, 0, 0, -0.08, -0.02, 0.00, 0.00, 0, 0 +ATT, 97690, 0.00, -1.43, 0.00, 0.02, 189.60, 189.60 +RCIN, 97690, 1503, 1504, 1026, 1511, 992, 992, 993, 991 +RCOU, 97691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97691, -0.001151724, 0.002814606, 0.001308166, 0.02615201, 0.2170453, -9.753443 +IMU2, 97691, -0.01074466, 0.001336033, -0.003856678, -0.0706284, 0.3597704, -9.68965 +IMU, 97710, -0.0009797476, 0.003878176, -0.01176087, 0.03324014, 0.346395, -9.82534 +IMU2, 97710, -0.01067719, 0.004306322, -0.01477076, 0.05228841, 0.5055866, -9.803888 +IMU, 97730, -0.003432868, 0.001033325, -0.001830435, 0.1203382, 0.4504208, -9.691119 +IMU2, 97730, -0.001859862, -0.004950619, -0.003085414, 0.1365914, 0.6247461, -9.669067 +IMU, 97750, 0.004894497, -0.002872646, 0.009271335, -0.05194965, 0.4584474, -9.91913 +IMU2, 97750, 0.006089196, 0.004356882, 0.01164783, -0.01224244, 0.6005051, -9.76209 +IMU, 97770, 0.0006659348, 0.003399979, 0.001380683, 0.04735705, 0.1631286, -9.733449 +IMU2, 97770, -0.003891846, -0.0008728933, -0.001348861, 0.02537739, 0.3488026, -9.679719 +MAG, 97780, -425, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97780, -283, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 97790, 0, 0, 0, 0, -0.08, -0.16, 0.00, 0.00, 0, 0 +ATT, 97790, 0.00, -1.45, 0.00, 0.03, 189.59, 189.59 +RCIN, 97790, 1503, 1504, 1026, 1510, 993, 992, 992, 992 +RCOU, 97791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97791, -0.001558537, 0.002029266, -0.01009224, 0.04538866, 0.3972062, -9.835378 +IMU2, 97791, -0.004288021, 0.01157895, -0.009274508, 0.09959435, 0.4939836, -9.8006 +IMU, 97810, -0.0026638, -0.002828479, -0.002132925, 0.1740034, 0.494275, -9.737828 +IMU2, 97810, 0.004643403, -0.006856284, 0.004542, 0.1468287, 0.6510121, -9.75069 +IMU, 97831, 0.004134746, -0.0003689751, 0.006204894, 0.02104741, 0.438797, -9.753789 +IMU2, 97831, 0.004082344, 0.001221947, 0.003773074, 0.03503978, 0.5444001, -9.638026 +GPS, 3, 56678000, 1777, 10, 2.42, 14.1105911, 100.619133, -0.08, 1.47, 1.12, 296.35, 0.03, 97840 +IMU, 97851, -0.0001340937, 0.0009457618, -0.002018677, 0.07796916, 0.3087648, -9.774381 +IMU2, 97851, 0.004240923, 0.000763108, 0.003108321, 0.0271498, 0.4251028, -9.731868 +IMU, 97870, -0.002352988, 0.005717576, -0.005571901, 0.06958007, 0.4166403, -9.828822 +IMU2, 97870, -0.008354152, 0.002414542, -0.002817529, 0.09432685, 0.5291157, -9.718664 +MAG, 97880, -423, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97880, -284, -17, 234, 0, 0, 0, 0, 0, 0 +CTUN, 97890, 0, 0, 0, 0, -0.08, -0.12, 0.00, 0.00, 0, 0 +DU32, 7, 262745 +CURR, 97890, 0, 0, 1533, 125, 5314, 12.77009 +ATT, 97891, 0.00, -1.47, 0.00, 0.03, 189.59, 189.59 +RCIN, 97891, 1503, 1504, 1028, 1510, 992, 992, 993, 992 +RCOU, 97891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97891, 9.826943E-05, -0.003694281, 0.005492737, 0.04900135, 0.5006176, -9.713171 +IMU2, 97891, 0.005135294, -0.003078458, 0.006473778, 0.05448079, 0.6498724, -9.870632 +IMU, 97910, 0.0043619, 0.0008941963, 0.005724513, -0.05553606, 0.3400166, -9.897219 +IMU2, 97910, 0.005698457, 0.005716341, -0.0003059199, -0.02150023, 0.472647, -9.869509 +IMU, 97930, 0.0004250482, 0.004484188, -0.006378135, 0.05563002, 0.3392111, -9.763164 +IMU2, 97930, 0.004094038, 0.0003996696, -0.006434865, -0.01959252, 0.5062276, -9.841893 +IMU, 97950, -0.003294567, -0.0001568273, -0.005211705, 0.08409099, 0.446012, -9.807865 +IMU2, 97950, -0.004335817, 0.005336693, -0.004062325, 0.1070225, 0.5612853, -9.785153 +IMU, 97970, 0.005020164, -0.003789365, 0.006167757, 0.0193703, 0.5570077, -9.756973 +IMU2, 97970, 0.005293019, -0.005423331, 0.001828918, 0.04552805, 0.6917776, -9.833418 +MAG, 97980, -424, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 97980, -283, -19, 232, 0, 0, 0, 0, 0, 0 +CTUN, 97990, 0, 0, 0, 0, -0.09, -0.13, 0.00, 0.00, 0, 0 +ATT, 97990, 0.00, -1.49, 0.00, 0.02, 189.60, 189.60 +RCIN, 97990, 1503, 1504, 1026, 1281, 993, 992, 992, 992 +RCOU, 97991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 97991, -0.005169937, -4.1686E-05, 0.004627439, -0.007010043, 0.2469673, -9.832038 +IMU2, 97991, 0.001501188, 0.004630838, 0.002296589, -0.05134881, 0.3726332, -9.686134 +IMU, 98010, -0.0002658907, 0.001670387, -0.005762041, 0.03429979, 0.4027213, -9.773249 +IMU2, 98010, -0.001969842, 0.005263042, -0.01244388, -0.04133427, 0.5049963, -9.752761 +IMU, 98031, -0.008464532, -0.001926221, -0.001075867, 0.1254611, 0.3859717, -9.690482 +IMU2, 98031, -0.006351205, -0.006579322, -0.0003892379, 0.1234138, 0.5666953, -9.658089 +GPS, 3, 56678200, 1777, 10, 2.42, 14.1105918, 100.6191313, -0.09, 1.35, 1.09, 293.58, 0.11, 98040 +IMU, 98050, 0.008776873, -0.002713218, 0.004409526, 0.001072451, 0.4896904, -9.804979 +IMU2, 98050, 0.007019531, -0.001569867, -0.0009901514, 0.02672386, 0.6448292, -9.754304 +IMU, 98070, -0.005849229, -0.0001298897, 0.0006194948, 0.03807498, 0.1748219, -9.789237 +IMU2, 98070, -0.01602691, -0.004835353, 0.0009577104, 0.01072443, 0.3336051, -9.86799 +MAG, 98080, -424, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 98080, -283, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 98090, 0, 0, 0, 0, -0.09, -0.10, 0.00, 0.00, 0, 0 +ATT, 98090, 0.00, -1.49, 0.00, 0.00, 189.60, 189.60 +RCIN, 98090, 1504, 1503, 1027, 1044, 992, 993, 992, 992 +RCOU, 98091, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98091, 0.001565598, 0.005342871, -0.007151244, 0.1169423, 0.5009068, -9.767206 +IMU2, 98091, -0.007975621, 0.002619634, 0.0005456356, 0.2225059, 0.6692783, -9.69457 +IMU, 98110, -0.007611969, -0.003176518, 0.005847425, 0.07707417, 0.4257923, -9.839363 +IMU2, 98110, -0.005156804, 0.001654006, 0.001567233, 0.03355777, 0.5202017, -9.827044 +IMU, 98130, 0.009248482, 0.0009321123, 0.004086928, 0.08276188, 0.497504, -9.777888 +IMU2, 98130, 0.00192374, -0.00643188, 0.002601457, 0.09300566, 0.6419121, -9.835669 +IMU, 98151, -0.005255213, 0.003228169, -0.003603097, 0.02949044, 0.1573078, -9.772739 +IMU2, 98151, -0.0105793, 0.006987888, -0.00217722, 0.01239812, 0.335458, -9.791435 +IMU, 98170, -0.001694603, 0.001212735, -0.004200726, 0.1304229, 0.5451467, -9.848415 +IMU2, 98170, -0.01252353, -0.001796251, 0.004350878, 0.1367394, 0.7295421, -9.866675 +MAG, 98180, -423, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 98180, -284, -20, 234, 0, 0, 0, 0, 0, 0 +CTUN, 98190, 0, 0, 0, 0, -0.09, -0.07, 0.00, 0.00, 0, 0 +ATT, 98190, 0.00, -1.48, 0.00, -0.04, 189.61, 189.61 +RCIN, 98190, 1504, 1503, 1026, 1003, 992, 993, 992, 992 +RCOU, 98191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98191, -0.000129018, -0.004799105, 0.006598519, 0.008324862, 0.3962408, -9.716734 +IMU2, 98191, 0.0001864582, -0.00576856, 0.01030604, -0.05223238, 0.521175, -9.729334 +IMU, 98210, 0.0006794464, -0.001170829, 0.001895011, 0.03518954, 0.443383, -9.837824 +IMU2, 98210, 0.001710491, 0.000952499, 0.001897829, 0.01525891, 0.5494621, -9.895976 +IMU, 98231, -0.003421972, 0.00284351, -0.004675084, 0.07583797, 0.3502201, -9.799784 +IMU2, 98231, -0.004082175, -0.0005494356, -0.002909932, 0.05363679, 0.4924558, -9.846443 +GPS, 3, 56678400, 1777, 9, 3.00, 14.1105913, 100.6191318, -0.09, 1.41, 0.80, 292.68, 0.14, 98240 +IMU, 98250, -0.002702119, -0.002949052, 0.002108626, 0.05854396, 0.6114032, -9.781138 +IMU2, 98250, -0.001528535, -0.006018687, 0.006537124, 0.1496087, 0.6663715, -9.833223 +IMU, 98270, 0.003698302, 0.0001285449, 0.003982902, -0.01689459, 0.4150078, -9.839013 +IMU2, 98270, 0.0043662, -0.005267701, 0.007755219, -0.0420593, 0.5351284, -9.826518 +MAG, 98280, -422, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 98280, -284, -18, 232, 0, 0, 0, 0, 0, 0 +CTUN, 98290, 0, 0, 0, 0, -0.09, -0.14, 0.00, 0.00, 0, 0 +ATT, 98290, 0.00, -1.50, 0.00, -0.07, 189.61, 189.61 +RCIN, 98290, 1503, 1504, 1023, 1003, 993, 992, 992, 992 +RCOU, 98290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98290, 0.001498666, 0.002198484, -0.002567244, -0.04172061, 0.2792139, -9.821782 +IMU2, 98290, 0.00269793, 0.00356118, -0.005807584, -0.06304216, 0.4615057, -9.841345 +IMU, 98311, -0.001321146, 0.003613278, -0.004348463, 0.06087108, 0.386266, -9.790531 +IMU2, 98311, -0.008618753, -0.004704624, 0.0005165704, 0.03313303, 0.5375099, -9.760395 +IMU, 98330, 0.0005324688, -0.003480393, 0.006569872, 0.06157019, 0.4984163, -9.806369 +IMU2, 98330, 0.002642032, 0.00235508, 0.006660666, 0.001069784, 0.6005646, -9.669304 +IMU, 98351, 0.0009583849, 0.0007315315, 0.002034906, -0.01318029, 0.4549608, -9.780295 +IMU2, 98351, 0.000926625, -0.006057595, -0.0009988691, 0.007840276, 0.5879949, -9.919662 +IMU, 98371, 0.004462028, 0.002038509, -0.00534701, 0.02655404, 0.2934862, -9.855229 +IMU2, 98371, 0.009255052, 0.006964754, -0.007323939, 0.0322938, 0.4415052, -9.803576 +MAG, 98380, -424, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 98380, -283, -16, 233, 0, 0, 0, 0, 0, 0 +CTUN, 98390, 0, 0, 0, 0, -0.09, -0.16, 0.00, 0.00, 0, 0 +ATT, 98391, 0.00, -1.59, 0.00, -0.08, 189.61, 189.61 +RCIN, 98391, 1503, 1504, 1024, 1006, 992, 992, 993, 991 +RCOU, 98391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98391, -0.002659248, -9.551644E-05, -0.000418385, 0.08946524, 0.5286142, -9.815563 +IMU2, 98391, -0.002487443, 0.003188985, 0.005063556, 0.07135403, 0.652898, -9.848013 +IMU, 98410, 0.01069168, -0.002801582, 0.006449934, -0.02010725, 0.3805334, -9.83953 +IMU2, 98410, -0.003670726, -0.003639284, 0.007559927, 0.01599205, 0.4484026, -9.766366 +IMU, 98430, 0.003727602, 0.0003967732, -0.0006588215, -0.07260045, 0.3092303, -9.911707 +IMU2, 98430, 0.009061996, 0.004149732, 0.001199823, -0.02618289, 0.4375365, -9.972965 +GPS, 3, 56678600, 1777, 9, 3.00, 14.110591, 100.6191327, -0.10, 1.32, 0.57, 292.68, 0.26, 98440 +IMU, 98450, 0.002848597, 0.004366424, -0.005718641, 0.05932051, 0.3652175, -9.754871 +IMU2, 98450, 0.004823815, 0.0003444646, -0.004801664, 0.1062446, 0.5183991, -9.767824 +IMU, 98471, 0.001735769, -0.002094358, 0.006442961, -0.009065077, 0.5138138, -9.94927 +IMU2, 98471, -0.004830856, 0.001154425, 0.01253589, -0.003134727, 0.5889211, -9.875297 +MAG, 98480, -421, 69, 59, -86, 10, 139, 0, 0, 0 +MAG2, 98480, -284, -17, 231, 0, 0, 0, 0, 0, 0 +CTUN, 98490, 0, 0, 0, 0, -0.09999999, -0.16, 0.00, 0.00, 0, 0 +ATT, 98490, 0.00, -1.65, 0.00, -0.10, 189.62, 189.62 +RCIN, 98490, 1503, 1504, 1025, 1006, 992, 993, 992, 992 +RCOU, 98490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98490, 0.005099775, 0.0005872473, 0.002321768, -0.02135764, 0.387024, -9.772491 +IMU2, 98490, -0.001528254, 0.0032959, -0.000680306, -0.07382464, 0.5497603, -9.898603 +IMU, 98510, -0.002068968, 0.007889211, -0.007955107, 0.0136925, 0.2457245, -9.77809 +IMU2, 98510, -0.007545594, -0.0001933742, -0.009778205, -0.0571779, 0.423431, -9.837021 +IMU, 98530, -0.003875406, 0.0003802776, -0.002088644, 0.1135934, 0.4887854, -9.8039 +IMU2, 98530, -0.007558947, 0.002343928, 0.005045754, 0.1592776, 0.5994635, -9.806319 +IMU, 98550, 0.007457329, -0.003447719, 0.008088847, -0.05115497, 0.3810063, -9.775395 +IMU2, 98550, 0.009486437, -0.003062183, 0.005662934, -0.05839872, 0.5050179, -9.665888 +IMU, 98570, 3.58317E-05, 0.001588415, -0.002373678, 0.03252706, 0.2850364, -9.820687 +IMU2, 98570, -0.004047142, 0.006558787, -0.005600941, 0.02335703, 0.3676244, -9.788292 +MAG, 98581, -423, 69, 62, -86, 10, 139, 0, 0, 0 +MAG2, 98581, -285, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 98590, 0, 0, 0, 0, -0.09999999, 0.01, 0.00, 0.00, 0, 0 +ATT, 98590, 0.00, -1.72, 0.00, -0.10, 189.62, 189.62 +RCIN, 98590, 1503, 1504, 1024, 1003, 992, 993, 992, 992 +RCOU, 98591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98591, 0.002575768, 0.004448663, -0.009999055, 0.1109966, 0.3935014, -9.805577 +IMU2, 98591, -0.00393091, 0.008701056, -0.008900761, 0.05778933, 0.5623397, -9.801163 +IMU, 98610, -0.007215342, -0.005424995, 0.004161853, 0.07699253, 0.4826076, -9.703601 +IMU2, 98610, -0.001220733, -0.005097787, 0.009152496, 0.08190703, 0.5921642, -9.736135 +IMU, 98631, 0.003259933, 0.0003828481, 0.003745798, 0.05865859, 0.4274116, -9.786655 +IMU2, 98631, -0.01047845, -0.004165061, 0.005258253, 0.06729245, 0.5683655, -9.800692 +GPS, 3, 56678800, 1777, 8, 3.37, 14.1105902, 100.6191353, -0.10, 1.14, 0.23, 292.68, 0.38, 98640 +IMU, 98650, -0.006993888, 0.004220389, -0.007033245, 0.03440108, 0.2156069, -9.789529 +IMU2, 98650, -0.007589892, 0.003558857, 0.0007115137, 0.04389226, 0.3968465, -9.749367 +IMU, 98670, -0.000170324, -0.0003647432, -0.004691194, 0.1596621, 0.5953149, -9.708954 +IMU2, 98670, 0.00476547, -0.002851892, -0.002739787, 0.1489856, 0.7286621, -9.848536 +MAG, 98680, -422, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 98680, -283, -19, 233, 0, 0, 0, 0, 0, 0 +CTUN, 98690, 0, 0, 0, 0, -0.09999999, -0.09, 0.00, 0.00, 0, 0 +ATT, 98690, 0.00, -1.80, 0.00, -0.12, 189.63, 189.63 +RCIN, 98690, 1503, 1504, 1024, 1003, 992, 992, 993, 992 +RCOU, 98690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98691, -0.001817832, -0.003095299, 0.008584191, 0.01609273, 0.4027892, -9.746135 +IMU2, 98691, 0.00152183, -0.004984742, 0.01058388, -0.01479959, 0.5345668, -9.797546 +IMU, 98710, 0.006103059, -0.002675425, -0.001362793, 0.0136856, 0.3936787, -9.874266 +IMU2, 98710, 0.001792315, -0.003703851, -0.001783147, -0.02109921, 0.5450466, -9.838737 +IMU, 98730, -0.003539084, 0.005766902, -0.00828944, 0.12118, 0.3111885, -9.756535 +IMU2, 98730, -0.004109202, 0.005145432, -0.006943872, 0.1363628, 0.454107, -9.837322 +IMU, 98750, 0.0009071101, -0.002404489, 0.004507435, 0.06548233, 0.5786526, -9.764311 +IMU2, 98750, -0.00105322, -0.00449586, 0.008678193, 0.1369514, 0.6727189, -9.69173 +IMU, 98770, 0.002088234, -0.003598034, 0.006678463, -0.02201818, 0.3807703, -9.781886 +IMU2, 98770, 0.003281809, 0.001547304, 0.006555176, 0.03887296, 0.5121708, -9.883424 +MAG, 98780, -425, 69, 61, -86, 10, 139, 0, 0, 0 +MAG2, 98780, -282, -20, 235, 0, 0, 0, 0, 0, 0 +CTUN, 98790, 0, 0, 0, 0, -0.09999999, -0.05, 0.00, 0.00, 0, 0 +ATT, 98790, 0.00, -1.88, 0.00, -0.14, 189.63, 189.63 +RCIN, 98790, 1503, 1504, 1024, 1003, 993, 992, 992, 992 +RCOU, 98791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98791, 0.003212649, 0.001554459, -0.005202568, -0.01202901, 0.3032285, -9.920295 +IMU2, 98791, 0.006184489, 0.004034344, -0.003155883, 0.03103495, 0.4298388, -9.896387 +IMU, 98810, -0.001849549, 0.001688175, -0.005514435, 0.1173348, 0.4975675, -9.803239 +IMU2, 98810, 0.007602178, -0.005415097, -0.0005522496, 0.1114187, 0.6195393, -9.823197 +IMU, 98831, 0.004957691, -0.002996415, 0.007559051, -0.01948197, 0.4632936, -9.826325 +IMU2, 98831, -0.001064543, -0.001518926, 0.008896465, -0.01603591, 0.6119761, -9.778654 +GPS, 3, 56679000, 1777, 8, 3.37, 14.1105902, 100.6191362, -0.10, 1.10, 0.22, 292.68, 0.38, 98840 +IMU, 98850, 0.003355078, 0.0008944981, -0.0002920718, -0.001666978, 0.3854052, -9.805753 +IMU2, 98850, 0.001225188, 0.006893665, -0.004743301, -0.03003109, 0.4376318, -9.829454 +IMU, 98870, -0.001395177, 0.006928638, -0.00680601, 0.09513403, 0.4021101, -9.784886 +IMU2, 98870, -0.008799881, -0.0012119, -0.004736784, 0.1408952, 0.5779223, -9.82667 +MAG, 98880, -422, 69, 61, -86, 10, 139, 0, 0, 0 +MAG2, 98880, -284, -20, 233, 0, 0, 0, 0, 0, 0 +CTUN, 98891, 0, 0, 0, 0, -0.09999999, -0.13, 0.00, 0.00, 0, 0 +DU32, 7, 262745 +CURR, 98891, 0, 0, 1531, 122, 5260, 13.11946 +ATT, 98891, 0.00, -1.95, 0.00, -0.13, 189.63, 189.63 +RCIN, 98891, 1503, 1504, 1022, 1004, 992, 993, 992, 992 +RCOU, 98891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98891, 0.0007582176, 0.0001759119, 0.003919898, 0.02192493, 0.5130094, -9.76209 +IMU2, 98891, -0.000594914, 0.008633265, 0.00673581, 0.04596877, 0.6458086, -9.684059 +IMU, 98910, 0.008555369, -0.003624283, 0.005532173, -0.07440092, 0.3651247, -9.71688 +IMU2, 98910, 0.004359283, 8.412264E-05, 0.001945632, -0.08466554, 0.4475285, -9.739316 +IMU, 98930, 0.003967337, 0.002802987, -0.007482421, 0.03499746, 0.2843157, -10.0172 +IMU2, 98930, 0.0004496295, 0.006429445, -0.0004790453, 0.01989686, 0.3761941, -10.10451 +IMU, 98951, 0.001468845, 0.002409298, -0.004812721, 0.1132853, 0.4341441, -9.826841 +IMU2, 98951, -0.001936281, -0.0006111367, 0.0003934959, 0.1348132, 0.5237405, -9.805401 +IMU, 98970, 0.004622953, -0.003839754, 0.007918321, 0.008715019, 0.4004187, -9.792552 +IMU2, 98970, -0.002587534, -0.008253757, 0.006423726, 0.006460071, 0.5152876, -9.666934 +MAG, 98980, -425, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 98980, -284, -20, 233, 0, 0, 0, 0, 0, 0 +CTUN, 98990, 0, 0, 0, 0, -0.09999999, -0.14, 0.00, 0.00, 0, 0 +ATT, 98990, 0.00, -1.96, 0.00, -0.11, 189.64, 189.64 +RCIN, 98990, 1503, 1504, 1022, 1006, 992, 992, 993, 992 +RCOU, 98991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 98991, 0.002823375, 0.0009379461, -0.0003324675, 0.04949731, 0.2957243, -9.828997 +IMU2, 98991, -0.007878782, -0.01041816, -0.003543898, 0.06666327, 0.4401557, -9.965231 +IMU, 99010, -0.006845014, 0.006336071, -0.008650813, 0.05625542, 0.3940163, -9.694487 +IMU2, 99010, -0.005324772, 0.009291263, -0.01197883, 0.127128, 0.5852046, -9.573356 +IMU, 99030, -0.001254851, -0.0006983727, 0.003339535, 0.09279501, 0.4992839, -9.690196 +IMU2, 99030, -8.613989E-05, -0.009954861, 0.006634166, 0.09012067, 0.6637303, -9.572134 +GPS, 3, 56679200, 1777, 8, 3.37, 14.11059, 100.6191367, -0.10, 1.13, 0.13, 292.68, 0.33, 99040 +IMU, 99050, 0.00239954, 0.002071165, 0.004800655, 0.01347069, 0.4450917, -9.723887 +IMU2, 99050, 0.006555837, 0.004404078, 0.001593554, 0.02377582, 0.5637532, -9.856186 +IMU, 99070, -0.005351776, 0.001515422, -0.006585394, 0.04992659, 0.2803554, -9.817282 +IMU2, 99070, -0.01850455, 0.004487485, -0.006050464, 0.04005718, 0.4433428, -9.800771 +MAG, 99080, -422, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 99080, -285, -17, 232, 0, 0, 0, 0, 0, 0 +CTUN, 99090, 0, 0, 0, 0, -0.09999999, -0.13, 0.00, 0.00, 0, -1 +ATT, 99090, 0.00, -1.97, 0.00, -0.09, 189.63, 189.63 +RCIN, 99090, 1504, 1504, 1024, 1005, 992, 993, 992, 992 +RCOU, 99090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99090, -9.63416E-05, 0.001650926, -0.001701466, 0.1449208, 0.5528419, -9.797822 +IMU2, 99090, -0.0007034466, -0.004500308, -0.0004629428, 0.1909832, 0.6554512, -9.875119 +IMU, 99110, -0.003362255, -0.003182635, 0.004640077, -0.01777269, 0.4647787, -9.752684 +IMU2, 99110, -0.001863925, -0.008811933, 0.007886627, -0.02990258, 0.5519321, -9.754408 +IMU, 99130, 0.008702792, -0.004961878, -0.002121484, 0.07431321, 0.4226093, -9.719002 +IMU2, 99130, 0.01051491, -0.003723478, -0.002769382, -0.006594419, 0.602603, -9.880643 +IMU, 99150, -0.008680465, 0.005963326, -0.00741408, 0.1217211, 0.4742988, -9.75943 +IMU2, 99150, -0.004978947, 0.003169613, -0.00334933, 0.08567309, 0.6034844, -9.861211 +IMU, 99170, 0.008458879, -0.004114769, 0.005343198, 0.06649118, 0.6219597, -9.743776 +IMU2, 99170, 0.001857642, 0.0003725942, 0.001148826, 0.06172609, 0.7318524, -9.631248 +MAG, 99180, -425, 69, 61, -86, 10, 139, 0, 0, 0 +MAG2, 99180, -283, -21, 235, 0, 0, 0, 0, 0, 0 +CTUN, 99190, 0, 0, 0, 0, -0.09999999, -0.05, 0.00, 0.00, 0, -1 +ATT, 99190, 0.00, -1.95, 0.00, -0.13, 189.64, 189.64 +RCIN, 99190, 1504, 1504, 1024, 1005, 992, 993, 992, 992 +RCOU, 99191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99191, 0.004000498, 0.002428934, 0.006749073, 0.006349742, 0.3556841, -9.832576 +IMU2, 99191, 0.006587151, 0.006650776, 0.006869392, -0.03409779, 0.4536133, -9.862153 +IMU, 99210, -0.0006846357, 0.001479968, -0.006764578, 0.005293265, 0.3401144, -9.939724 +IMU2, 99210, -0.004778543, 0.009303821, -0.005281714, 0.02388203, 0.4510192, -9.887829 +IMU, 99230, -0.0001845267, 0.004595507, 0.002333866, 0.09780604, 0.3910793, -9.820708 +IMU2, 99230, -0.004554002, 0.002061065, 0.003048686, 0.1771108, 0.5121578, -9.749632 +GPS, 3, 56679400, 1777, 8, 3.37, 14.1105893, 100.6191368, -0.10, 1.35, 0.22, 292.68, 0.23, 99240 +IMU, 99250, 0.003334476, -0.002892923, 0.006888689, -0.04541834, 0.4142087, -9.853859 +IMU2, 99250, 0.006754529, 0.002836974, 0.007903526, -0.1248087, 0.5100216, -9.758055 +IMU, 99270, -0.002024414, 0.00222344, -0.004603053, 0.1152605, 0.2584174, -9.71493 +IMU2, 99270, 0.000666447, 0.005235098, -0.00819709, 0.05513453, 0.4329317, -9.850081 +MAG, 99280, -423, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 99280, -284, -18, 232, 0, 0, 0, 0, 0, 0 +CTUN, 99290, 0, 0, 0, 0, -0.09999999, -0.07, 0.00, 0.00, 0, -1 +ATT, 99291, 0.00, -1.94, 0.00, -0.15, 189.64, 189.64 +RCIN, 99291, 1504, 1504, 1022, 1004, 992, 992, 993, 991 +RCOU, 99291, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99291, -0.00616104, 0.003190868, -0.006966989, 0.1198601, 0.4387134, -9.789811 +IMU2, 99291, -0.01131736, -0.005576464, -0.00400815, 0.09095323, 0.5647514, -9.761732 +IMU, 99310, -0.002023088, -0.006048124, 0.006691954, 0.03491504, 0.548535, -9.733667 +IMU2, 99310, -0.005772928, -0.0004382208, 0.008152848, 0.003557682, 0.738906, -9.874132 +IMU, 99330, 0.0006284714, -0.002380557, 0.004656637, -0.03526613, 0.4108614, -9.705063 +IMU2, 99330, 0.003549691, -0.00106922, 0.003264705, -0.03345346, 0.4484293, -9.725747 +IMU, 99351, -0.0001216698, 0.002766773, -0.00804774, 0.07161422, 0.3951331, -9.928395 +IMU2, 99351, -0.008667359, 0.002216541, -0.01340568, 0.06987011, 0.4696201, -9.785876 +IMU, 99370, 0.002014238, -0.001743726, 0.002884142, 0.05659837, 0.509932, -9.889293 +IMU2, 99370, -0.00238096, -0.002869389, 0.007103669, 0.08131909, 0.6008441, -9.804075 +MAG, 99380, -423, 70, 60, -86, 10, 139, 0, 0, 0 +MAG2, 99380, -283, -18, 234, 0, 0, 0, 0, 0, 0 +CTUN, 99390, 0, 0, 0, 0, -0.09999999, -0.09, 0.00, 0.00, 0, -1 +ATT, 99390, 0.00, -1.89, 0.00, -0.19, 189.65, 189.65 +RCIN, 99390, 1504, 1503, 1023, 1004, 992, 992, 992, 992 +RCOU, 99391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99391, 0.006387927, -0.003203865, 0.007428739, -0.05592209, 0.3668689, -9.842304 +IMU2, 99391, 0.006173033, 0.002230071, 0.005166642, -0.09166062, 0.5030746, -9.756334 +IMU, 99410, 0.001028491, 0.004782587, -0.005775472, 0.09308281, 0.2042275, -9.762752 +IMU2, 99410, -0.0171168, -0.0007693358, -0.005663381, 0.04905069, 0.3782403, -9.725251 +GPS, 3, 56679600, 1777, 8, 3.37, 14.1105893, 100.619136, -0.10, 1.56, 0.41, 292.68, 0.11, 99420 +IMU, 99431, -0.005422266, 0.003357582, -0.006210052, 0.1065648, 0.4782923, -9.768845 +IMU2, 99431, 0.003290473, 0.004525709, -0.003927783, 0.1540159, 0.5929251, -9.748516 +IMU, 99450, -0.001470299, -0.0041622, 0.008440807, 0.02421536, 0.5269005, -9.705994 +IMU2, 99450, -0.005181009, -0.007793733, 0.004222427, 0.04359853, 0.7305058, -9.752207 +IMU, 99470, 0.001747627, 0.003297098, 0.0009806172, 0.02155599, 0.3972293, -9.679233 +IMU2, 99470, -0.002813082, 0.002037444, 0.001394284, 0.01877952, 0.530737, -9.680684 +MAG, 99480, -422, 69, 61, -86, 10, 139, 0, 0, 0 +MAG2, 99480, -283, -18, 233, 0, 0, 0, 0, 0, 0 +CTUN, 99490, 0, 0, 0, 0, -0.09999999, -0.17, 0.00, 0.00, 0, -1 +ATT, 99491, 0.00, -1.83, 0.00, -0.17, 189.65, 189.65 +RCIN, 99491, 1503, 1504, 1023, 1004, 992, 992, 992, 992 +RCOU, 99491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99491, -0.00441931, 0.003812339, -0.009922523, 0.1324047, 0.4726726, -9.883744 +IMU2, 99491, -0.005819742, 0.003838863, -0.01030077, 0.1051399, 0.6077168, -9.939369 +IMU, 99510, -6.365217E-05, -0.001647104, 0.006653844, 0.07757685, 0.5219742, -9.817894 +IMU2, 99510, -0.0006923862, 0.006329656, 0.01809245, 0.03778064, 0.6186568, -9.89406 +IMU, 99530, 0.002837893, -0.003954969, 0.008733028, -0.03101945, 0.3577663, -9.843947 +IMU2, 99530, -0.000763271, -0.0002740342, 0.01183747, -0.005691648, 0.4702122, -9.879848 +IMU, 99551, 0.000872096, 0.002573244, -0.00753727, 0.03641149, 0.2435728, -9.814958 +IMU2, 99551, -0.01110152, 0.008656163, -0.009641311, 0.02866268, 0.3756604, -9.795425 +IMU, 99570, -0.008176604, 0.001290023, -0.006067516, 0.09295821, 0.4886034, -9.82099 +IMU2, 99570, -0.009433638, 0.0007967371, -0.0034083, 0.04880893, 0.6444218, -9.876154 +MAG, 99580, -425, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 99580, -284, -17, 232, 0, 0, 0, 0, 0, 0 +CTUN, 99590, 0, 0, 0, 0, -0.11, -0.01, 0.00, 0.00, 0, -1 +ATT, 99590, 0.00, -1.77, 0.00, -0.14, 189.65, 189.65 +RCIN, 99590, 1503, 1504, 1022, 1004, 992, 992, 993, 992 +RCOU, 99591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99591, 0.003168399, -0.004843976, 0.008466155, 0.01869392, 0.5293859, -9.752801 +IMU2, 99591, 0.005017541, -0.002162352, 0.01414546, -0.02080655, 0.6476079, -9.834265 +IMU, 99610, 0.0001141354, 0.004440002, 0.0004820309, 0.009893522, 0.3145996, -9.72324 +IMU2, 99610, -0.0005776305, -0.0001652017, 0.0005070129, -0.1067028, 0.4913424, -9.82855 +IMU, 99631, -0.003119072, 0.002124682, -0.0102851, 0.1361986, 0.4123305, -9.868114 +IMU2, 99631, -0.01539892, 0.001215139, -0.003903178, 0.1176684, 0.4873869, -9.863784 +GPS, 3, 56679800, 1777, 9, 3.00, 14.1105892, 100.6191364, -0.11, 1.64, 0.30, 292.68, 0.07, 99640 +IMU, 99650, -0.00233846, -0.002318311, 0.007296436, 0.09842473, 0.5289965, -9.809088 +IMU2, 99650, 0.001682475, -0.004710078, 0.009854767, 0.1127322, 0.6454133, -9.855017 +IMU, 99670, -0.008441763, -0.002659906, 0.005821141, -0.05424561, 0.3463888, -9.720198 +IMU2, 99670, -0.01587264, -0.002017448, 0.004615176, -0.1561198, 0.4485623, -9.776019 +MAG, 99680, -422, 69, 60, -86, 10, 139, 0, 0, 0 +MAG2, 99680, -284, -19, 234, 0, 0, 0, 0, 0, 0 +CTUN, 99690, 0, 0, 0, 0, -0.09999999, -0.14, 0.00, 0.00, 0, -1 +ATT, 99691, 0.00, -1.74, 0.00, -0.11, 189.66, 189.66 +RCIN, 99691, 1503, 1505, 1024, 1004, 992, 992, 993, 991 +RCOU, 99691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99691, 0.00179467, 0.002258666, -0.009354093, 0.09085455, 0.4275376, -9.791979 +IMU2, 99691, -0.001348823, 0.003790719, -0.007056342, 0.07966256, 0.5707374, -9.697812 +IMU, 99710, -0.005579459, -0.0008292794, -0.003887746, 0.1134638, 0.5248096, -9.824264 +IMU2, 99710, 0.004267879, -0.003230988, 0.0006194916, 0.1034172, 0.5978465, -9.954821 +IMU, 99730, 0.01045288, -0.003393847, 0.009647575, 0.007037565, 0.4848244, -9.744705 +IMU2, 99730, 0.01200656, -0.008731111, 0.007320829, -0.03635609, 0.585927, -9.881698 +IMU, 99750, -0.001895698, 0.003722027, -0.0001289467, -0.009118274, 0.2144258, -9.795908 +IMU2, 99750, -0.005636141, 0.005268741, -0.0003013974, 0.0694288, 0.3961399, -9.856679 +IMU, 99770, -0.001690483, -6.371737E-05, -0.00922798, 0.1200482, 0.4617835, -9.925169 +IMU2, 99770, -0.01616947, 0.004782059, -0.008872852, 0.1471076, 0.6174694, -9.917435 +MAG, 99780, -424, 69, 61, -86, 10, 139, 0, 0, 0 +MAG2, 99780, -283, -19, 232, 0, 0, 0, 0, 0, 0 +CTUN, 99790, 0, 0, 0, 0, -0.11, -0.13, 0.00, 0.00, 0, -1 +ATT, 99790, 0.00, -1.75, 0.00, -0.10, 189.66, 189.66 +RCIN, 99790, 1503, 1504, 1023, 1003, 993, 992, 992, 992 +RCOU, 99791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99791, 0.003766743, -0.0002668276, 0.007942175, 0.009943008, 0.4435855, -9.776484 +IMU2, 99791, 0.001921723, 0.001875058, 0.006849817, -0.005600452, 0.6176859, -9.845956 +IMU, 99810, 0.0003019832, -0.0005800314, 0.002922729, 0.003569886, 0.3038493, -9.820212 +IMU2, 99810, -0.0003082417, 0.00746589, 0.00229156, -0.05661106, 0.4247375, -9.682405 +IMU, 99830, -0.0009104125, 0.005249828, -0.01111909, 0.1301367, 0.3306299, -9.82153 +IMU2, 99830, -0.01039157, 0.003175567, -0.009199141, 0.1532388, 0.4823462, -9.648136 +GPS, 3, 56680000, 1777, 8, 3.37, 14.110589, 100.6191381, -0.11, 1.46, 0.16, 292.68, 0.14, 99840 +IMU, 99851, -0.004400702, -0.0004771277, 0.000275715, 0.05180195, 0.5493466, -9.747105 +IMU2, 99851, -0.01143571, -0.002298098, 0.005300025, 0.09222412, 0.6376193, -9.723732 +IMU, 99870, 0.004721332, -0.003769275, 0.007575646, 0.007873833, 0.4054738, -9.636546 +IMU2, 99870, -0.002089746, -0.003688134, 0.005603625, 0.00451684, 0.5259866, -9.722897 +MAG, 99880, -422, 69, 59, -86, 10, 139, 0, 0, 0 +MAG2, 99880, -283, -19, 232, 0, 0, 0, 0, 0, 0 +PM, 0, 0, 3, 1000, 2639992, 13, 0, 0, 0 +CTUN, 99890, 0, 0, 0, 0, -0.11, -0.06, 0.00, 0.00, 0, -1 +DU32, 7, 262745 +CURR, 99890, 0, 0, 1531, 131, 5312, 13.46396 +ATT, 99890, 0.00, -1.78, 0.00, -0.09, 189.66, 189.66 +RCIN, 99890, 1503, 1504, 1024, 1003, 992, 993, 992, 992 +RCOU, 99891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99891, -0.0005407128, 0.003793683, -0.002825154, 0.03863762, 0.2778402, -9.841671 +IMU2, 99891, -0.006304637, 0.006648956, -0.004171841, -0.0234915, 0.3857838, -9.839526 +IMU, 99910, 0.0002839435, -0.002021179, -0.006154333, 0.09924071, 0.5365158, -9.872346 +IMU2, 99910, 0.003066916, -0.009222001, -0.001923052, 0.09085429, 0.6834072, -10.01367 +IMU, 99930, 0.007834025, -0.003490023, 0.005090807, -0.02450722, 0.4386109, -9.845732 +IMU2, 99930, 0.007838678, -0.001788601, 0.005286873, -0.004460216, 0.5447507, -9.83433 +IMU, 99950, 0.001026822, -0.0005732216, 0.002049084, 0.003953397, 0.3253032, -9.814947 +IMU2, 99950, 0.004390106, -0.007286205, 0.002884285, -0.09962094, 0.4725175, -9.824824 +IMU, 99970, -0.002591895, 0.002240054, -0.007594511, 0.1233448, 0.4110432, -9.723927 +IMU2, 99970, 0.000235064, 0.0006810445, -0.005234629, 0.091645, 0.5498232, -9.807002 +MAG, 99980, -424, 70, 61, -86, 10, 139, 0, 0, 0 +MAG2, 99980, -283, -16, 233, 0, 0, 0, 0, 0, 0 +CTUN, 99990, 0, 0, 0, 0, -0.11, 0.04, 0.00, 0.00, 0, -1 +ATT, 99991, 0.00, -1.83, 0.00, -0.09, 189.66, 189.66 +RCIN, 99991, 1504, 1504, 1024, 1003, 992, 993, 992, 992 +RCOU, 99991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 99991, -0.003177317, -0.001608491, 0.004347101, 0.06286513, 0.5661558, -9.785329 +IMU2, 99991, 0.002658952, 0.004805965, 0.01127636, 0.07239521, 0.6427889, -9.924076 +IMU, 100011, 0.004194031, 0.0001429953, 0.008531148, -0.03088214, 0.3830802, -9.740406 +IMU2, 100011, 0.005808551, 0.000232514, 0.01173777, -0.03003883, 0.4686028, -9.711623 +IMU, 100031, -0.001291392, 0.001761734, -0.005953279, 0.04458472, 0.2759756, -9.80163 +IMU2, 100031, -0.0111605, -0.001515143, -0.003058071, 0.01783001, 0.4304096, -9.782933 +GPS, 3, 56680200, 1777, 8, 3.37, 14.1105886, 100.619139, -0.11, 1.27, 0.17, 292.68, 0.24, 100040 +IMU, 100051, 0.0008018445, -0.001653515, -0.002376257, 0.1042004, 0.4663773, -9.866737 +IMU2, 100051, -0.006505627, -0.00800875, -4.771538E-05, 0.03904605, 0.6094342, -9.765942 +IMU, 100070, 0.007641856, 0.001171038, 0.005972357, -0.0214964, 0.3209479, -9.815849 +IMU2, 100070, -0.001995906, 0.004768234, 0.007815219, -0.09871674, 0.4980431, -9.76078 +MAG, 100080, -423, 68, 60, -86, 10, 139, 0, 0, 0 +MAG2, 100080, -283, -16, 232, 0, 0, 0, 0, 0, 0 +EV, 11 +D32, 9, 18251 +CMD, 1, 0, 16, 0, 0, 0.00, 14.1105685, 100.6192319 +EV, 10 +CTUN, 115391, 0, 0, 0, 0, 0.68, -0.09, 0.00, 0.00, 0, -1 +ATT, 115391, 0.00, 0.09, 0.00, 0.57, 182.49, 182.49 +RCIN, 115391, 1503, 1504, 1015, 2011, 992, 992, 993, 991 +RCOU, 115391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115391, 0.02690804, -0.01455218, -0.05497147, 0.1667195, 0.3931115, -9.793042 +IMU2, 115391, 0.0263056, -0.02078444, -0.05019797, 0.1527848, 0.5016375, -9.800529 +IMU, 115410, 0.03036566, -0.01380969, -0.04499388, 0.1692534, 0.3570677, -9.624863 +IMU2, 115410, 0.03022759, -0.01939039, -0.0475689, 0.1592191, 0.477726, -9.68758 +IMU, 115431, 0.04194621, -0.01591257, -0.03196166, 0.1949993, 0.3057886, -9.636971 +IMU2, 115431, 0.0370039, -0.02730206, -0.03320817, 0.2038536, 0.4546751, -9.562141 +GPS, 3, 56695600, 1777, 10, 1.44, 14.1105676, 100.6192312, 0.66, -1.39, 1.36, 292.68, 0.26, 115440 +IMU, 115450, 0.05943602, -0.02002659, -0.01912385, 0.2339035, 0.3040345, -9.75034 +IMU2, 115450, 0.05916355, -0.02423742, -0.01961913, 0.1897056, 0.4871972, -9.740042 +IMU, 115471, 0.06709114, -0.03165295, -0.0105688, 0.1594438, 0.2799598, -9.724665 +IMU2, 115471, 0.06145966, -0.03705858, -0.01170277, 0.1605941, 0.3937998, -9.680115 +MAG, 115480, -413, 17, 64, -86, 10, 139, 0, 0, 0 +MAG2, 115480, -273, -67, 241, 0, 0, 0, 0, 0, 0 +CTUN, 115490, 0, 0, 0, 0, 0.64, 0.19, 0.00, 0.00, 0, -3 +ATT, 115490, 0.00, 0.38, 0.00, 0.45, 182.35, 182.35 +RCIN, 115490, 1503, 1504, 1015, 2010, 993, 992, 992, 992 +RCOU, 115490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115490, 0.06334537, -0.04203882, -0.006845377, 0.2279209, 0.2027942, -9.75786 +IMU2, 115490, 0.0528127, -0.05422081, -0.01066912, 0.2024636, 0.3245736, -9.760239 +IMU, 115510, 0.04725132, -0.04965584, -0.002633009, 0.2179027, 0.1950002, -9.759245 +IMU2, 115510, 0.0271508, -0.06321153, -0.006081348, 0.2232369, 0.3267967, -9.765306 +IMU, 115530, 0.02960253, -0.06450482, 0.002986668, 0.1930816, 0.2478441, -9.829196 +IMU2, 115530, 0.02461168, -0.0672119, 0.003414482, 0.2287951, 0.4212712, -9.738664 +IMU, 115550, 0.02062048, -0.08677064, 0.01599443, 0.08001745, 0.3870621, -9.900935 +IMU2, 115550, 0.01509798, -0.09373377, 0.01518229, 0.0853107, 0.5500257, -9.893063 +IMU, 115570, 0.02021939, -0.1084567, 0.02616423, -0.05692558, 0.3291879, -9.821019 +IMU2, 115570, 0.02077651, -0.1136564, 0.02239345, -0.1879882, 0.5167003, -9.846665 +MAG, 115580, -414, 15, 65, -86, 10, 139, 0, 0, 0 +MAG2, 115580, -273, -71, 245, 0, 0, 0, 0, 0, 0 +CTUN, 115590, 0, 0, 0, 0, 0.61, 0.06, 0.00, 0.00, 0, -3 +ATT, 115591, 0.00, 0.59, 0.00, 0.02, 182.44, 182.44 +RCIN, 115591, 1503, 1504, 1015, 2011, 992, 992, 993, 992 +RCOU, 115591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115591, 0.007736364, -0.1157989, 0.02784019, 0.09935526, 0.3002955, -9.868073 +IMU2, 115591, 0.002810054, -0.1405549, 0.02340015, -0.01728225, 0.4487035, -9.812546 +IMU, 115611, 0.004328081, -0.1133414, 0.02233808, 0.209344, 0.2492395, -9.91753 +IMU2, 115611, 0.009767517, -0.1181583, 0.01433307, 0.2131573, 0.3339938, -9.919143 +IMU, 115631, 0.01127743, -0.1030415, 0.01553266, 0.03159006, 0.235072, -10.02503 +IMU2, 115631, 0.004213776, -0.1081834, 0.01061667, 0.05504012, 0.3186265, -9.944636 +GPS, 3, 56695800, 1777, 10, 1.44, 14.1105676, 100.6192309, 0.60, -1.24, 1.35, 292.68, 0.14, 115640 +IMU, 115651, 0.01335111, -0.1034502, 0.0003944493, -0.06040041, 0.2295935, -9.880753 +IMU2, 115651, 0.008094121, -0.1117278, -0.008961888, -0.06342459, 0.3385991, -9.872526 +IMU, 115671, 0.007724741, -0.1071697, -0.01731027, 0.02564165, 0.1759006, -9.867425 +IMU2, 115671, 0.0001417696, -0.1145198, -0.02363271, -0.01923287, 0.3253454, -9.903049 +MAG, 115680, -410, 17, 67, -86, 10, 139, 0, 0, 0 +MAG2, 115680, -270, -67, 243, 0, 0, 0, 0, 0, 0 +CTUN, 115690, 0, 0, 0, 0, 0.58, 0.09, 0.00, 0.00, 0, -2 +ATT, 115690, 0.00, 0.68, 0.00, -0.55, 182.48, 182.48 +RCIN, 115690, 1502, 1504, 1016, 2009, 992, 993, 992, 992 +RCOU, 115690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115690, 0.01224511, -0.1116434, -0.01063881, -0.01657945, 0.3684975, -9.790956 +IMU2, 115690, 0.01125038, -0.123853, -0.008393773, 0.005031228, 0.5344663, -9.72822 +IMU, 115710, 0.02943747, -0.1137598, -0.001305062, -0.175747, 0.341751, -9.827951 +IMU2, 115710, 0.02614116, -0.1287145, 0.002503884, -0.176473, 0.5046936, -9.785298 +IMU, 115730, 0.04014501, -0.1147434, 0.006589631, -0.220872, 0.3451048, -9.885088 +IMU2, 115730, 0.04297461, -0.1216449, 7.071579E-05, -0.2533998, 0.4610878, -9.859377 +IMU, 115750, 0.04954944, -0.1114918, 0.01517949, -0.1241176, 0.3355871, -9.848474 +IMU2, 115750, 0.05198195, -0.1187758, 0.01404706, -0.09447527, 0.5077688, -9.897835 +IMU, 115771, 0.05865136, -0.1066497, 0.02732355, -0.1169869, 0.2567283, -9.810445 +IMU2, 115771, 0.05865894, -0.118271, 0.0238355, -0.1107857, 0.4245034, -9.744092 +MAG, 115780, -410, 18, 71, -86, 10, 139, 0, 0, 0 +MAG2, 115780, -269, -68, 246, 0, 0, 0, 0, 0, 0 +CTUN, 115790, 0, 0, 0, 0, 0.55, 0.04, 0.00, 0.00, 0, -2 +ATT, 115790, 0.00, 0.95, 0.00, -1.12, 182.59, 182.59 +RCIN, 115790, 1502, 1504, 1019, 1994, 992, 993, 992, 992 +RCOU, 115791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115791, 0.06840818, -0.09893979, 0.03922037, -0.1503436, 0.2416834, -9.806296 +IMU2, 115791, 0.06574005, -0.1068758, 0.03740536, -0.1333612, 0.3761913, -9.756814 +IMU, 115811, 0.05998819, -0.09042607, 0.04710741, -0.279656, 0.2519215, -9.762287 +IMU2, 115811, 0.05353534, -0.09683144, 0.03842175, -0.2949936, 0.3443083, -9.801629 +IMU, 115831, 0.03325316, -0.08750983, 0.0500738, -0.3641734, 0.3094987, -9.750574 +IMU2, 115831, 0.02541475, -0.09674378, 0.04691467, -0.3452589, 0.4979928, -9.816926 +GPS, 3, 56696000, 1777, 10, 1.44, 14.1105669, 100.6192302, 0.54, -1.15, 1.31, 292.68, 0.01, 115840 +IMU, 115850, 0.006272806, -0.08138268, 0.05133354, -0.3082497, 0.3037277, -9.809681 +IMU2, 115850, -0.003047243, -0.08192144, 0.05039652, -0.3815953, 0.4626906, -9.8357 +IMU, 115870, 0.003532192, -0.06328905, 0.05630835, -0.1640976, 0.2143421, -9.817572 +IMU2, 115870, -0.01086139, -0.0641753, 0.05727068, -0.1473631, 0.3718152, -9.841953 +MAG, 115880, -408, 19, 75, -86, 10, 139, 0, 0, 0 +MAG2, 115880, -270, -63, 251, 0, 0, 0, 0, 0, 0 +CTUN, 115890, 0, 0, 0, 0, 0.53, -0.10, 0.00, 0.00, 0, -3 +DU32, 7, 262745 +CURR, 115890, 0, 0, 1534, 173, 5296, 15.94009 +ATT, 115890, 0.00, 1.10, 0.00, -1.53, 182.91, 182.91 +RCIN, 115890, 1503, 1504, 1022, 1907, 993, 992, 992, 992 +RCOU, 115891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115891, 0.02411056, -0.05073525, 0.06618109, -0.1768657, 0.2144334, -9.821573 +IMU2, 115891, 0.01329903, -0.0609922, 0.07018863, -0.1831052, 0.2935958, -9.81319 +IMU, 115910, 0.04401014, -0.04548221, 0.07053198, -0.2657516, 0.2454923, -9.750841 +IMU2, 115910, 0.02802921, -0.05312811, 0.07535889, -0.2884775, 0.3604183, -9.785096 +IMU, 115930, 0.04686096, -0.04403868, 0.0750584, -0.2843723, 0.2100314, -9.680636 +IMU2, 115930, 0.03847486, -0.04548398, 0.07979912, -0.3182583, 0.3320683, -9.658493 +IMU, 115950, 0.04323879, -0.05125578, 0.07301318, -0.2730866, 0.1395936, -9.57781 +IMU2, 115950, 0.0378068, -0.04290136, 0.07902635, -0.2760785, 0.2660916, -9.495477 +IMU, 115970, 0.03547266, -0.06484267, 0.06696816, -0.2291156, 0.1231432, -9.718628 +IMU2, 115970, 0.02701087, -0.06923495, 0.06674493, -0.2553955, 0.2396895, -9.82921 +MAG, 115980, -408, 23, 78, -86, 10, 139, 0, 0, 0 +MAG2, 115980, -267, -62, 255, 0, 0, 0, 0, 0, 0 +CTUN, 115990, 0, 0, 0, 0, 0.49, 0.00, 0.00, 0.00, 0, -4 +ATT, 115991, 0.00, 1.29, 0.00, -1.87, 183.31, 183.31 +RCIN, 115991, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 115991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 115991, 0.03033623, -0.07973009, 0.06093697, -0.2854325, 0.1691675, -9.704501 +IMU2, 115991, 0.02538193, -0.08330084, 0.05508354, -0.345376, 0.2649649, -9.775978 +IMU, 116010, 0.0241315, -0.09326053, 0.05583867, -0.3040803, 0.2318722, -9.88312 +IMU2, 116010, 0.0240815, -0.1113079, 0.04872046, -0.2887886, 0.4071159, -9.81708 +IMU, 116030, 0.02397696, -0.1050379, 0.05262403, -0.2971615, 0.2014783, -9.759925 +IMU2, 116030, 0.01949208, -0.1140253, 0.04300368, -0.3258197, 0.3747357, -9.834929 +IMU, 116051, 0.03092356, -0.1047011, 0.04560102, -0.354841, 0.09736912, -9.630186 +IMU2, 116051, 0.03123454, -0.1081335, 0.03589176, -0.3486666, 0.1904304, -9.667379 +GPS, 3, 56696200, 1777, 10, 1.44, 14.1105671, 100.6192292, 0.47, -1.41, 1.20, 292.68, 0.07, 116060 +IMU, 116070, 0.03384493, -0.09150905, 0.03409164, -0.2884087, 0.02216963, -9.711663 +IMU2, 116070, 0.02617063, -0.09080698, 0.02550149, -0.2916924, 0.1636964, -9.734908 +MAG, 116080, -406, 25, 79, -86, 10, 139, 0, 0, 0 +MAG2, 116080, -267, -59, 257, 0, 0, 0, 0, 0, 0 +CTUN, 116090, 0, 0, 0, 0, 0.46, -0.12, 0.00, 0.00, 0, -5 +ATT, 116090, 0.00, 1.43, 0.00, -2.42, 183.58, 183.58 +RCIN, 116090, 1503, 1504, 1023, 1512, 992, 993, 992, 992 +RCOU, 116091, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116091, 0.03505609, -0.0771466, 0.02277755, -0.332266, 0.03265695, -9.828631 +IMU2, 116091, 0.0299151, -0.08061966, 0.01332434, -0.4229044, 0.2131151, -9.750269 +IMU, 116111, 0.0360851, -0.07552053, 0.01191106, -0.4048513, 0.1529027, -9.80523 +IMU2, 116111, 0.02406125, -0.08251381, 0.009330388, -0.3920845, 0.2629697, -9.709765 +IMU, 116130, 0.03850688, -0.09012641, 0.00431654, -0.4914058, 0.2293433, -9.714173 +IMU2, 116130, 0.03655974, -0.09598343, -0.00129008, -0.5076028, 0.3106682, -9.712324 +IMU, 116150, 0.04217252, -0.1000528, -0.004469417, -0.5546361, 0.1178601, -9.66655 +IMU2, 116150, 0.03966861, -0.09987855, -0.01094393, -0.6123786, 0.2993754, -9.77423 +IMU, 116171, 0.04223485, -0.1012614, -0.01593897, -0.5597661, 0.07629171, -9.819757 +IMU2, 116171, 0.04195588, -0.1072763, -0.02371536, -0.5474951, 0.2281997, -9.80346 +MAG, 116180, -406, 28, 83, -86, 10, 139, 0, 0, 0 +MAG2, 116180, -267, -58, 260, 0, 0, 0, 0, 0, 0 +CTUN, 116190, 0, 0, 0, 0, 0.42, 0.09, 0.00, 0.00, 0, -6 +ATT, 116191, 0.00, 1.63, 0.00, -2.88, 183.56, 183.56 +RCIN, 116191, 1503, 1504, 1024, 1512, 993, 992, 992, 992 +RCOU, 116191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116191, 0.04628224, -0.09756964, -0.03011232, -0.5976271, 0.07910591, -9.872504 +IMU2, 116191, 0.046953, -0.1098479, -0.02669201, -0.6470818, 0.2212896, -9.823536 +IMU, 116210, 0.04842381, -0.08451848, -0.04143876, -0.6104528, 0.02729033, -9.860401 +IMU2, 116210, 0.04333009, -0.08978164, -0.04500625, -0.6017625, 0.2101228, -9.83567 +IMU, 116230, 0.05971505, -0.0668439, -0.04794986, -0.6046584, 0.08492178, -9.711192 +IMU2, 116230, 0.05429805, -0.06939015, -0.04589346, -0.6693056, 0.191914, -9.740698 +GPS, 3, 56696400, 1777, 10, 1.44, 14.1105681, 100.6192302, 0.41, -1.46, 0.88, 292.68, 0, 116240 +IMU, 116251, 0.06395472, -0.0471021, -0.0552394, -0.7058128, 0.0850641, -9.778576 +IMU2, 116251, 0.05617969, -0.05316672, -0.05896766, -0.7467968, 0.2244179, -9.740659 +IMU, 116270, 0.05631832, -0.03044459, -0.06372896, -0.6750425, 0.01044628, -9.805564 +IMU2, 116270, 0.03769498, -0.03604573, -0.06429363, -0.6864195, 0.1665852, -9.747357 +MAG, 116281, -402, 27, 86, -86, 10, 139, 0, 0, 0 +MAG2, 116281, -266, -57, 263, 0, 0, 0, 0, 0, 0 +CTUN, 116290, 0, 0, 0, 0, 0.4, -0.12, 0.00, 0.00, 0, -6 +ATT, 116290, 0.00, 1.90, 0.00, -3.11, 183.26, 183.26 +RCIN, 116290, 1503, 1504, 1024, 1512, 993, 993, 992, 992 +RCOU, 116290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116290, 0.06712219, -0.0201014, -0.07138287, -0.6187585, -0.01975518, -9.940761 +IMU2, 116290, 0.06383781, -0.01735736, -0.06912898, -0.6780776, 0.1351814, -9.968992 +IMU, 116310, 0.07592814, -0.01195259, -0.07489975, -0.6655945, 0.02573255, -9.821389 +IMU2, 116310, 0.07260013, -0.02075817, -0.07114484, -0.6845127, 0.164807, -9.958166 +IMU, 116330, 0.07914601, -0.005651806, -0.07397985, -0.726751, 0.1554224, -9.868339 +IMU2, 116330, 0.08203789, -0.005736005, -0.06980728, -0.774883, 0.342967, -9.911212 +IMU, 116350, 0.08502454, 0.001789898, -0.06952904, -0.7714886, 0.03164326, -9.858279 +IMU2, 116350, 0.09484642, -0.003370704, -0.06518656, -0.7723172, 0.164103, -9.853385 +IMU, 116371, 0.07856411, 0.01526326, -0.06937611, -0.8605814, -0.1235069, -9.870687 +IMU2, 116371, 0.06614043, 0.01216324, -0.06469724, -0.8309932, 0.03072, -9.778282 +MAG, 116380, -404, 25, 87, -86, 10, 139, 0, 0, 0 +MAG2, 116380, -265, -59, 264, 0, 0, 0, 0, 0, 0 +CTUN, 116390, 0, 0, 0, 0, 0.37, -0.09, 0.00, 0.00, 0, -6 +ATT, 116390, 0.00, 2.25, 0.00, -3.01, 182.86, 182.86 +RCIN, 116390, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 116391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116391, 0.08701456, 0.02162955, -0.06933358, -0.8819101, -0.1355979, -9.767688 +IMU2, 116391, 0.09146942, 0.01703206, -0.06624062, -0.8551226, -0.02709711, -9.648767 +IMU, 116410, 0.06948835, 0.04204944, -0.06833901, -0.9332362, -0.09635898, -9.917822 +IMU2, 116410, 0.06776123, 0.04445623, -0.06465599, -1.010648, 0.1072036, -9.829921 +IMU, 116430, 0.04979735, 0.07218318, -0.07517684, -0.852758, -0.2370566, -10.01067 +IMU2, 116430, 0.03605238, 0.07879896, -0.07444216, -0.9203621, -0.06701124, -10.06 +IMU, 116451, 0.02246658, 0.111619, -0.08984154, -0.7516978, -0.4509764, -9.950024 +IMU2, 116451, 0.01396038, 0.1058795, -0.08207822, -0.8249428, -0.3212789, -9.953943 +GPS, 3, 56696600, 1777, 10, 1.44, 14.1105687, 100.6192319, 0.34, -1.29, 0.63, 292.68, -0.16, 116460 +IMU, 116470, -0.004609438, 0.125141, -0.102388, -0.5422509, -0.3510333, -9.80039 +IMU2, 116470, -0.004893348, 0.1192378, -0.09682731, -0.5417066, -0.2195796, -9.76455 +MAG, 116480, -405, 23, 86, -86, 10, 139, 0, 0, 0 +MAG2, 116480, -265, -59, 262, 0, 0, 0, 0, 0, 0 +CTUN, 116490, 0, 0, 0, 0, 0.34, 0.01, 0.00, 0.00, 0, -5 +ATT, 116490, 0.00, 2.33, 0.00, -2.43, 182.39, 182.39 +RCIN, 116490, 1503, 1504, 1023, 1513, 992, 992, 992, 992 +RCOU, 116490, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116490, -0.01347781, 0.1091938, -0.103817, -0.4665349, -0.20182, -9.69292 +IMU2, 116490, -0.01047758, 0.1032592, -0.09711953, -0.443479, -0.07663119, -9.576138 +IMU, 116511, -0.03403082, 0.08333059, -0.09744696, -0.5780783, -0.1298074, -9.685418 +IMU2, 116511, -0.03307624, 0.0801027, -0.09453752, -0.539325, -0.02440369, -9.69243 +IMU, 116530, -0.06599847, 0.05914425, -0.09542148, -0.5157356, -0.2195051, -9.881344 +IMU2, 116530, -0.0770462, 0.05061404, -0.08600509, -0.541532, -0.03935122, -9.894301 +IMU, 116550, -0.08870151, 0.03116141, -0.09328078, -0.4235162, -0.2096688, -9.836433 +IMU2, 116550, -0.0833391, 0.02725226, -0.08574948, -0.4593824, 0.03064024, -9.788182 +IMU, 116570, -0.096164, -0.002040818, -0.08568002, -0.3119761, -0.08562025, -9.68532 +IMU2, 116570, -0.1092465, -0.00266319, -0.0791999, -0.4396606, 0.06865704, -9.658781 +MAG, 116580, -406, 18, 83, -86, 10, 139, 0, 0, 0 +MAG2, 116580, -268, -65, 260, 0, 0, 0, 0, 0, 0 +CTUN, 116590, 0, 0, 0, 0, 0.31, -0.05, 0.00, 0.00, 0, -6 +ATT, 116590, 0.00, 1.84, 0.00, -2.21, 181.88, 181.88 +RCIN, 116590, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 116591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116591, -0.1071032, -0.01345348, -0.06861033, -0.4059207, -0.05883446, -9.669391 +IMU2, 116591, -0.107173, -0.01366816, -0.06707998, -0.3595338, 0.04959154, -9.666223 +IMU, 116610, -0.1090406, -0.02747566, -0.05475406, -0.5654252, 0.05509323, -9.788559 +IMU2, 116610, -0.1055493, -0.02663721, -0.04579759, -0.5877437, 0.244916, -9.749816 +IMU, 116630, -0.08234814, -0.04455535, -0.03988758, -0.6378797, -0.03695497, -9.815259 +IMU2, 116630, -0.08135263, -0.0463939, -0.03822169, -0.5386238, 0.09451222, -9.892529 +GPS, 3, 56696800, 1777, 10, 1.44, 14.1105702, 100.619232, 0.30, -0.96, 0.84, 292.68, -0.36, 116640 +IMU, 116651, -0.0563247, -0.04454555, -0.02305163, -0.3440128, -0.06335875, -10.10552 +IMU2, 116651, -0.06422588, -0.04504533, -0.02280359, -0.3435614, 0.09004176, -10.19637 +IMU, 116671, -0.05030577, -0.006285828, -0.006163771, -0.3445104, -0.04347193, -10.26189 +IMU2, 116671, -0.0525053, -0.003709464, -0.004537581, -0.359704, 0.06175077, -10.27447 +MAG, 116681, -406, 15, 83, -86, 10, 139, 0, 0, 0 +MAG2, 116681, -268, -68, 261, 0, 0, 0, 0, 0, 0 +CTUN, 116690, 0, 0, 0, 0, 0.29, -0.04, 0.00, 0.00, 0, -5 +ATT, 116691, 0.00, 1.38, 0.00, -2.32, 181.74, 181.74 +RCIN, 116691, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 116691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116691, -0.06117756, 0.03668883, 0.00650034, -0.543448, 0.05305412, -10.0393 +IMU2, 116691, -0.05320524, 0.04066825, 0.01006226, -0.602885, 0.1776534, -9.960754 +IMU, 116711, -0.07262829, 0.05894051, 0.01284601, -0.650125, -0.02592421, -9.915814 +IMU2, 116711, -0.07299113, 0.06282394, 0.01980509, -0.6274688, 0.07450056, -9.960472 +IMU, 116730, -0.08518613, 0.06469356, 0.01800328, -0.4571621, 0.007672787, -9.832757 +IMU2, 116730, -0.08960433, 0.06537877, 0.02128005, -0.5070043, 0.1863035, -9.765821 +IMU, 116750, -0.08223957, 0.06947086, 0.03526187, -0.4377394, 0.0788614, -9.744729 +IMU2, 116750, -0.07678399, 0.06875437, 0.0427129, -0.3820567, 0.2184068, -9.710426 +IMU, 116771, -0.07207753, 0.08875547, 0.05145389, -0.3542717, 0.0396266, -9.872977 +IMU2, 116771, -0.07523662, 0.08718221, 0.05650371, -0.3334617, 0.1924216, -9.919302 +MAG, 116780, -406, 14, 82, -86, 10, 139, 0, 0, 0 +MAG2, 116780, -267, -71, 260, 0, 0, 0, 0, 0, 0 +CTUN, 116790, 0, 0, 0, 0, 0.27, -0.14, 0.00, 0.00, 0, -5 +ATT, 116791, 0.00, 0.97, 0.00, -1.84, 181.92, 181.92 +RCIN, 116791, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 116791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116791, -0.05802776, 0.1044076, 0.0564643, -0.4995188, -0.01239198, -9.912688 +IMU2, 116791, -0.06068019, 0.09948125, 0.07097063, -0.5626667, 0.1505718, -9.934712 +IMU, 116810, -0.05366028, 0.1030445, 0.05985322, -0.4364357, 0.1881879, -9.651985 +IMU2, 116810, -0.04626532, 0.09169893, 0.06812935, -0.4710171, 0.3187633, -9.596663 +IMU, 116830, -0.04946787, 0.0934643, 0.07676983, -0.3772928, 0.2839409, -9.707454 +IMU2, 116830, -0.0469239, 0.09125239, 0.09106331, -0.436758, 0.471529, -9.751163 +IMU, 116850, -0.04281236, 0.09430249, 0.09509605, -0.2947295, 0.2449124, -9.871351 +IMU2, 116850, -0.03837687, 0.09159642, 0.110699, -0.3152012, 0.3713228, -9.90888 +GPS, 3, 56697000, 1777, 10, 1.44, 14.1105716, 100.6192317, 0.24, -0.56, 1.00, 292.68, -0.51, 116860 +IMU, 116871, -0.0342041, 0.0916924, 0.1041852, -0.4121078, 0.2139892, -9.864397 +IMU2, 116871, -0.03937078, 0.09378269, 0.1134256, -0.4448359, 0.4157795, -9.82269 +MAG, 116880, -408, 15, 80, -86, 10, 139, 0, 0, 0 +MAG2, 116880, -269, -68, 255, 0, 0, 0, 0, 0, 0 +CTUN, 116890, 0, 0, 0, 0, 0.24, -0.16, 0.00, 0.00, 0, -5 +DU32, 7, 262745 +CURR, 116890, 0, 0, 1524, 131, 5302, 16.29026 +ATT, 116890, 0.00, 0.74, 0.00, -1.25, 182.41, 182.41 +RCIN, 116890, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 116891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116891, -0.02695091, 0.07611218, 0.1091999, -0.3406712, 0.2446236, -9.643405 +IMU2, 116891, -0.03016887, 0.06929269, 0.1203969, -0.3627322, 0.3883885, -9.61189 +IMU, 116910, -0.01434217, 0.05738731, 0.1194864, -0.3266249, 0.2652216, -9.729502 +IMU2, 116910, -0.0133842, 0.06569894, 0.1272651, -0.3535087, 0.4329015, -9.715868 +IMU, 116930, -0.01309804, 0.0707515, 0.1227214, -0.2762843, 0.1588566, -9.750234 +IMU2, 116930, -0.01543277, 0.07907437, 0.1304825, -0.3183284, 0.3178951, -9.795519 +IMU, 116950, -0.01640927, 0.1042213, 0.1144351, -0.3016173, 0.03998028, -9.931955 +IMU2, 116950, -0.02493755, 0.1063093, 0.1262649, -0.2358489, 0.2238026, -9.861126 +IMU, 116971, -0.02545351, 0.1188257, 0.1025549, -0.1878571, 0.1575403, -9.743476 +IMU2, 116971, -0.02618165, 0.1146114, 0.112643, -0.2094291, 0.3490102, -9.736527 +MAG, 116980, -408, 19, 76, -86, 10, 139, 0, 0, 0 +MAG2, 116980, -269, -64, 254, 0, 0, 0, 0, 0, 0 +CTUN, 116990, 0, 0, 0, 0, 0.21, -0.04, 0.00, 0.00, 0, -6 +ATT, 116990, 0.00, 0.66, 0.00, -0.70, 183.04, 183.04 +RCIN, 116990, 1503, 1504, 1024, 1512, 992, 993, 992, 992 +RCOU, 116991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 116991, -0.02093845, 0.1110106, 0.1006892, -0.1417458, 0.1167948, -9.753437 +IMU2, 116991, -0.02919092, 0.1062185, 0.1100556, -0.1229028, 0.2822288, -9.79158 +IMU, 117010, -0.0257157, 0.1029518, 0.09176763, -0.06620391, 0.1070635, -9.665768 +IMU2, 117010, -0.02339575, 0.1083495, 0.1058979, -0.06645977, 0.2372344, -9.722922 +IMU, 117030, -0.03550876, 0.09912993, 0.07546505, -0.1225603, -0.04738632, -9.780321 +IMU2, 117030, -0.03614217, 0.1049322, 0.08065376, -0.1870347, 0.104303, -9.80204 +IMU, 117050, -0.06081738, 0.09330483, 0.05491823, -0.1062876, 0.09384881, -9.775389 +IMU2, 117050, -0.06459036, 0.08321033, 0.05372472, -0.1441851, 0.2619226, -9.753411 +GPS, 3, 56697200, 1777, 10, 1.44, 14.1105714, 100.619232, 0.20, -0.15, 0.93, 292.68, -0.55, 117060 +IMU, 117071, -0.07585202, 0.07928058, 0.04290515, -0.2037199, 0.2513373, -9.72442 +IMU2, 117071, -0.07456967, 0.07071021, 0.04139363, -0.2397164, 0.3643205, -9.754216 +MAG, 117081, -408, 23, 73, -86, 10, 139, 0, 0, 0 +MAG2, 117081, -271, -62, 250, 0, 0, 0, 0, 0, 0 +CTUN, 117090, 0, 0, 0, 0, 0.19, -0.13, 0.00, 0.00, 0, -7 +ATT, 117090, 0.00, 0.40, 0.00, -0.18, 183.38, 183.38 +RCIN, 117090, 1503, 1504, 1025, 1513, 992, 992, 993, 991 +RCOU, 117090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117090, -0.08245774, 0.06120326, 0.03091223, -0.07824671, 0.2154339, -9.732973 +IMU2, 117090, -0.077682, 0.05447542, 0.03007675, -0.07493126, 0.3640894, -9.8044 +IMU, 117110, -0.06949358, 0.03955791, 0.01619016, -0.001769438, 0.1013711, -9.759501 +IMU2, 117110, -0.06495633, 0.04055288, 0.01607258, -0.1285, 0.2579626, -9.801716 +IMU, 117130, -0.05243329, 0.008609209, 0.0062338, 0.02395079, 0.2446147, -9.723518 +IMU2, 117130, -0.05096428, 0.004686844, 0.005570011, -0.06389534, 0.3904901, -9.760997 +IMU, 117150, -0.03837316, -0.01392576, 0.003893062, -0.03728826, 0.4036737, -9.846715 +IMU2, 117150, -0.03966792, -0.01422605, 0.006073729, -0.1541001, 0.528348, -9.810584 +IMU, 117171, -0.04176461, -0.01626013, -0.003576415, -0.04082234, 0.3147911, -9.901887 +IMU2, 117171, -0.04732361, -0.01337431, -0.007055567, -0.06004298, 0.3945162, -9.906599 +MAG, 117180, -410, 23, 71, -86, 10, 139, 0, 0, 0 +MAG2, 117180, -271, -61, 249, 0, 0, 0, 0, 0, 0 +CTUN, 117190, 0, 0, 0, 0, 0.17, -0.24, 0.00, 0.00, 0, -7 +ATT, 117190, 0.00, 0.13, 0.00, -0.23, 183.40, 183.40 +RCIN, 117190, 1503, 1504, 1024, 1511, 993, 992, 992, 992 +RCOU, 117191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117191, -0.04444544, -0.01436562, -0.0182518, -0.008383885, 0.2632056, -9.895354 +IMU2, 117191, -0.04230009, -0.01239261, -0.02424458, -0.003419638, 0.374398, -9.926292 +IMU, 117211, -0.03847518, -0.02567658, -0.02942085, 0.02129512, 0.41841, -9.815163 +IMU2, 117211, -0.04607527, -0.02564985, -0.03219263, -0.02982008, 0.5480752, -9.776895 +IMU, 117231, -0.02501072, -0.03528861, -0.03424976, -0.08809042, 0.4505571, -9.760715 +IMU2, 117231, -0.03685334, -0.03513128, -0.03703337, -0.1049894, 0.5490811, -9.800944 +IMU, 117251, -0.02263357, -0.02767121, -0.0468214, -0.1422769, 0.329169, -9.805989 +IMU2, 117251, -0.02929503, -0.0247331, -0.04455423, -0.1879686, 0.47364, -9.897201 +GPS, 3, 56697400, 1777, 10, 1.44, 14.1105721, 100.6192328, 0.14, 0.14, 0.99, 292.68, -0.52, 117260 +IMU, 117271, -0.02356184, -0.005963281, -0.06032375, -0.02368349, 0.224813, -9.884753 +IMU2, 117271, -0.01645371, 0.00118289, -0.06123804, -0.04820538, 0.4171413, -9.909933 +MAG, 117280, -409, 22, 72, -86, 10, 139, 0, 0, 0 +MAG2, 117280, -272, -61, 248, 0, 0, 0, 0, 0, 0 +CTUN, 117290, 0, 0, 0, 0, 0.14, -0.10, 0.00, 0.00, 0, -7 +ATT, 117290, 0.00, 0.00, 0.00, -0.39, 183.15, 183.15 +RCIN, 117290, 1503, 1504, 1025, 1512, 992, 992, 993, 992 +RCOU, 117290, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117291, -0.02493996, 0.01365298, -0.06464987, -0.04588169, 0.361598, -9.82 +IMU2, 117291, -0.02128894, 0.01799068, -0.0635044, -0.0570991, 0.5218568, -9.854136 +IMU, 117311, -0.03093101, 0.02795317, -0.06750774, -0.1423792, 0.3492673, -9.68103 +IMU2, 117311, -0.03875658, 0.02796199, -0.05711748, -0.1500553, 0.510486, -9.79527 +IMU, 117330, -0.03742039, 0.03270713, -0.07609621, -0.1582019, 0.2427923, -9.636387 +IMU2, 117330, -0.04349362, 0.03353019, -0.07234497, -0.1628351, 0.2957759, -9.622797 +IMU, 117350, -0.04010361, 0.02393949, -0.07363725, 0.00632365, 0.3051108, -9.549396 +IMU2, 117350, -0.03779893, 0.02018358, -0.06983713, 0.01528013, 0.4368175, -9.497549 +IMU, 117371, -0.02779602, 0.001423478, -0.06422334, -0.04362363, 0.4100886, -9.611665 +IMU2, 117371, -0.02470981, -0.002311596, -0.05916747, -0.07266819, 0.5682677, -9.693636 +MAG, 117380, -410, 20, 72, -86, 10, 139, 0, 0, 0 +MAG2, 117380, -270, -64, 251, 0, 0, 0, 0, 0, 0 +CTUN, 117390, 0, 0, 0, 0, 0.12, -0.01, 0.00, 0.00, 0, -9 +ATT, 117390, 0.00, -0.20, 0.00, -0.28, 182.77, 182.77 +RCIN, 117390, 1503, 1504, 1025, 1512, 993, 992, 992, 992 +RCOU, 117391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117391, -0.03044801, -0.0205385, -0.05664979, -0.09295537, 0.3488954, -9.631238 +IMU2, 117391, -0.03100515, -0.03516607, -0.05334138, -0.06521249, 0.4654833, -9.675624 +IMU, 117410, -0.03626223, -0.03761911, -0.05869341, -0.08681607, 0.2718317, -9.708946 +IMU2, 117410, -0.05260962, -0.03969115, -0.05505452, -0.1258281, 0.4046412, -9.733184 +IMU, 117430, -0.03935701, -0.05270894, -0.05333196, 0.07218814, 0.4169963, -9.787305 +IMU2, 117430, -0.04046997, -0.0552492, -0.05286962, 0.04627514, 0.5390579, -9.819648 +IMU, 117450, -0.02746166, -0.06376126, -0.04058257, 0.01716058, 0.523329, -9.936768 +IMU2, 117450, -0.03743423, -0.07036601, -0.03703359, 0.0183121, 0.6564106, -9.951926 +GPS, 3, 56697600, 1777, 10, 1.44, 14.110574, 100.6192315, 0.10, 0.14, 1.22, 292.68, -0.46, 117460 +IMU, 117470, -0.02058432, -0.07049303, -0.03385177, 0.02512094, 0.4312539, -9.94559 +IMU2, 117470, -0.03156573, -0.07735404, -0.03446482, 0.01284862, 0.6263483, -9.903705 +MAG, 117481, -408, 18, 73, -86, 10, 139, 0, 0, 0 +MAG2, 117481, -271, -66, 248, 0, 0, 0, 0, 0, 0 +CTUN, 117490, 0, 0, 0, 0, 0.09999999, -0.05, 0.00, 0.00, 0, -9 +ATT, 117490, 0.00, -0.38, 0.00, -0.58, 182.53, 182.53 +RCIN, 117490, 1503, 1504, 1025, 1512, 993, 992, 992, 992 +RCOU, 117491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117491, -0.02264452, -0.07839122, -0.03142375, 0.05089399, 0.5229556, -9.960092 +IMU2, 117491, -0.02769973, -0.07745758, -0.03152798, 0.04543781, 0.7115234, -9.954218 +IMU, 117510, -0.02210565, -0.09269018, -0.02164523, 0.1214809, 0.6793487, -9.778975 +IMU2, 117510, -0.02390922, -0.1015965, -0.01652577, 0.1481426, 0.8103355, -9.887909 +IMU, 117530, 0.0005943254, -0.1003717, -0.00683379, -0.009554386, 0.6045391, -9.820844 +IMU2, 117530, -0.001240583, -0.1024401, -0.0048008, 0.04152524, 0.6877049, -9.811231 +IMU, 117550, 0.01056843, -0.1073745, -0.002467008, -0.06604236, 0.533691, -9.798155 +IMU2, 117550, 0.02238047, -0.1106995, -0.002622208, -0.05014098, 0.6802157, -9.833942 +IMU, 117570, 0.02856555, -0.1178884, 0.000299623, -0.1483808, 0.5149733, -9.672022 +IMU2, 117570, 0.02410585, -0.1273649, 0.0001236429, -0.1095437, 0.5863967, -9.59309 +MAG, 117580, -409, 14, 75, -86, 10, 139, 0, 0, 0 +MAG2, 117580, -270, -68, 250, 0, 0, 0, 0, 0, 0 +CTUN, 117590, 0, 0, 0, 0, 0.08, 0.00, 0.00, 0.00, 0, -9 +ATT, 117591, 0.00, -0.29, 0.00, -1.14, 182.52, 182.52 +RCIN, 117591, 1503, 1504, 1025, 1511, 993, 992, 992, 992 +RCOU, 117591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117591, 0.03967092, -0.1279338, 0.007591167, -0.2090134, 0.585847, -9.669685 +IMU2, 117591, 0.04701026, -0.1345015, 0.008049215, -0.1731597, 0.755468, -9.678996 +IMU, 117610, 0.05001412, -0.1235296, 0.01072866, -0.3784581, 0.4415379, -9.742291 +IMU2, 117610, 0.05751882, -0.1300466, 0.004772284, -0.3945971, 0.5641981, -9.74796 +IMU, 117631, 0.047542, -0.1210654, 0.00910164, -0.3647814, 0.3532028, -9.814203 +IMU2, 117631, 0.05479926, -0.1242523, 0.007867985, -0.364907, 0.5060414, -9.871842 +IMU, 117650, 0.04520031, -0.112832, 0.01363218, -0.4109563, 0.4183363, -9.727365 +IMU2, 117650, 0.04264569, -0.1233033, 0.009399571, -0.3815548, 0.6098298, -9.794961 +GPS, 3, 56697800, 1777, 10, 1.44, 14.1105752, 100.619231, 0.07, 0.36, 1.23, 292.68, -0.47, 117660 +IMU, 117671, 0.04848558, -0.1018538, 0.01825734, -0.46978, 0.4374076, -9.763465 +IMU2, 117671, 0.05266003, -0.1111677, 0.01386907, -0.488475, 0.5722555, -9.805814 +MAG, 117680, -407, 15, 80, -86, 10, 139, 0, 0, 0 +MAG2, 117680, -270, -67, 254, 0, 0, 0, 0, 0, 0 +CTUN, 117690, 0, 0, 0, 0, 0.07, -0.01, 0.00, 0.00, 0, -9 +ATT, 117690, 0.00, 0.00, 0.00, -1.72, 182.63, 182.63 +RCIN, 117690, 1502, 1504, 1026, 1512, 992, 993, 992, 992 +RCOU, 117691, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117691, 0.04586201, -0.07763086, 0.01461237, -0.4116467, 0.2163721, -9.684008 +IMU2, 117691, 0.03854356, -0.08418664, 0.005680665, -0.4002373, 0.3369629, -9.619946 +IMU, 117710, 0.03949074, -0.06054238, 0.01092196, -0.3927801, 0.2073742, -9.691479 +IMU2, 117710, 0.02685307, -0.06264491, 0.01239502, -0.3974991, 0.3229737, -9.693765 +IMU, 117730, 0.03868091, -0.045282, 0.01027444, -0.3842472, 0.2334592, -9.65008 +IMU2, 117730, 0.02322498, -0.04372466, 0.00137263, -0.4190927, 0.3774804, -9.71194 +IMU, 117750, 0.03173429, -0.03400413, 0.00252969, -0.5062115, 0.1769472, -9.75001 +IMU2, 117750, 0.0262577, -0.03171613, -0.004278515, -0.5575434, 0.2892452, -9.760246 +IMU, 117771, 0.007650571, -0.03141832, -0.01141114, -0.5056998, 0.1443598, -9.6745 +IMU2, 117771, -0.008236153, -0.03804246, -0.01047271, -0.5124002, 0.3361536, -9.655693 +MAG, 117780, -406, 17, 83, -86, 10, 139, 0, 0, 0 +MAG2, 117780, -268, -66, 258, 0, 0, 0, 0, 0, 0 +CTUN, 117790, 0, 0, 0, 0, 0.05, -0.05, 0.00, 0.00, 0, -10 +ATT, 117791, 0.00, 0.14, 0.00, -1.98, 182.64, 182.64 +RCIN, 117791, 1504, 1504, 1025, 1511, 993, 992, 992, 992 +RCOU, 117791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117791, -0.01221393, -0.03778698, -0.01663449, -0.4687413, 0.2763363, -9.791633 +IMU2, 117791, -0.02947382, -0.0414579, -0.01532654, -0.5138789, 0.4580209, -9.885198 +IMU, 117810, -0.01315474, -0.04368081, -0.01454571, -0.470436, 0.3120265, -9.782681 +IMU2, 117810, -0.03155909, -0.04482481, -0.01540106, -0.4072, 0.535846, -9.864117 +IMU, 117830, -0.01323279, -0.03846147, -0.02052666, -0.4370447, 0.1749167, -9.918552 +IMU2, 117830, -0.02826628, -0.04916193, -0.01930139, -0.4267719, 0.3077537, -9.989121 +GPS, 3, 56698000, 1777, 10, 1.44, 14.1105766, 100.6192317, 0.04, 0.35, 1.02, 292.68, -0.49, 117840 +IMU, 117851, -0.01688864, -0.03492314, -0.02422944, -0.3787388, 0.2633567, -9.904424 +IMU2, 117851, -0.03070118, -0.03826906, -0.02547097, -0.4119968, 0.3679384, -9.884615 +IMU, 117870, -0.0181188, -0.03744674, -0.02062927, -0.408254, 0.4526689, -9.879974 +IMU2, 117870, -0.02681179, -0.04290065, -0.01912717, -0.3733532, 0.6299162, -9.895722 +MAG, 117881, -404, 16, 84, -86, 10, 139, 0, 0, 0 +MAG2, 117881, -267, -67, 257, 0, 0, 0, 0, 0, 0 +CTUN, 117890, 0, 0, 0, 0, 0.04, -0.02, 0.00, 0.00, 0, -10 +DU32, 7, 262745 +CURR, 117890, 0, 0, 1529, 125, 5283, 16.63677 +ATT, 117890, 0.00, 0.03, 0.00, -2.22, 182.54, 182.54 +RCIN, 117890, 1503, 1504, 1025, 1513, 992, 992, 993, 991 +RCOU, 117891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117891, -0.00198541, -0.04696069, -0.02134884, -0.4546933, 0.4107634, -9.970998 +IMU2, 117891, -0.008964859, -0.05198474, -0.02126155, -0.4793274, 0.5370034, -9.94678 +IMU, 117910, 0.01644112, -0.06291922, -0.02543474, -0.4072914, 0.3759084, -10.02783 +IMU2, 117910, 0.003205253, -0.07745913, -0.02978421, -0.4183356, 0.5083942, -10.01198 +IMU, 117930, 0.03485631, -0.08317554, -0.02136862, -0.4055308, 0.5004877, -9.824969 +IMU2, 117930, 0.0359715, -0.0883541, -0.02344617, -0.3511005, 0.6502844, -9.770474 +IMU, 117950, 0.05839092, -0.09442969, -0.01345934, -0.5162552, 0.4379844, -9.704681 +IMU2, 117950, 0.05191392, -0.09621216, -0.01771206, -0.5698719, 0.5550861, -9.720756 +IMU, 117970, 0.07779472, -0.08760075, -0.0182718, -0.4988881, 0.2153152, -9.770504 +IMU2, 117970, 0.06740378, -0.09010039, -0.02631683, -0.4710855, 0.3321123, -9.790085 +MAG, 117980, -405, 15, 85, -86, 10, 139, 0, 0, 0 +MAG2, 117980, -267, -67, 262, 0, 0, 0, 0, 0, 0 +CTUN, 117990, 0, 0, 0, 0, 0.02, -0.12, 0.00, 0.00, 0, -9 +ATT, 117990, 0.00, 0.21, 0.00, -2.69, 182.45, 182.45 +RCIN, 117990, 1504, 1503, 1026, 1512, 992, 992, 993, 992 +RCOU, 117991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 117991, 0.07959608, -0.07818529, -0.01962547, -0.4159826, 0.1504221, -9.750491 +IMU2, 117991, 0.07255781, -0.08838247, -0.01598399, -0.47736, 0.3374972, -9.72333 +IMU, 118010, 0.07570416, -0.0715895, -0.01627858, -0.5234317, 0.2663339, -9.64144 +IMU2, 118010, 0.07298603, -0.07462509, -0.00972244, -0.4342809, 0.4371922, -9.80619 +IMU, 118030, 0.06303816, -0.06882063, -0.02059203, -0.6988841, 0.1661585, -9.750016 +IMU2, 118030, 0.05212268, -0.06248822, -0.02210246, -0.6362548, 0.2811788, -9.759702 +IMU, 118051, 0.03998006, -0.06103485, -0.03383057, -0.6444452, 0.05762066, -9.681142 +IMU2, 118051, 0.02844827, -0.06112605, -0.03700707, -0.6972815, 0.1852878, -9.656788 +GPS, 3, 56698200, 1777, 10, 1.44, 14.1105771, 100.6192307, 0.01, 0.21, 0.89, 292.68, -0.35, 118060 +IMU, 118070, 0.0107778, -0.05803759, -0.03727339, -0.683156, 0.1760196, -9.593516 +IMU2, 118070, -0.001947517, -0.06248464, -0.03589718, -0.5892595, 0.3182831, -9.65955 +MAG, 118081, -404, 14, 89, -86, 10, 139, 0, 0, 0 +MAG2, 118081, -265, -66, 265, 0, 0, 0, 0, 0, 0 +CTUN, 118090, 0, 0, 0, 0, 0, -0.12, 0.00, 0.00, 0, -10 +ATT, 118090, 0.00, 0.37, 0.00, -3.08, 182.30, 182.30 +RCIN, 118090, 1503, 1504, 1026, 1512, 992, 992, 993, 992 +RCOU, 118090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 118090, -0.008140625, -0.05352993, -0.03453452, -0.6930082, 0.2116694, -9.743829 +IMU2, 118090, -0.02078513, -0.0622712, -0.02913642, -0.7286759, 0.2949578, -9.781599 +IMU, 118110, -0.01787397, -0.0403234, -0.04151883, -0.6947161, 0.1053011, -9.792717 +IMU2, 118110, -0.02562324, -0.04258044, -0.04324329, -0.692003, 0.3020397, -9.78549 +IMU, 118130, -0.03297688, -0.03247427, -0.04391371, -0.6527497, 0.2123973, -9.666496 +IMU2, 118130, -0.02668674, -0.03210483, -0.04181741, -0.6733007, 0.4007797, -9.560126 +IMU, 118150, -0.03436286, -0.03481855, -0.03272477, -0.6411967, 0.3477221, -9.748982 +IMU2, 118150, -0.04331817, -0.04794471, -0.02870226, -0.5939569, 0.4822071, -9.712712 +IMU, 118170, -0.01094867, -0.03481741, -0.02647128, -0.6715757, 0.2202929, -9.765799 +IMU2, 118170, -0.01394664, -0.02625813, -0.02486631, -0.6222938, 0.3378042, -9.722919 +MAG, 118180, -405, 14, 91, -86, 10, 139, 0, 0, 0 +MAG2, 118180, -264, -69, 269, 0, 0, 0, 0, 0, 0 +CTUN, 118190, 0, 0, 0, 0, 0, -0.16, 0.00, 0.00, 0, -11 +ATT, 118190, 0.00, 0.30, 0.00, -3.38, 182.11, 182.11 +RCIN, 118190, 1503, 1504, 1027, 1511, 993, 992, 992, 992 +RCOU, 118191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 118191, 0.003716871, -0.03268297, -0.02796047, -0.6004952, 0.2113713, -9.81896 +IMU2, 118191, 5.036592E-06, -0.03514703, -0.02870652, -0.5969143, 0.3307809, -9.821586 +IMU, 118210, 0.008461589, -0.03716719, -0.01971598, -0.5956843, 0.3183894, -9.775168 +IMU2, 118210, -0.006623622, -0.03890967, -0.01966814, -0.6171578, 0.4990432, -9.704137 +EV, 15 +IMU, 118230, 0.01886911, -0.05077928, -0.007437171, -0.6537081, 0.4040784, -9.829169 +IMU2, 118230, 0.002570774, -0.06382611, -0.008247514, -0.601205, 0.54002, -9.748709 +IMU, 118251, 0.02364587, -0.06147926, -0.01107863, -0.456117, 0.2462089, -9.762282 +IMU2, 118251, 0.01439221, -0.07334606, -0.01400589, -0.4638785, 0.4025568, -9.775249 +GPS, 3, 56698400, 1777, 10, 1.44, 14.1105797, 100.6192266, -0.02, 0.23, 1.55, 301.04, -0.29, 118260 +IMU, 118270, 0.02705537, -0.05935871, -0.008481384, -0.7008579, 0.388254, -10.06721 +IMU2, 118270, 0.02494279, -0.05595931, 0.0001205998, -0.6507919, 0.530412, -10.10859 +MAG, 118281, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118281, -256, -71, 247, 0, 0, 0, 0, 0, 0 +CTUN, 118290, 202, 0, 202, 0, -0.02, -0.07, 0.00, 0.00, 0, -10 +ATT, 118290, 0.00, 0.48, 0.00, -3.71, 182.07, 182.07 +RCIN, 118290, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 118291, 1322, 1210, 1303, 1233, 0, 0, 0, 0 +IMU, 118291, 0.03398599, -0.0386472, 0.006943359, -0.9528567, 0.4785241, -10.10479 +IMU2, 118291, 0.03318095, -0.02718784, 0.005025792, -0.9880323, 0.5976744, -10.19705 +IMU, 118311, 0.02729038, 0.006937377, -0.001249405, -1.037256, -0.02327266, -10.14934 +IMU2, 118311, 0.01048926, 0.01411848, -0.00555661, -1.069976, 0.1264081, -10.11006 +IMU, 118330, 0.02314684, 0.04430267, -0.002464815, -0.9947029, 0.08204147, -10.05811 +IMU2, 118330, 0.002607271, 0.04887997, -0.002185052, -1.009635, 0.2365041, -9.905854 +IMU, 118350, 0.007798841, 0.1003018, -0.001262228, -1.320865, -0.06320614, -10.12138 +IMU2, 118350, 0.004571576, 0.1092757, -0.003223399, -1.311403, -0.04328823, -10.16308 +IMU, 118371, -0.07218486, 0.1349631, -0.002145908, -1.067099, 0.2797121, -10.17071 +IMU2, 118371, -0.06537825, 0.1392305, 0.005519991, -1.105784, 0.3730093, -10.07955 +MAG, 118380, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118380, -253, -83, 239, 0, 0, 0, 0, 0, 0 +CTUN, 118390, 202, 0, 202, 0, -0.04, -0.09, 0.00, 0.00, 0, -7 +ATT, 118390, 0.00, 2.56, 0.00, -3.30, 182.07, 182.07 +RCIN, 118390, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 118391, 1286, 1210, 1253, 1255, 0, 0, 0, 0 +IMU, 118391, -0.06540987, 0.1539248, 0.009939826, -1.323405, -0.1232645, -10.1784 +IMU2, 118391, -0.07200199, 0.1463101, 0.01582218, -1.338412, 0.04360986, -10.18717 +IMU, 118410, -0.08688523, 0.1671252, 0.002364935, -0.9637141, 0.1839392, -9.979731 +IMU2, 118410, -0.08284947, 0.1567003, 0.002584099, -0.9244465, 0.3137364, -9.990106 +IMU, 118430, -0.07334684, 0.166354, 0.0207173, -1.042493, -0.186229, -9.77547 +IMU2, 118430, -0.07948069, 0.1687077, 0.01946603, -1.088215, -0.02250695, -9.80652 +IMU, 118451, -0.1112062, 0.1825927, 0.01916965, -0.69665, -0.05407271, -9.966374 +IMU2, 118451, -0.1113861, 0.1823214, 0.02459777, -0.7259262, 0.08736801, -9.960247 +GPS, 3, 56698600, 1777, 10, 1.44, 14.1105819, 100.6192227, -0.04, 0.08, 1.82, 303.96, -0.19, 118460 +IMU, 118470, -0.1606875, 0.172448, 0.03606346, -0.832628, 0.1257562, -10.07914 +IMU2, 118470, -0.1492862, 0.1799493, 0.0456781, -0.8319222, 0.1656041, -10.21806 +MAG, 118481, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118481, -260, -75, 250, 0, 0, 0, 0, 0, 0 +CTUN, 118490, 202, 0, 202, 0, -0.05, 0.04, 0.00, 0.00, 0, -5 +ATT, 118490, 0.00, 4.11, 0.00, -2.47, 182.25, 182.25 +RCIN, 118490, 1503, 1504, 1066, 1512, 992, 992, 993, 992 +RCOU, 118490, 1264, 1210, 1263, 1244, 0, 0, 0, 0 +IMU, 118490, -0.2169756, 0.1628079, 0.04685889, -0.3957147, 0.3873013, -9.897372 +IMU2, 118490, -0.2113275, 0.1525738, 0.05111823, -0.3154706, 0.5622334, -9.969704 +IMU, 118511, -0.2160548, 0.1278497, 0.0747397, -0.4559729, 0.0384578, -9.795688 +IMU2, 118511, -0.2188382, 0.1271609, 0.08474448, -0.4893156, 0.1701447, -9.888566 +IMU, 118530, -0.2197219, 0.09475452, 0.07198795, -0.06205222, -0.05085391, -9.847742 +IMU2, 118530, -0.2489389, 0.0848822, 0.0740412, 0.01311004, 0.2881244, -9.63337 +IMU, 118550, -0.2167003, 0.05589218, 0.0927169, -0.2547595, 0.4496791, -9.927505 +IMU2, 118550, -0.2176674, 0.05380568, 0.1050791, -0.2951083, 0.5525925, -10.06411 +IMU, 118571, -0.2642899, 0.01049513, 0.08917286, 0.1398289, 0.8098478, -10.08505 +IMU2, 118571, -0.2600517, 0.01113816, 0.09854006, 0.2053413, 0.9813327, -10.15137 +MAG, 118580, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118580, -260, -77, 243, 0, 0, 0, 0, 0, 0 +CTUN, 118590, 201, 0, 200, 0, -0.05, 0.03, 0.00, 0.00, 0, -4 +ATT, 118590, 0.00, 5.10, 0.00, -2.28, 182.75, 182.75 +RCIN, 118590, 1503, 1504, 1065, 1512, 992, 993, 992, 992 +RCOU, 118591, 1387, 1210, 1354, 1318, 0, 0, 0, 0 +IMU, 118591, -0.2357778, -0.03303306, 0.1300951, -0.2158858, 0.2542732, -9.829878 +IMU2, 118591, -0.2484834, -0.03488629, 0.1267154, -0.2171656, 0.3884978, -9.76165 +IMU, 118610, -0.2231407, -0.07716035, 0.1322046, -0.128782, 1.210932, -9.473305 +IMU2, 118610, -0.1923283, -0.07325159, 0.1453949, -0.08474064, 1.351868, -9.688465 +IMU, 118630, -0.1713338, -0.08998117, 0.1576418, -0.198891, 0.03678915, -9.519857 +IMU2, 118630, -0.2018903, -0.09083791, 0.1583914, -0.2492086, 0.2430803, -9.334386 +GPS, 3, 56698800, 1777, 11, 1.42, 14.1105826, 100.6192238, -0.05, 0.08, 1.46, 307.17, -0.08, 118640 +IMU, 118650, -0.158422, -0.09425621, 0.1898917, -0.3883126, 0.7198675, -9.730177 +IMU2, 118650, -0.1404104, -0.09092158, 0.1889785, -0.4885961, 0.6944104, -9.855974 +IMU, 118670, -0.2125846, -0.08701536, 0.1672168, -0.4449133, 0.1348209, -9.611242 +IMU2, 118670, -0.2549534, -0.07500808, 0.1714222, -0.3838622, 0.4038284, -9.510722 +MAG, 118680, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118680, -254, -79, 227, 0, 0, 0, 0, 0, 0 +CTUN, 118690, 202, 0, 202, 0, -0.05, 0.00, 0.00, 0.00, 0, -7 +ATT, 118690, 0.00, 6.18, 0.00, -2.84, 183.58, 183.58 +RCIN, 118690, 1504, 1503, 1066, 1513, 992, 992, 993, 991 +RCOU, 118690, 1383, 1210, 1364, 1334, 0, 0, 0, 0 +IMU, 118690, -0.2432955, -0.0680257, 0.1800602, -0.6423501, 0.2828821, -9.393067 +IMU2, 118690, -0.2628097, -0.05607123, 0.1841595, -0.7851152, 0.3760201, -9.254789 +IMU, 118710, -0.3010362, -0.0368824, 0.1607615, -0.4721855, 1.077112, -9.80226 +IMU2, 118710, -0.3024865, -0.0298221, 0.1679728, -0.3631174, 1.212047, -9.809614 +IMU, 118730, -0.3094987, -0.008985523, 0.1460229, -0.8741884, -0.2433835, -9.72007 +IMU2, 118730, -0.3534991, 0.01315164, 0.1449538, -0.8111903, 0.09964883, -9.613585 +IMU, 118750, -0.3043254, 0.03254157, 0.1636724, -0.8171836, 0.3990003, -9.482764 +IMU2, 118750, -0.3107746, 0.0405957, 0.1637839, -0.9382721, 0.294089, -9.55846 +IMU, 118770, -0.4165696, 0.06815883, 0.1400517, -0.8184342, 1.396707, -9.794366 +IMU2, 118770, -0.4122462, 0.09614363, 0.1603351, -0.6126067, 1.553741, -9.723526 +MAG, 118780, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118780, -260, -72, 245, 0, 0, 0, 0, 0, 0 +CTUN, 118790, 202, 0, 202, 0, -0.06, -0.13, 0.00, 0.00, 0, -9 +ATT, 118790, 0.00, 6.51, 0.00, -2.79, 184.35, 184.35 +RCIN, 118790, 1503, 1504, 1066, 1513, 992, 992, 992, 992 +RCOU, 118791, 1279, 1210, 1301, 1268, 0, 0, 0, 0 +IMU, 118791, -0.4682251, 0.1047058, 0.1251846, -0.5601153, 0.3953825, -9.172825 +IMU2, 118791, -0.4728242, 0.1023096, 0.1368871, -0.6918441, 0.5611329, -9.230287 +IMU, 118810, -0.4286012, 0.1097233, 0.1295279, -0.7129802, 1.11857, -9.955308 +IMU2, 118810, -0.4427958, 0.1214808, 0.1293952, -0.6852532, 1.169596, -9.880804 +IMU, 118831, -0.4510812, 0.1124856, 0.1180552, -0.4538409, 1.929393, -9.807808 +IMU2, 118831, -0.4238749, 0.1223344, 0.1328439, -0.3136856, 2.134554, -9.917916 +GPS, 3, 56699000, 1777, 11, 1.42, 14.1105829, 100.6192236, -0.06, 0.10, 1.10, 307.17, -0.11, 118840 +IMU, 118851, -0.4180443, 0.101213, 0.1165914, -0.531862, 0.3838805, -9.795286 +IMU2, 118851, -0.434184, 0.1103285, 0.1288452, -0.6046762, 0.6913913, -9.968926 +IMU, 118870, -0.3715342, 0.1103421, 0.1311039, -0.07613908, 1.594135, -9.623027 +IMU2, 118870, -0.379968, 0.1227036, 0.1418901, 0.06686687, 1.494065, -9.500364 +MAG, 118881, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118881, -262, -69, 247, 0, 0, 0, 0, 0, 0 +CTUN, 118890, 202, 0, 202, 0, -0.07, 0.03, 0.00, 0.00, 0, -11 +DU32, 7, 262777 +CURR, 118890, 202, 1412, 1526, 604, 5307, 18.26205 +ATT, 118891, 0.00, 6.46, 0.00, -2.39, 185.03, 185.03 +RCIN, 118891, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 118891, 1364, 1210, 1334, 1324, 0, 0, 0, 0 +IMU, 118891, -0.4099984, 0.08547246, 0.1319816, 0.1754799, 2.480813, -9.57228 +IMU2, 118891, -0.3643107, 0.09202133, 0.1529924, 0.1482137, 2.665481, -9.83928 +IMU, 118910, -0.4074506, 0.08994018, 0.122778, 0.1743392, 1.240438, -9.883668 +IMU2, 118910, -0.4255405, 0.08958031, 0.1370942, 0.3605186, 1.487356, -9.620042 +IMU, 118930, -0.3263507, 0.05107959, 0.1475869, 0.239891, 1.408366, -9.73796 +IMU2, 118930, -0.3511946, 0.05590354, 0.141542, 0.05821002, 1.358021, -9.729156 +IMU, 118950, -0.4024594, 0.02636492, 0.1481558, 0.2461585, 2.644836, -9.93103 +IMU2, 118950, -0.375345, 0.0392293, 0.1531206, 0.3570023, 2.812225, -10.05665 +IMU, 118970, -0.4563733, -0.04435765, 0.1390601, 0.3407898, 1.391072, -9.498364 +IMU2, 118970, -0.4958405, -0.04772064, 0.1464201, 0.2626339, 1.62189, -9.479417 +MAG, 118980, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 118980, -261, -71, 240, 0, 0, 0, 0, 0, 0 +CTUN, 118990, 202, 0, 202, 0, -0.08, 0.03, 0.00, 0.00, 0, -15 +ATT, 118990, 0.00, 6.53, 0.00, -2.48, 185.75, 185.75 +RCIN, 118990, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 118991, 1463, 1210, 1416, 1346, 0, 0, 0, 0 +IMU, 118991, -0.4276682, -0.1029291, 0.1437516, 0.2884077, 1.868155, -9.183166 +IMU2, 118991, -0.435733, -0.1074487, 0.1425554, 0.2843395, 1.857334, -9.188185 +IMU, 119010, -0.4403501, -0.1660073, 0.1117482, 0.2509333, 3.115346, -9.374969 +IMU2, 119010, -0.3949756, -0.187895, 0.123071, 0.2070202, 3.270288, -9.435873 +IMU, 119030, -0.3979405, -0.1971139, 0.08154722, -0.3097227, 1.824151, -9.589874 +IMU2, 119030, -0.4181914, -0.1943986, 0.08353786, -0.2098451, 2.095149, -9.336564 +IMU, 119050, -0.2766182, -0.2125002, 0.09570478, -0.3020373, 1.84631, -9.457026 +IMU2, 119050, -0.2985046, -0.2122837, 0.08832627, -0.4705554, 1.833985, -9.417267 +EV, 28 +GPS, 3, 56699200, 1777, 11, 1.42, 14.1105836, 100.6192221, -0.09, 0.07, 1.11, 307.17, -0.04, 119060 +IMU, 119071, -0.2520892, -0.1889026, 0.0978979, -0.5420339, 3.16864, -9.846885 +IMU2, 119071, -0.2235125, -0.1881595, 0.09912903, -0.4108674, 3.052377, -9.740399 +MAG, 119080, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119080, -256, -76, 234, 0, 0, 0, 0, 0, 0 +CTUN, 119090, 202, 0, 202, 0, -0.09, -0.17, 0.00, 0.00, 0, -21 +ATT, 119090, 0.00, 6.98, 0.00, -3.56, 186.03, 186.16 +RCIN, 119090, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 119090, 1478, 1210, 1407, 1356, 0, 0, 0, 0 +IMU, 119090, -0.2897203, -0.1702886, 0.08978014, -0.9169019, 3.094676, -9.770012 +IMU2, 119090, -0.2663072, -0.1484475, 0.09454093, -0.9747418, 3.445683, -10.04036 +IMU, 119110, -0.2407556, -0.09021489, 0.0764164, -0.7475848, 2.013383, -9.117608 +IMU2, 119110, -0.2633222, -0.08853097, 0.07397582, -0.6981844, 2.17765, -9.226692 +IMU, 119130, -0.1653782, -0.01356022, 0.07096943, -0.8722744, 2.000268, -9.314461 +IMU2, 119130, -0.1876131, -0.001407674, 0.06442894, -0.9897802, 2.006256, -9.09088 +IMU, 119150, -0.1574522, 0.04735005, 0.05587002, -1.032238, 2.857754, -9.34001 +IMU2, 119150, -0.1455583, 0.04654883, 0.06560416, -0.9484904, 2.792143, -9.258422 +IMU, 119170, -0.2454779, 0.06279606, 0.03926987, -1.340649, 3.05815, -9.725466 +IMU2, 119170, -0.2240837, 0.07971562, 0.05379732, -1.203271, 3.369605, -9.917611 +MAG, 119180, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119180, -256, -76, 244, 0, 0, 0, 0, 0, 0 +CTUN, 119190, 202, 0, 202, 0, -0.12, 0.00, 0.00, 0.00, 0, -27 +ATT, 119190, 0.00, 8.08, 0.00, -3.52, 186.03, 186.44 +RCIN, 119190, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 119191, 1444, 1210, 1338, 1383, 0, 0, 0, 0 +IMU, 119191, -0.2343841, 0.08676866, 0.03686884, -0.9089888, 1.768498, -8.97308 +IMU2, 119191, -0.2676366, 0.08839311, 0.03568914, -0.894895, 2.295817, -9.033433 +IMU, 119210, -0.1959882, 0.1161867, 0.04809744, -0.8975713, 2.005819, -9.11454 +IMU2, 119210, -0.2016709, 0.1243288, 0.05773201, -0.8023547, 2.073873, -9.065223 +IMU, 119230, -0.1927397, 0.1202815, 0.0603223, -0.7953458, 2.809923, -9.382029 +IMU2, 119230, -0.1820576, 0.1222801, 0.07960672, -0.6893929, 2.832889, -9.289086 +GPS, 3, 56699400, 1777, 11, 1.42, 14.110584, 100.6192204, -0.14, 0.10, 1.03, 307.17, -0.04, 119240 +IMU, 119250, -0.2315916, 0.1320013, 0.06094199, -0.6484291, 2.820742, -9.766487 +IMU2, 119250, -0.22977, 0.1319776, 0.08434717, -0.4600974, 3.092257, -9.918737 +IMU, 119270, -0.2315625, 0.1506424, 0.06869174, -0.3655645, 2.028634, -9.597137 +IMU2, 119270, -0.2557053, 0.147191, 0.08508576, -0.2272575, 2.215578, -9.424739 +MAG, 119280, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119281, -259, -74, 245, 0, 0, 0, 0, 0, 0 +CTUN, 119290, 202, 0, 202, 0, -0.15, -0.12, 0.00, 0.00, 0, -35 +ATT, 119290, 0.00, 9.08, 0.00, -2.96, 186.03, 186.87 +RCIN, 119290, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 119290, 1489, 1210, 1337, 1459, 0, 0, 0, 0 +IMU, 119291, -0.2019687, 0.1426211, 0.08179177, -0.4320335, 2.242506, -9.706777 +IMU2, 119291, -0.2062442, 0.1468407, 0.08286227, -0.3587084, 2.257863, -9.693668 +IMU, 119310, -0.2281521, 0.1079045, 0.08194569, -0.128037, 3.206855, -9.572418 +IMU2, 119310, -0.2132929, 0.1100349, 0.09545151, -0.04688466, 3.280793, -9.730561 +IMU, 119330, -0.262158, 0.0777685, 0.07718788, 0.3672464, 2.853306, -9.697316 +IMU2, 119330, -0.2780896, 0.07652034, 0.08214945, 0.3469414, 3.203526, -9.737006 +IMU, 119350, -0.1996458, 0.07094192, 0.08863204, 0.7932507, 2.21679, -9.323524 +IMU2, 119350, -0.2375949, 0.05557616, 0.09174942, 0.7514626, 2.405096, -9.186548 +IMU, 119370, -0.1532346, 0.0419616, 0.09332203, 0.5418528, 2.921175, -9.243025 +IMU2, 119370, -0.1463836, 0.05057464, 0.09483131, 0.5636595, 2.749245, -9.329206 +MAG, 119380, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119380, -261, -74, 242, 0, 0, 0, 0, 0, 0 +CTUN, 119391, 202, 0, 202, 0, -0.19, 0.02, 0.00, 0.00, 0, -44 +ATT, 119391, 0.00, 10.20, 0.00, -2.77, 186.03, 187.31 +RCIN, 119391, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 119392, 1499, 1210, 1361, 1426, 0, 0, 0, 0 +IMU, 119392, -0.1670006, -0.01950363, 0.0451951, 0.3546614, 3.280995, -9.122807 +IMU2, 119392, -0.1511238, -0.02333594, 0.04799, 0.4395977, 3.57053, -9.242687 +IMU, 119411, -0.1380568, -0.09719022, -0.001216226, 0.4124074, 2.183599, -8.625597 +IMU2, 119411, -0.1543782, -0.1165249, -0.01441146, 0.3871284, 2.471555, -8.613132 +IMU, 119430, -0.03429425, -0.1753741, -0.03422541, 0.1536917, 2.084798, -8.666061 +IMU2, 119430, -0.04048555, -0.1843706, -0.05341269, 0.1308124, 2.105969, -8.549107 +GPS, 3, 56699600, 1777, 11, 1.42, 14.1105866, 100.6192165, -0.21, -0.28, 1.17, 307.17, 0.08, 119440 +IMU, 119451, -0.009923989, -0.2366466, -0.07622971, 0.1215331, 3.146125, -8.862097 +IMU2, 119451, 0.02531778, -0.2431809, -0.08283079, 0.09173191, 3.176734, -9.023492 +IMU, 119470, -0.03421821, -0.2795731, -0.1340466, -0.02660677, 2.804479, -8.499823 +IMU2, 119470, -0.02939915, -0.2816647, -0.1446151, -0.1858906, 3.134392, -8.545085 +MAG, 119480, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119480, -259, -76, 239, 0, 0, 0, 0, 0, 0 +CTUN, 119490, 202, 0, 202, 0, -0.23, 0.00, 0.00, 0.00, 0, -60 +ATT, 119490, 0.00, 12.11, 0.00, -3.80, 186.03, 186.69 +RCIN, 119490, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 119490, 1537, 1210, 1343, 1405, 0, 0, 0, 0 +IMU, 119490, -0.002463268, -0.2648776, -0.1680748, -0.06470348, 2.105048, -8.715077 +IMU2, 119490, -0.0142162, -0.2726793, -0.1812559, -0.2025534, 2.158141, -8.733257 +IMU, 119510, 0.006114645, -0.2224153, -0.1811519, -0.08423011, 3.226242, -8.967216 +IMU2, 119510, 0.02889549, -0.227476, -0.1917707, -0.1145141, 3.109101, -9.049902 +IMU, 119530, -0.05675416, -0.1705665, -0.2046513, -0.3788742, 3.419989, -9.303217 +IMU2, 119530, -0.03744776, -0.1666489, -0.2052555, -0.3121302, 3.593485, -9.630672 +IMU, 119550, -0.0601842, -0.09742042, -0.2119114, -0.5828596, 1.975758, -9.08941 +IMU2, 119550, -0.07685566, -0.09654772, -0.2148437, -0.6119055, 2.224029, -9.170494 +IMU, 119571, -0.0335785, -0.02184608, -0.2032692, -0.9963188, 2.287694, -9.31612 +IMU2, 119571, -0.04423216, -0.01395833, -0.2023423, -0.9639723, 2.260546, -9.29189 +MAG, 119580, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119580, -255, -83, 246, 0, 0, 0, 0, 0, 0 +CTUN, 119591, 202, 0, 202, 0, -0.29, 0.03, 0.00, 0.00, 0, -73 +ATT, 119591, 0.00, 14.13, 0.00, -4.09, 186.03, 185.53 +RCIN, 119591, 1504, 1504, 1066, 1511, 992, 993, 992, 992 +RCOU, 119591, 1548, 1210, 1276, 1457, 0, 0, 0, 0 +IMU, 119591, -0.0845401, 0.04177494, -0.1961038, -0.9870998, 3.151103, -9.436042 +IMU2, 119591, -0.06783731, 0.04428921, -0.184929, -0.9064037, 3.195209, -9.533559 +IMU, 119610, -0.1343863, 0.09063478, -0.1793662, -0.9030228, 2.478764, -9.356245 +IMU2, 119610, -0.1449468, 0.09406084, -0.1672562, -0.9828818, 2.772914, -9.396649 +IMU, 119630, -0.1162961, 0.1458064, -0.1315888, -0.7949084, 2.203629, -9.370528 +IMU2, 119630, -0.1105725, 0.1468993, -0.1253329, -0.8105406, 2.252659, -9.288188 +GPS, 3, 56699800, 1777, 11, 1.42, 14.1105885, 100.619215, -0.33, -0.62, 0.94, 307.17, 0.14, 119640 +IMU, 119650, -0.1713091, 0.1603958, -0.09907939, -0.7095855, 3.153898, -9.378579 +IMU2, 119650, -0.1509508, 0.1595969, -0.08897945, -0.7315977, 3.242734, -9.345186 +IMU, 119670, -0.27791, 0.1542275, -0.08514893, -0.8693259, 2.504196, -9.578992 +IMU2, 119670, -0.297209, 0.1626731, -0.07656703, -0.7756819, 3.056719, -9.716364 +MAG, 119680, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119680, -255, -91, 246, 0, 0, 0, 0, 0, 0 +CTUN, 119690, 202, 0, 202, 0, -0.36, 0.04, 0.00, 0.00, 0, -83 +ATT, 119690, 0.00, 15.22, 0.00, -3.25, 186.03, 185.17 +RCIN, 119690, 1503, 1504, 1066, 1511, 992, 993, 992, 992 +RCOU, 119690, 1532, 1210, 1288, 1465, 0, 0, 0, 0 +IMU, 119691, -0.2676858, 0.1624656, -0.03008487, -0.7565838, 2.17811, -9.52882 +IMU2, 119691, -0.2931348, 0.1548958, -0.02060319, -0.6985639, 2.301318, -9.449127 +IMU, 119710, -0.2793009, 0.1480428, 0.01742723, -0.4937752, 3.30352, -9.86775 +IMU2, 119710, -0.276462, 0.147003, 0.04271581, -0.3550129, 3.349786, -9.684479 +IMU, 119730, -0.3307035, 0.1094409, 0.04397395, -0.4867455, 2.789915, -9.814205 +IMU2, 119730, -0.3749399, 0.1152852, 0.06653135, -0.2824887, 3.260788, -9.591096 +IMU, 119750, -0.256574, 0.07201942, 0.09413126, -0.3108466, 2.334052, -9.57257 +IMU2, 119750, -0.2960475, 0.06475979, 0.1070908, -0.2266498, 2.41239, -9.453025 +IMU, 119770, -0.251307, 0.01413244, 0.1408956, 0.06267601, 3.774523, -9.303348 +IMU2, 119770, -0.240624, 0.002920764, 0.1608023, 0.1307601, 3.737036, -9.264937 +MAG, 119780, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119780, -259, -93, 246, 0, 0, 0, 0, 0, 0 +CTUN, 119790, 202, 0, 201, 0, -0.43, 0.09, 0.00, 0.00, 0, -96 +ATT, 119790, 0.00, 15.87, 0.00, -3.10, 186.03, 185.72 +RCIN, 119790, 1504, 1503, 1066, 1513, 992, 992, 993, 991 +RCOU, 119791, 1502, 1210, 1355, 1429, 0, 0, 0, 0 +IMU, 119791, -0.309848, -0.05330262, 0.1501404, -0.09818852, 3.174734, -9.300912 +IMU2, 119791, -0.3305766, -0.06032126, 0.1567205, -0.08447087, 3.552945, -9.356819 +IMU, 119810, -0.2618478, -0.09284739, 0.1696511, -0.09549439, 2.97256, -9.155827 +IMU2, 119810, -0.2699142, -0.1018425, 0.1630897, -0.1282798, 3.087567, -9.135202 +IMU, 119830, -0.2782252, -0.1071113, 0.1683292, 0.4278515, 4.590294, -9.458721 +IMU2, 119830, -0.2600386, -0.1145023, 0.1709101, 0.5715438, 4.631788, -9.445458 +GPS, 3, 56700000, 1777, 11, 1.42, 14.11059, 100.619212, -0.48, -0.78, 0.98, 307.17, 0.18, 119840 +IMU, 119850, -0.3229777, -0.1261341, 0.1349486, 0.1678581, 3.676726, -9.421895 +IMU2, 119850, -0.3426124, -0.1182779, 0.1401896, 0.249154, 4.163916, -9.386766 +IMU, 119870, -0.2395494, -0.1431008, 0.1201035, -0.3843271, 3.133654, -8.951303 +IMU2, 119870, -0.2585889, -0.1380615, 0.1140879, -0.3859382, 3.277136, -8.882263 +MAG, 119880, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119880, -259, -90, 246, 0, 0, 0, 0, 0, 0 +PM, 16, 16, 5, 1000, 10698, 10, 0, 0, 0 +CTUN, 119890, 202, 0, 202, 0, -0.52, -0.04, 0.00, 0.00, 0, -115 +DU32, 7, 262265 +CURR, 119890, 202, 3431, 1528, 707, 5267, 20.55008 +ATT, 119890, 0.00, 16.62, 0.00, -4.01, 186.03, 186.19 +RCIN, 119890, 1503, 1504, 1066, 1512, 993, 992, 992, 992 +RCOU, 119891, 1508, 1210, 1344, 1435, 0, 0, 0, 0 +IMU, 119891, -0.1810892, -0.1774186, 0.07979792, -0.1536832, 4.49776, -8.99227 +IMU2, 119891, -0.1647751, -0.1809488, 0.07601518, -0.1640042, 4.563289, -8.899393 +IMU, 119910, -0.1611137, -0.2189192, 0.02563305, -0.226642, 3.678396, -9.065203 +IMU2, 119910, -0.1813801, -0.2249118, 0.0164459, -0.2572886, 4.08982, -9.075308 +IMU, 119930, -0.04692656, -0.2442994, -0.01298489, -0.4857887, 3.062824, -8.607371 +IMU2, 119930, -0.06902619, -0.2471138, -0.03343199, -0.6609592, 3.180787, -8.577071 +IMU, 119950, -0.01307065, -0.2592671, -0.06439098, -0.1260458, 4.224293, -8.628184 +IMU2, 119950, 0.00491358, -0.2686563, -0.07764178, -0.2134312, 4.244638, -8.743273 +IMU, 119971, -0.04116452, -0.2626238, -0.1350489, -0.3303271, 3.645131, -8.706758 +IMU2, 119971, -0.03993414, -0.2569734, -0.1504531, -0.3618603, 4.031707, -8.865118 +MAG, 119980, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 119980, -257, -93, 251, 0, 0, 0, 0, 0, 0 +CTUN, 119990, 202, 0, 202, 0, -0.63, -0.04, 0.00, 0.00, 0, -141 +ATT, 119991, 0.00, 18.62, 0.00, -5.17, 186.03, 185.50 +RCIN, 119991, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 119991, 1534, 1210, 1319, 1430, 0, 0, 0, 0 +IMU, 119991, 0.008764882, -0.225984, -0.1692296, -0.3143525, 3.38761, -8.767689 +IMU2, 119991, -0.0001407228, -0.2331486, -0.1845192, -0.4170032, 3.435771, -8.722379 +IMU, 120011, 0.01063902, -0.1809574, -0.2036481, -0.4163826, 4.613874, -8.78567 +IMU2, 120011, 0.02963783, -0.1908092, -0.2120717, -0.3894365, 4.58532, -8.78884 +IMU, 120030, -0.02776724, -0.1480426, -0.2558784, -1.015053, 3.810076, -9.063055 +IMU2, 120030, -0.03445064, -0.1452911, -0.2569553, -0.9447073, 4.247834, -9.135535 +IMU, 120050, 0.03668275, -0.09218018, -0.2706695, -1.430536, 3.166366, -9.218024 +IMU2, 120050, 0.02381117, -0.09211299, -0.2727316, -1.411404, 3.342912, -9.091483 +IMU, 120070, 0.05707563, -0.03915593, -0.2749674, -1.309967, 4.220933, -9.538876 +IMU2, 120070, 0.07746215, -0.03556827, -0.2684767, -1.263387, 4.234675, -9.54988 +MAG, 120081, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120081, -253, -102, 258, 0, 0, 0, 0, 0, 0 +CTUN, 120090, 201, 0, 201, 0, -0.76, -0.10, 0.00, 0.00, 0, -165 +ATT, 120090, 0.00, 21.09, 0.00, -5.24, 186.03, 184.05 +RCIN, 120090, 1503, 1504, 1065, 1513, 992, 992, 993, 991 +RCOU, 120090, 1553, 1210, 1273, 1454, 0, 0, 0, 0 +IMU, 120090, 0.00264637, 0.008891478, -0.2828599, -1.60996, 3.689288, -9.594251 +IMU2, 120090, -0.01160094, 0.0207611, -0.2705281, -1.575302, 4.162926, -9.581481 +GPS, 3, 56700200, 1777, 11, 1.42, 14.1105891, 100.6192145, -0.79, -0.84, 0.49, 307.17, 0.13, 120101 +IMU, 120110, 0.04883865, 0.07833122, -0.2560704, -1.791067, 2.836312, -9.376728 +IMU2, 120110, 0.02721054, 0.08470003, -0.2486287, -1.820895, 3.027126, -9.407296 +IMU, 120130, 0.04215055, 0.1342326, -0.221415, -1.459522, 4.069212, -9.34154 +IMU2, 120130, 0.06934749, 0.1285722, -0.2052436, -1.350196, 4.159807, -9.465903 +IMU, 120150, -0.03761741, 0.1585873, -0.1980998, -1.253591, 3.678154, -9.474014 +IMU2, 120150, -0.04133844, 0.1620792, -0.187447, -1.229594, 4.070811, -9.533333 +IMU, 120170, -0.01798484, 0.1679712, -0.1345442, -1.310941, 3.256077, -9.454223 +IMU2, 120170, -0.02834449, 0.1571481, -0.1282914, -1.286139, 3.415406, -9.353833 +MAG, 120180, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120180, -252, -109, 256, 0, 0, 0, 0, 0, 0 +CTUN, 120190, 202, 1, 203, 0, -0.92, -0.02, 0.00, 0.00, 0, -188 +ATT, 120191, 0.00, 23.02, 0.00, -4.33, 186.03, 183.46 +RCIN, 120191, 1503, 1504, 1066, 1511, 992, 993, 992, 992 +RCOU, 120191, 1540, 1210, 1270, 1477, 0, 0, 0, 0 +IMU, 120191, -0.03629004, 0.1600097, -0.07471896, -0.9863584, 4.400149, -9.621876 +IMU2, 120191, -0.0186455, 0.1548074, -0.055677, -0.816074, 4.532917, -9.694745 +IMU, 120210, -0.07015243, 0.1442474, -0.02736456, -1.149039, 3.370494, -9.616851 +IMU2, 120210, -0.07997636, 0.1448228, -0.01364862, -0.9478832, 3.785423, -9.541195 +IMU, 120230, -0.02784111, 0.1421565, 0.06008138, -1.212528, 3.252415, -9.459556 +IMU2, 120230, -0.05224872, 0.1360761, 0.08107372, -1.074138, 3.381291, -9.458743 +GPS, 3, 56700400, 1777, 11, 1.42, 14.1105883, 100.6192166, -1.01, -0.94, 0.56, 307.17, 0.09999999, 120240 +IMU, 120250, -0.08358483, 0.1132378, 0.09841555, -0.9359732, 4.489856, -9.184659 +IMU2, 120250, -0.06966282, 0.1038307, 0.1255426, -0.8020713, 4.606156, -9.278159 +IMU, 120270, -0.1085968, 0.05564114, 0.1285644, -1.058752, 3.224495, -8.966753 +IMU2, 120270, -0.1150049, 0.05215879, 0.1458475, -0.9293433, 3.430553, -8.920606 +MAG, 120280, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120280, -255, -110, 253, 0, 0, 0, 0, 0, 0 +CTUN, 120290, 202, 1, 203, 0, -1.08, -0.17, 0.00, 0.00, 0, -213 +ATT, 120290, 0.00, 24.63, 0.00, -4.10, 186.03, 184.07 +RCIN, 120290, 1502, 1504, 1066, 1512, 992, 992, 993, 992 +RCOU, 120291, 1514, 1210, 1311, 1466, 0, 0, 0, 0 +IMU, 120291, -0.07948279, 0.01511034, 0.1837469, -0.7818945, 3.666495, -9.001183 +IMU2, 120291, -0.08306594, 0.01891066, 0.1955691, -0.7393214, 3.714378, -9.009679 +IMU, 120310, -0.1400929, 0.01049034, 0.2001879, -0.2400384, 4.071182, -9.029075 +IMU2, 120310, -0.1338892, 0.01967314, 0.2090776, -0.1631869, 4.290131, -8.986259 +IMU, 120331, -0.1400924, -0.00803943, 0.2186282, -0.5546045, 2.994734, -8.709513 +IMU2, 120331, -0.1542384, -0.004181007, 0.2136604, -0.6179429, 3.164016, -8.770059 +IMU, 120350, -0.1511251, -0.05189028, 0.2188569, -0.3223435, 4.021602, -8.413712 +IMU2, 120350, -0.1289314, -0.0533254, 0.2203176, -0.3246886, 4.10219, -8.502306 +IMU, 120371, -0.2242486, -0.08379275, 0.1841487, -0.3020754, 3.61889, -8.651039 +IMU2, 120371, -0.2326652, -0.08462757, 0.1847103, -0.3159428, 3.766922, -8.724155 +MAG, 120380, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120380, -256, -105, 255, 0, 0, 0, 0, 0, 0 +CTUN, 120390, 202, 1, 202, 0, -1.28, 0.03, 0.00, 0.00, 0, -243 +ATT, 120391, 0.00, 25.86, 0.00, -4.76, 186.03, 184.91 +RCIN, 120391, 1503, 1504, 1066, 1512, 993, 992, 992, 992 +RCOU, 120391, 1500, 1210, 1327, 1460, 0, 0, 0, 0 +IMU, 120391, -0.2050032, -0.08137253, 0.181933, -0.658293, 3.02603, -8.67794 +IMU2, 120391, -0.2269951, -0.07722692, 0.1745803, -0.6228746, 3.049584, -8.514411 +IMU, 120410, -0.2477178, -0.0786123, 0.1617779, -0.3651096, 4.617543, -8.744476 +IMU2, 120410, -0.2369459, -0.06726968, 0.1700048, -0.28408, 4.739725, -8.89129 +IMU, 120430, -0.2583203, -0.09091468, 0.1219736, -0.4515053, 3.693974, -8.72478 +IMU2, 120430, -0.2711259, -0.09212637, 0.1175094, -0.4419867, 3.894647, -8.596397 +GPS, 3, 56700600, 1777, 11, 1.42, 14.1105873, 100.6192198, -1.40, -1.06, 0.55, 307.17, 0.13, 120440 +IMU, 120450, -0.1856419, -0.1124511, 0.1190489, -0.662884, 3.67978, -8.547593 +IMU2, 120450, -0.1852227, -0.1138457, 0.1160886, -0.7782387, 3.65681, -8.630177 +IMU, 120470, -0.2159294, -0.1309669, 0.08541235, -0.3396387, 4.704413, -8.56782 +IMU2, 120470, -0.2007868, -0.132875, 0.09280712, -0.3013633, 4.865501, -8.669574 +MAG, 120480, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120480, -255, -101, 254, 0, 0, 0, 0, 0, 0 +CTUN, 120490, 202, 1, 203, 0, -1.49, 0.00, 0.00, 0.00, 0, -277 +ATT, 120490, 0.00, 26.75, 0.00, -5.54, 186.03, 185.19 +RCIN, 120490, 1504, 1503, 1066, 1513, 992, 992, 992, 992 +RCOU, 120490, 1506, 1210, 1336, 1448, 0, 0, 0, 0 +IMU, 120490, -0.1958238, -0.1397841, 0.06616323, -0.4888904, 3.634124, -8.659774 +IMU2, 120490, -0.2039824, -0.1501866, 0.06267537, -0.5615456, 3.823666, -8.49879 +IMU, 120510, -0.1392998, -0.1539488, 0.0669613, -0.5478984, 4.326402, -8.466464 +IMU2, 120510, -0.1282317, -0.1544241, 0.08251498, -0.6358982, 4.172328, -8.728794 +IMU, 120531, -0.179516, -0.1592735, 0.02192155, -0.3822479, 4.505899, -8.559166 +IMU2, 120531, -0.1760775, -0.1641461, 0.01635162, -0.3289761, 4.675927, -8.563434 +IMU, 120551, -0.1467402, -0.1484636, 0.007575302, -0.6428237, 3.498518, -8.408602 +IMU2, 120551, -0.1677873, -0.1504812, -0.002730266, -0.7018514, 3.673701, -8.372497 +IMU, 120570, -0.1150082, -0.123465, -0.0002418046, -0.4301849, 4.974116, -8.280162 +IMU2, 120570, -0.09318224, -0.1375531, -0.005984461, -0.530892, 4.863956, -8.371728 +MAG, 120580, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120580, -254, -103, 258, 0, 0, 0, 0, 0, 0 +CTUN, 120590, 202, 1, 203, 0, -1.73, -0.05, 0.00, 0.00, 0, -314 +ATT, 120591, 0.00, 28.17, 0.00, -6.24, 186.03, 184.89 +RCIN, 120591, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 120591, 1511, 1210, 1330, 1450, 0, 0, 0, 0 +IMU, 120591, -0.1522306, -0.1105769, -0.02674682, -0.3513995, 4.645787, -8.370109 +IMU2, 120591, -0.1552896, -0.1156445, -0.02514063, -0.244302, 4.790354, -8.540518 +IMU, 120611, -0.07469395, -0.09481477, -0.01620686, -0.7532021, 3.823262, -8.290855 +IMU2, 120611, -0.08458686, -0.09693925, -0.0229682, -0.6873872, 3.971209, -8.218175 +IMU, 120630, -0.05523664, -0.07587194, -0.007360855, -0.5226733, 5.276298, -8.468231 +IMU2, 120630, -0.03351334, -0.09095007, -0.0009331577, -0.5421332, 5.356634, -8.393656 +GPS, 3, 56700800, 1777, 11, 1.42, 14.110586, 100.6192235, -1.89, -1.08, 0.50, 307.17, 0.16, 120640 +IMU, 120650, -0.06005632, -0.07253049, -0.01840349, -0.9409075, 4.517164, -8.564435 +IMU2, 120650, -0.06631479, -0.07281784, -0.02024278, -0.8160656, 4.682307, -8.578921 +IMU, 120670, 0.03601542, -0.05740895, -0.0004074296, -1.172153, 3.859403, -8.391577 +IMU2, 120670, 0.011661, -0.06543845, -0.004070258, -1.148768, 3.852854, -8.312376 +MAG, 120680, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120680, -252, -105, 261, 0, 0, 0, 0, 0, 0 +CTUN, 120690, 202, 1, 203, 0, -2, -0.05, 0.00, 0.00, 0, -355 +ATT, 120690, 0.00, 30.06, 0.00, -6.55, 186.03, 184.67 +RCIN, 120690, 1503, 1504, 1066, 1512, 993, 992, 992, 992 +RCOU, 120690, 1507, 1210, 1318, 1464, 0, 0, 0, 0 +IMU, 120690, 0.04352294, -0.03508602, -0.003899687, -0.8247541, 5.129296, -8.799298 +IMU2, 120690, 0.06454044, -0.03046341, 0.0105845, -0.7768169, 5.165844, -8.834615 +IMU, 120710, 0.05016782, -0.006394614, -0.01414193, -0.909673, 4.219837, -8.915563 +IMU2, 120710, 0.03773317, -0.005778329, -0.01657644, -0.7791767, 4.383328, -8.911386 +IMU, 120730, 0.1162831, 0.004717834, 0.003729383, -1.122679, 4.127629, -8.569141 +IMU2, 120730, 0.0963426, -0.004687196, 0.000501195, -1.129446, 4.001588, -8.571844 +IMU, 120750, 0.05392028, 0.01144795, -0.009630378, -0.7502182, 5.204134, -8.842341 +IMU2, 120750, 0.0790815, 0.01129436, -0.001196662, -0.6146979, 5.310268, -9.086137 +IMU, 120770, 0.04672949, 0.02392055, -0.009602903, -0.7817262, 3.881374, -8.909164 +IMU2, 120770, 0.04275466, 0.01904727, -0.009878084, -0.6940305, 4.090192, -8.949183 +MAG, 120781, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120781, -252, -104, 265, 0, 0, 0, 0, 0, 0 +CTUN, 120790, 202, 2, 204, 0, -2.3, 0.04, 0.00, 0.00, 0, -396 +ATT, 120790, 0.00, 32.60, 0.00, -6.52, 186.03, 184.67 +RCIN, 120790, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 120791, 1502, 1210, 1317, 1470, 0, 0, 0, 0 +IMU, 120791, 0.09625018, 0.03110724, 0.01264956, -0.813466, 4.094265, -8.614484 +IMU2, 120791, 0.107445, 0.02149213, 0.01561313, -0.7347077, 3.957186, -8.513485 +IMU, 120810, 0.02789874, 0.02026873, -0.01118165, -0.7917362, 4.583382, -8.558179 +IMU2, 120810, 0.02187407, 0.02131719, -0.002462045, -0.6278892, 4.824897, -8.452066 +IMU, 120831, 0.02714905, 0.001381006, -0.02245378, -1.089135, 3.282952, -8.764796 +IMU2, 120831, -0.01480896, -0.003730035, -0.01362548, -0.8763048, 3.517162, -8.586386 +GPS, 3, 56701000, 1777, 11, 1.42, 14.110587, 100.6192253, -2.49, -1.03, 0.61, 307.17, 0.18, 120840 +IMU, 120851, 0.04112938, -0.004395351, -0.01837472, -1.021015, 4.414034, -8.709385 +IMU2, 120851, 0.02956226, -0.0150526, -0.005633889, -0.9110088, 4.36473, -8.657833 +IMU, 120870, -0.0301019, -0.01122152, -0.03835133, -1.025007, 4.426511, -8.775629 +IMU2, 120870, -0.03447049, -0.02099494, -0.01862781, -0.8586466, 4.751499, -8.710862 +MAG, 120880, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120880, -251, -103, 263, 0, 0, 0, 0, 0, 0 +CTUN, 120890, 202, 2, 204, 0, -2.63, 0.01, 0.00, 0.00, 0, -440 +DU32, 7, 262265 +CURR, 120890, 204, 5459, 1521, 767, 5270, 22.76009 +ATT, 120890, 0.00, 34.70, 0.00, -6.47, 186.03, 184.60 +RCIN, 120890, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 120891, 1502, 1210, 1327, 1461, 0, 0, 0, 0 +IMU, 120891, -0.01993599, -0.005415577, -0.02964217, -1.208, 3.398966, -8.826233 +IMU2, 120891, -0.0442575, -0.01001954, -0.01935334, -1.060681, 3.615629, -8.735451 +IMU, 120910, -0.02222229, 0.005014859, -0.01144625, -0.8359064, 4.980513, -9.012038 +IMU2, 120910, 0.004071865, -0.006046285, 0.006452505, -0.773952, 4.951796, -8.879604 +IMU, 120930, -0.08437372, 0.00587333, -0.01434649, -0.7481355, 4.48802, -9.081948 +IMU2, 120930, -0.08638871, 0.006769668, -0.007620472, -0.4896742, 4.958152, -9.086847 +IMU, 120950, -0.03134686, 0.01459933, 0.01751138, -1.028443, 3.523896, -8.951644 +IMU2, 120950, -0.04718155, 0.01441193, 0.0125677, -1.056074, 3.677862, -8.768542 +IMU, 120970, -0.03464547, 0.03327233, 0.04258281, -0.7913195, 4.904829, -8.982535 +IMU2, 120970, -0.01054906, 0.03419065, 0.05568652, -0.6318526, 4.944257, -8.886909 +MAG, 120980, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 120980, -252, -104, 263, 0, 0, 0, 0, 0, 0 +CTUN, 120990, 202, 3, 205, 0, -2.99, -0.02, 0.00, 0.00, 0, -485 +ATT, 120990, 0.00, 36.62, 0.00, -6.51, 186.03, 184.70 +RCIN, 120990, 1504, 1504, 1066, 1511, 992, 992, 993, 991 +RCOU, 120990, 1492, 1210, 1335, 1467, 0, 0, 0, 0 +IMU, 120990, -0.09453438, 0.03189777, 0.04710437, -0.8940896, 4.181313, -8.762299 +IMU2, 120990, -0.09803132, 0.02723353, 0.06091758, -0.6732643, 4.533216, -8.488169 +IMU, 121011, -0.06677175, 0.004854813, 0.08044598, -1.138585, 3.678983, -8.626837 +IMU2, 121011, -0.08194481, 0.00385017, 0.08744998, -1.071772, 3.80297, -8.584677 +IMU, 121030, -0.08701244, -0.01620614, 0.1013685, -0.8789546, 5.274945, -8.920201 +IMU2, 121030, -0.05373201, -0.01567894, 0.1166039, -0.6890328, 5.359389, -9.019489 +GPS, 3, 56701200, 1777, 11, 1.42, 14.1105869, 100.6192278, -3.22, -1.62, 0.31, 307.17, 0.4, 121040 +IMU, 121050, -0.09395212, -0.03394219, 0.1188123, -0.9277081, 4.359721, -8.993962 +IMU2, 121050, -0.1012535, -0.03464136, 0.1189477, -0.6394328, 4.825586, -8.908348 +IMU, 121071, -0.0136856, -0.03446486, 0.1670294, -0.9777868, 3.705139, -8.862671 +IMU2, 121071, -0.02099846, -0.03348131, 0.1561199, -1.017565, 3.832489, -8.642534 +MAG, 121080, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121080, -252, -103, 264, 0, 0, 0, 0, 0, 0 +CTUN, 121090, 202, 3, 205, 0, -3.38, 0.02, 0.00, 0.00, 0, -535 +ATT, 121090, 0.00, 38.22, 0.00, -7.08, 186.03, 185.17 +RCIN, 121090, 1503, 1504, 1066, 1510, 992, 993, 992, 992 +RCOU, 121091, 1477, 1210, 1347, 1470, 0, 0, 0, 0 +IMU, 121091, -0.05034822, -0.01953719, 0.1842046, -0.7499338, 5.104294, -9.055102 +IMU2, 121091, -0.01709401, -0.0121954, 0.1861634, -0.7011517, 5.239663, -9.118958 +IMU, 121110, -0.05976089, -0.002193406, 0.1802549, -0.8572232, 3.9787, -9.04588 +IMU2, 121110, -0.06748331, 0.0003022552, 0.1818627, -0.6699559, 4.444904, -9.159129 +IMU, 121130, 0.01801393, 0.0103279, 0.204475, -0.7500021, 3.72418, -8.935925 +IMU2, 121130, -0.001761513, 0.0184516, 0.1981543, -0.7524317, 3.699351, -8.842566 +IMU, 121151, -0.005898511, 0.007891577, 0.1947194, -0.6386346, 5.035808, -9.06135 +IMU2, 121151, 0.004354987, 0.01419768, 0.2038402, -0.4675694, 5.127364, -9.07618 +IMU, 121171, 0.0002183411, -0.01132716, 0.1659451, -0.7320893, 3.849106, -8.874701 +IMU2, 121171, -0.01285041, 0.007946525, 0.1646595, -0.5137414, 4.243353, -8.899722 +MAG, 121181, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121181, -253, -96, 265, 0, 0, 0, 0, 0, 0 +CTUN, 121190, 202, 3, 205, 0, -3.81, -0.09, 0.00, 0.00, 0, -588 +ATT, 121191, 0.00, 40.36, 0.00, -7.73, 186.03, 185.87 +RCIN, 121191, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 121191, 1478, 1210, 1347, 1469, 0, 0, 0, 0 +IMU, 121191, 0.092843, -0.03836537, 0.1610482, -0.6940202, 3.577932, -8.461497 +IMU2, 121191, 0.05429162, -0.03619827, 0.1553775, -0.6963459, 3.659739, -8.334767 +IMU, 121211, 0.06433752, -0.05266759, 0.1343393, -0.6084524, 5.149919, -8.673501 +IMU2, 121211, 0.09288288, -0.05164889, 0.1313345, -0.5080026, 5.179996, -8.874175 +IMU, 121230, 0.03791776, -0.05651593, 0.1058608, -0.5486184, 4.095959, -8.641464 +IMU2, 121230, 0.05110674, -0.0655244, 0.09527659, -0.4817779, 4.393464, -8.71265 +IMU, 121250, 0.09993546, -0.06153922, 0.09631094, -0.6709407, 3.353414, -8.26742 +IMU2, 121250, 0.09993496, -0.08427088, 0.07034772, -0.7777561, 3.474303, -8.320883 +GPS, 3, 56701400, 1777, 11, 1.42, 14.1105871, 100.6192289, -4.18, -1.76, 0.36, 307.17, 0.34, 121260 +IMU, 121270, 0.05859296, -0.05591209, 0.07309763, -0.7539316, 4.972761, -8.780079 +IMU2, 121270, 0.112511, -0.05399441, 0.06364261, -0.8079808, 4.945212, -9.07073 +MAG, 121280, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121280, -252, -90, 266, 0, 0, 0, 0, 0, 0 +CTUN, 121290, 202, 4, 206, 0, -4.27, 0.07, 0.00, 0.00, 0, -643 +ATT, 121290, 0.00, 42.77, 0.00, -8.26, 186.03, 186.02 +RCIN, 121290, 1503, 1504, 1066, 1511, 992, 993, 992, 992 +RCOU, 121291, 1469, 1210, 1357, 1467, 0, 0, 0, 0 +IMU, 121291, 0.01557366, -0.04349631, 0.03791127, -0.7796109, 4.425594, -8.901202 +IMU2, 121291, 0.002420507, -0.04010615, 0.03880623, -0.8042766, 4.805861, -8.904198 +IMU, 121310, 0.06451328, -0.005356286, 0.02903064, -0.8195554, 3.289773, -8.910854 +IMU2, 121310, 0.01479118, -0.01035682, 0.02570121, -0.745097, 3.478039, -8.730888 +IMU, 121330, 0.06417819, 0.03242825, 0.01252929, -0.726554, 4.36922, -9.017963 +IMU2, 121330, 0.05437393, 0.02619384, 0.02608481, -0.5429319, 4.367787, -8.798293 +IMU, 121351, -0.007522447, 0.0194338, -0.02716725, -0.6282805, 4.223436, -9.052505 +IMU2, 121351, -0.02760227, 0.01404008, -0.01095423, -0.5431106, 4.657491, -9.098605 +IMU, 121370, 0.00320599, 0.004876509, -0.03629232, -0.6270906, 3.472856, -8.903803 +IMU2, 121370, -0.04171788, -0.003047879, -0.02380037, -0.5739061, 3.632432, -8.730343 +MAG, 121380, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121380, -252, -88, 267, 0, 0, 0, 0, 0, 0 +CTUN, 121390, 202, 5, 207, 0, -4.77, -0.05, 0.00, 0.00, 0, -699 +ATT, 121390, 0.00, 45.10, 0.00, -8.21, 186.03, 185.99 +RCIN, 121391, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 121391, 1482, 1210, 1343, 1474, 0, 0, 0, 0 +IMU, 121391, 0.05880703, -0.01399893, -0.02942168, -0.4256033, 4.403307, -8.881502 +IMU2, 121391, 0.06849801, -0.03415, -0.02425819, -0.4892337, 4.223818, -8.873462 +IMU, 121410, 0.02562213, -0.07226893, -0.0410886, -0.4832932, 4.721781, -8.905303 +IMU2, 121410, 0.05810253, -0.08875823, -0.0400392, -0.4314137, 4.950359, -9.077115 +IMU, 121431, 0.06229687, -0.1324318, -0.04782156, -0.7991918, 3.440922, -8.741462 +IMU2, 121431, 0.06276852, -0.1461021, -0.06989937, -0.7439914, 3.720688, -8.723503 +GPS, 3, 56701600, 1777, 11, 1.42, 14.1105883, 100.6192289, -5.09, -1.84, 0.59, 307.17, 0.29, 121440 +IMU, 121451, 0.1490798, -0.1488709, -0.02702012, -0.5463187, 3.656263, -8.86001 +IMU2, 121451, 0.1484945, -0.1676642, -0.04668427, -0.5820877, 3.594651, -8.696804 +IMU, 121470, 0.1029804, -0.1246823, -0.0218427, -0.8332478, 4.741274, -9.364621 +IMU2, 121470, 0.114587, -0.1153868, -0.02902022, -0.7028095, 4.966683, -9.538031 +MAG, 121480, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121480, -251, -87, 266, 0, 0, 0, 0, 0, 0 +CTUN, 121490, 202, 6, 208, 0, -5.31, -0.05, 0.00, 0.00, 0, -758 +ATT, 121490, 0.00, 47.67, 0.00, -8.56, 186.03, 185.45 +RCIN, 121490, 1503, 1503, 1066, 1513, 992, 992, 993, 991 +RCOU, 121491, 1471, 1210, 1352, 1476, 0, 0, 0, 0 +IMU, 121491, 0.08115792, -0.07544769, -0.02822907, -0.9405177, 3.522126, -9.118261 +IMU2, 121491, 0.05419412, -0.07383133, -0.03218193, -0.8618495, 3.812317, -9.060167 +IMU, 121510, 0.1071171, -0.0386049, -0.02729775, -1.113194, 3.082066, -8.704291 +IMU2, 121510, 0.06770831, -0.03622537, -0.03478293, -1.091223, 3.12791, -8.528998 +IMU, 121530, 0.03567977, -0.01413561, -0.04531235, -1.443278, 4.552725, -8.982687 +IMU2, 121530, 0.05047039, 0.004182013, -0.03699343, -1.219386, 4.434219, -8.908154 +IMU, 121551, -0.04013235, -0.008773118, -0.07095362, -1.417964, 4.135907, -8.921514 +IMU2, 121551, -0.03453601, -0.00483096, -0.06854832, -1.276125, 4.35161, -8.969693 +IMU, 121570, -0.02967146, 0.009787638, -0.07290786, -1.370914, 3.309372, -8.690102 +IMU2, 121570, -0.05832895, 0.01062669, -0.06710832, -1.443031, 3.517159, -8.736757 +MAG, 121580, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121580, -250, -89, 271, 0, 0, 0, 0, 0, 0 +CTUN, 121590, 202, 6, 208, 0, -5.88, -0.10, 0.00, 0.00, 0, -820 +ATT, 121590, 0.00, 49.86, 0.00, -8.37, 186.03, 185.21 +RCIN, 121590, 1502, 1504, 1066, 1511, 992, 992, 992, 992 +RCOU, 121591, 1476, 1210, 1344, 1480, 0, 0, 0, 0 +IMU, 121591, -0.02757347, 0.0294423, -0.05909792, -1.096243, 4.440397, -8.679952 +IMU2, 121591, -0.00758215, 0.02412762, -0.06140231, -1.194004, 4.283955, -8.797016 +IMU, 121610, -0.09429762, 0.02681702, -0.06500387, -0.9874955, 4.754856, -8.733531 +IMU2, 121610, -0.06344227, 0.03087211, -0.04871991, -0.9020672, 4.939888, -8.996187 +IMU, 121631, -0.06606159, 0.02281857, -0.05465011, -1.079661, 3.327945, -8.583425 +IMU2, 121631, -0.08174419, 0.02244494, -0.05815076, -1.024986, 3.642867, -8.545488 +GPS, 3, 56701800, 1777, 11, 1.42, 14.1105878, 100.6192291, -6.25, -1.91, 0.60, 307.17, 0.24, 121640 +IMU, 121650, 0.01839513, 0.04204721, -0.02600512, -0.8462582, 3.601285, -8.641203 +IMU2, 121650, 0.01056895, 0.03521256, -0.02125915, -0.818854, 3.522696, -8.515017 +IMU, 121670, -0.03077001, 0.04736035, -0.02026004, -0.8456353, 4.641572, -9.148903 +IMU2, 121670, -0.02169579, 0.04633673, -0.003743624, -0.7486019, 4.781212, -9.114589 +MAG, 121680, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121680, -250, -91, 269, 0, 0, 0, 0, 0, 0 +CTUN, 121691, 202, 7, 209, 0, -6.5, -0.18, 0.00, 0.00, 0, -886 +ATT, 121691, 0.00, 51.70, 0.00, -8.14, 186.03, 185.17 +RCIN, 121691, 1502, 1504, 1066, 1510, 993, 992, 992, 992 +RCOU, 121691, 1470, 1210, 1358, 1474, 0, 0, 0, 0 +IMU, 121691, -0.07771251, 0.02968548, -0.02552048, -0.9043388, 3.779049, -8.955983 +IMU2, 121691, -0.09878742, 0.02695509, -0.009888405, -0.8761836, 4.086289, -8.845907 +IMU, 121710, -0.04189956, 0.005784884, -0.01106724, -0.7332675, 3.393383, -8.894102 +IMU2, 121710, -0.07817391, -0.006448158, -0.008062616, -0.6905575, 3.511649, -8.696216 +IMU, 121730, -0.0694017, -0.008493971, 0.005024078, -0.6506609, 4.78154, -9.152309 +IMU2, 121730, -0.06553825, -0.00347028, 0.008249216, -0.5448796, 4.852739, -9.028002 +IMU, 121751, -0.1175686, -0.03369805, 0.003058682, -0.7489314, 4.58316, -8.992105 +IMU2, 121751, -0.1176298, -0.04075162, 0.007223267, -0.5977722, 4.8961, -9.000126 +IMU, 121770, -0.07591401, -0.04934625, 0.02716188, -0.7722326, 3.533018, -8.607226 +IMU2, 121770, -0.1071531, -0.06876695, 0.0221575, -0.860487, 3.656599, -8.439167 +MAG, 121780, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121780, -250, -94, 268, 0, 0, 0, 0, 0, 0 +CTUN, 121790, 202, 8, 210, 0, -7.17, -0.02, 0.00, 0.00, 0, -956 +ATT, 121791, 0.00, 53.44, 0.00, -8.36, 186.03, 185.09 +RCIN, 121791, 1503, 1504, 1066, 1512, 993, 992, 992, 992 +RCOU, 121791, 1470, 1210, 1351, 1482, 0, 0, 0, 0 +IMU, 121791, -0.03569657, -0.04489939, 0.05315671, -0.683062, 4.60328, -8.839444 +IMU2, 121791, -0.01835087, -0.04410724, 0.0441317, -0.6592641, 4.600685, -8.794902 +IMU, 121812, -0.07915784, -0.05676742, 0.06521766, -0.7726045, 4.934319, -8.867061 +IMU2, 121812, -0.04549133, -0.05653759, 0.07307494, -0.6716157, 5.091639, -9.045763 +IMU, 121831, -0.05515839, -0.06218924, 0.06923807, -0.9756868, 3.531135, -8.607537 +IMU2, 121831, -0.07555605, -0.06555842, 0.06400412, -0.9615206, 3.891864, -8.677152 +GPS, 3, 56702000, 1777, 11, 1.42, 14.1105896, 100.6192277, -7.58, -2.24, 0.82, 307.17, 0.24, 121840 +IMU, 121851, 0.006148344, -0.05729671, 0.0793859, -0.915248, 3.608906, -8.406041 +IMU2, 121851, -0.0005983412, -0.06132001, 0.07801384, -0.9604326, 3.680307, -8.41481 +IMU, 121870, -0.0618696, -0.06896931, 0.06652715, -1.122185, 5.028658, -8.672603 +IMU2, 121870, -0.04224561, -0.06700486, 0.07326326, -1.135934, 5.076663, -8.667712 +MAG, 121880, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121880, -250, -92, 268, 0, 0, 0, 0, 0, 0 +CTUN, 121890, 202, 9, 211, 0, -7.87, -0.12, 0.00, 0.00, 0, -1029 +DU32, 7, 262265 +CURR, 121890, 211, 7533, 1520, 774, 5302, 24.88764 +ATT, 121891, 0.00, 55.20, 0.00, -8.83, 186.03, 185.02 +RCIN, 121891, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 121891, 1462, 1210, 1376, 1468, 0, 0, 0, 0 +IMU, 121891, -0.1195827, -0.08707174, 0.03897982, -1.245167, 4.473973, -8.750121 +IMU2, 121891, -0.1439454, -0.08654119, 0.05002877, -1.177456, 4.853792, -8.627576 +IMU, 121910, -0.06410708, -0.08155634, 0.03075948, -1.139516, 3.579407, -8.531755 +IMU2, 121910, -0.1025887, -0.07856144, 0.03022817, -1.043504, 3.709215, -8.446067 +IMU, 121930, -0.03685226, -0.046023, 0.02959816, -0.8666834, 4.709036, -8.900711 +IMU2, 121930, -0.03619458, -0.03355253, 0.03726036, -0.8113269, 4.741639, -8.918921 +IMU, 121950, -0.078436, -0.008894347, 0.01606823, -0.7706576, 4.957667, -9.027401 +IMU2, 121950, -0.05813078, -0.01296031, 0.0265865, -0.6881355, 5.186544, -9.147945 +IMU, 121970, -0.06828813, 0.009187583, 0.008056007, -0.8269079, 3.767218, -8.743578 +IMU2, 121970, -0.08200929, -0.002716393, -0.001969085, -0.8630761, 3.989529, -8.738843 +MAG, 121981, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 121981, -249, -92, 272, 0, 0, 0, 0, 0, 0 +CTUN, 121990, 202, 10, 212, 0, -8.61, -0.07, 0.00, 0.00, 0, -1106 +ATT, 121991, 0.00, 57.13, 0.00, -9.02, 186.03, 184.97 +RCIN, 121991, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 121991, 1465, 1210, 1354, 1488, 0, 0, 0, 0 +IMU, 121991, 0.002302695, 0.01571424, 0.01841389, -0.7213976, 3.691874, -8.681678 +IMU2, 121991, 0.002069702, 0.004493001, 0.01233434, -0.6994061, 3.749587, -8.580477 +IMU, 122011, -0.032697, -0.009847734, 0.02024528, -0.7591546, 4.843484, -8.790403 +IMU2, 122011, -0.02739179, -0.00990784, 0.02112232, -0.7023755, 4.838625, -8.968547 +IMU, 122030, -0.05690586, -0.04435914, 0.01023224, -1.061548, 4.289976, -8.732267 +IMU2, 122030, -0.07565731, -0.03678148, 0.009381384, -0.9615335, 4.477002, -8.613004 +GPS, 3, 56702200, 1777, 11, 1.42, 14.1105889, 100.6192284, -9.08, -2.51, 0.73, 307.17, 0.25, 122040 +IMU, 122051, 0.003881304, -0.06727058, 0.01481948, -1.075461, 3.462028, -8.566529 +IMU2, 122051, -0.04820433, -0.06953205, 0.01000093, -0.9898486, 3.607263, -8.333688 +IMU, 122070, 0.04770567, -0.05176987, 0.02199043, -1.188159, 4.52277, -8.909946 +IMU2, 122070, 0.04646444, -0.04358186, 0.02178239, -1.025572, 4.390664, -8.911444 +MAG, 122080, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122080, -249, -91, 272, 0, 0, 0, 0, 0, 0 +CTUN, 122090, 202, 11, 213, 0, -9.4, -0.01, 0.00, 0.00, 0, -1185 +ATT, 122091, 0.00, 59.07, 0.00, -9.26, 186.03, 184.78 +RCIN, 122091, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 122091, 1463, 1210, 1361, 1488, 0, 0, 0, 0 +IMU, 122091, 0.008684168, -0.03444017, 0.01463366, -1.160435, 5.125741, -8.858491 +IMU2, 122091, 0.04037465, -0.02676931, 0.0118823, -1.081223, 5.248929, -8.895741 +IMU, 122110, -0.0118789, -0.005109809, -0.0004186679, -1.036672, 4.143998, -8.652293 +IMU2, 122110, -0.03123979, -0.00184042, 0.003106214, -1.059628, 4.430539, -8.752041 +IMU, 122130, 0.04423196, 0.03479919, 0.005300786, -0.9004015, 3.708893, -8.392819 +IMU2, 122130, 0.03209332, 0.02489637, 0.001017715, -0.9064125, 3.836483, -8.134818 +IMU, 122150, 0.01112618, 0.03823759, -0.000853264, -0.8765823, 5.147348, -8.710326 +IMU2, 122150, 0.02583698, 0.02285937, 0.001029715, -0.7987676, 5.313918, -8.726312 +IMU, 122170, -0.06274395, 0.02002138, -0.01225873, -1.054749, 4.885548, -8.851444 +IMU2, 122170, -0.05165192, 0.008100666, -0.007937828, -0.9554255, 5.094442, -9.001105 +MAG, 122180, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122180, -249, -92, 276, 0, 0, 0, 0, 0, 0 +CTUN, 122190, 202, 11, 213, 0, -10.24, -0.01, 0.00, 0.00, 0, -1266 +ATT, 122190, 0.00, 61.23, 0.00, -9.21, 186.03, 184.81 +RCIN, 122190, 1503, 1504, 1066, 1511, 992, 993, 992, 992 +RCOU, 122191, 1460, 1210, 1368, 1483, 0, 0, 0, 0 +IMU, 122191, -0.03335413, -0.006273054, -0.01395409, -0.9514481, 3.449074, -8.394053 +IMU2, 122191, -0.06320534, -0.01489603, -0.02269921, -1.043381, 3.720319, -8.285451 +IMU, 122210, 0.007123085, -0.007436022, -0.004063399, -1.167343, 3.788215, -8.70122 +IMU2, 122210, 0.008492772, -0.01309894, -0.006927872, -1.172566, 3.858126, -8.676165 +IMU, 122231, -0.02977273, -0.01040551, -0.009850758, -1.1488, 4.953833, -9.023399 +IMU2, 122231, -0.01668128, -0.003763104, -0.00811041, -1.078081, 5.047722, -9.04293 +GPS, 3, 56702400, 1777, 11, 1.42, 14.1105891, 100.6192297, -10.76, -2.63, 0.48, 307.17, 0.18, 122240 +IMU, 122251, -0.05438031, -0.01711147, -0.02221768, -1.308094, 4.33621, -9.043341 +IMU2, 122251, -0.07204317, -0.01281004, -0.0203111, -1.283326, 4.681406, -9.039665 +IMU, 122270, 0.02242573, -0.01196945, -0.01283783, -1.142088, 3.63048, -8.583914 +IMU2, 122270, -0.01180387, -0.01737062, -0.01285181, -1.009188, 3.762892, -8.387712 +MAG, 122280, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122280, -249, -90, 275, 0, 0, 0, 0, 0, 0 +CTUN, 122290, 202, 9, 211, 0, -11.12, 0.06, 0.00, 0.00, 0, -1350 +ATT, 122291, 0.00, 63.12, 0.00, -9.24, 186.03, 184.75 +RCIN, 122291, 1503, 1504, 1066, 1512, 992, 992, 993, 992 +RCOU, 122291, 1461, 1210, 1354, 1493, 0, 0, 0, 0 +IMU, 122291, 0.03622176, -0.006102286, 0.001780076, -1.153394, 4.755993, -8.890806 +IMU2, 122291, 0.05048987, -0.00429396, 0.000281834, -1.107693, 4.829413, -8.898783 +IMU, 122310, -0.03138454, 0.01024403, 0.00281307, -0.9730268, 5.28271, -8.90858 +IMU2, 122310, -0.007045921, 0.009053642, 0.0006874755, -0.962357, 5.411571, -9.112842 +IMU, 122330, -0.04658844, 0.02031222, 0.008476142, -0.9500186, 4.177492, -8.716382 +IMU2, 122330, -0.06623707, 0.01624957, 0.00215173, -0.9130601, 4.326265, -8.791666 +IMU, 122350, 0.02190925, 0.04098757, 0.02101608, -0.7856493, 3.928062, -8.694594 +IMU2, 122350, 0.0177686, 0.03405596, 0.01627801, -0.7156587, 4.019731, -8.621119 +IMU, 122370, 0.01408637, 0.02990638, 0.01983906, -0.7626853, 4.889226, -8.908115 +IMU2, 122370, 0.02323013, 0.02303928, 0.02519725, -0.65425, 5.042627, -8.974091 +MAG, 122380, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122380, -250, -93, 275, 0, 0, 0, 0, 0, 0 +CTUN, 122390, 201, 7, 208, 0, -12.05, -0.13, 0.00, 0.00, 0, -1437 +ATT, 122391, 0.00, 65.32, 0.00, -9.23, 186.03, 184.85 +RCIN, 122391, 1502, 1504, 1065, 1512, 992, 993, 992, 992 +RCOU, 122391, 1447, 1210, 1367, 1485, 0, 0, 0, 0 +IMU, 122391, -0.01856238, 0.01155375, 0.007352598, -1.078748, 4.385458, -8.920555 +IMU2, 122391, -0.02345277, 0.01205162, 0.009039434, -0.9615821, 4.55481, -8.981088 +IMU, 122411, 0.02631622, -0.00988289, 0.008902208, -0.9994018, 3.242879, -8.599323 +IMU2, 122411, -0.01811987, -0.01513148, 0.01482785, -0.9375136, 3.423377, -8.382448 +IMU, 122431, 0.05263358, -0.0171361, 0.01633298, -1.193131, 4.200058, -8.936512 +IMU2, 122431, 0.04649306, -0.02062378, 0.01986467, -1.131315, 4.079874, -8.855522 +GPS, 3, 56702600, 1777, 11, 1.42, 14.1105903, 100.6192298, -12.63, -2.77, 0.63, 307.17, 0.17, 122440 +IMU, 122451, 0.0140443, -0.02990134, 0.004550496, -0.9364103, 4.809994, -8.906095 +IMU2, 122451, 0.01753106, -0.03320815, 0.01385125, -0.8055423, 4.925331, -8.899138 +IMU, 122470, -0.004773146, -0.02913674, -0.006013922, -0.8678269, 3.999219, -8.889067 +IMU2, 122470, -0.02778263, -0.02496766, -0.01545118, -0.8308361, 4.192219, -8.786569 +MAG, 122480, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122480, -249, -90, 274, 0, 0, 0, 0, 0, 0 +CTUN, 122490, 201, 5, 206, 0, -13.03, 0.06, 0.00, 0.00, 0, -1527 +ATT, 122491, 0.00, 67.38, 0.00, -9.36, 186.03, 184.81 +RCIN, 122491, 1503, 1504, 1065, 1511, 992, 993, 992, 992 +RCOU, 122491, 1451, 1210, 1350, 1494, 0, 0, 0, 0 +IMU, 122491, 0.06861667, -0.004471242, 0.008337259, -0.7006652, 3.717836, -8.38571 +IMU2, 122491, 0.06342209, -0.001022255, -0.002619893, -0.7901291, 3.811511, -8.145758 +IMU, 122510, 0.04312638, 0.0005741902, 0.0179146, -0.7160525, 5.168837, -8.605449 +IMU2, 122510, 0.06373466, -0.006553112, 0.0250224, -0.7511097, 5.274057, -8.670987 +IMU, 122530, -0.01540888, -0.004825659, 0.002204723, -0.806651, 5.053179, -8.675108 +IMU2, 122530, -0.005093042, -0.007481806, 0.003005533, -0.597367, 5.274435, -8.689487 +IMU, 122551, 0.02013652, -0.02100117, -0.002069383, -0.7128795, 3.550096, -8.490668 +IMU2, 122551, -0.01253255, -0.02716918, -0.008947864, -0.6949553, 3.860195, -8.341972 +IMU, 122571, 0.07636531, -0.007831536, 0.006632429, -0.9587609, 4.190867, -8.878709 +IMU2, 122571, 0.07930057, -0.008341465, 0.004310671, -0.8769429, 4.280209, -8.890991 +MAG, 122580, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122580, -249, -90, 276, 0, 0, 0, 0, 0, 0 +CTUN, 122590, 202, 4, 206, 0, -14.05, 0.00, 0.00, 0.00, 0, -1621 +ATT, 122590, 0.00, 69.79, 0.00, -9.41, 186.03, 184.70 +RCIN, 122590, 1503, 1504, 1066, 1512, 992, 992, 993, 991 +RCOU, 122591, 1446, 1210, 1357, 1492, 0, 0, 0, 0 +IMU, 122591, 0.04495281, -0.02540707, -0.002348981, -0.9964892, 4.840359, -8.991516 +IMU2, 122591, 0.04751647, -0.02183984, 0.002378118, -0.9003638, 4.997673, -9.064214 +IMU, 122610, 0.02525352, -0.03766789, -0.02012208, -1.167211, 4.119825, -9.052484 +IMU2, 122610, -0.007243382, -0.03379039, -0.02374217, -1.067716, 4.457182, -8.945318 +IMU, 122630, 0.1114313, -0.02686167, -0.02046297, -0.8889951, 3.291665, -8.514625 +IMU2, 122630, 0.0849297, -0.02732699, -0.03086705, -0.869517, 3.407592, -8.2761 +GPS, 3, 56702800, 1777, 11, 1.42, 14.1105914, 100.6192285, -14.69, -2.93, 0.81, 307.17, 0.19, 122640 +IMU, 122650, 0.1145958, -0.02323749, -0.02105515, -1.141542, 4.44119, -8.681067 +IMU2, 122650, 0.127644, -0.01699994, -0.02556098, -1.030947, 4.481464, -8.789151 +IMU, 122670, 0.03517856, -0.0238872, -0.0288299, -1.046345, 4.968502, -8.407017 +IMU2, 122670, 0.05933151, -0.01876437, -0.02977771, -1.03531, 5.06221, -8.689642 +MAG, 122681, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122681, -249, -89, 275, 0, 0, 0, 0, 0, 0 +CTUN, 122690, 202, 2, 204, 0, -15.13, -0.04, 0.00, 0.00, 0, -1716 +ATT, 122690, 0.00, 72.06, 0.00, -9.40, 186.03, 184.54 +RCIN, 122690, 1503, 1504, 1066, 1512, 992, 993, 992, 992 +RCOU, 122690, 1443, 1210, 1363, 1485, 0, 0, 0, 0 +IMU, 122690, 0.0182506, -0.02854822, -0.02927819, -0.8890297, 3.755622, -8.324371 +IMU2, 122690, 0.004633091, -0.03717333, -0.03719326, -0.8840256, 3.898454, -8.318209 +IMU, 122710, 0.06055415, -0.01846198, -0.01486684, -1.003161, 4.097819, -8.528645 +IMU2, 122710, 0.06757861, -0.02333758, -0.01925209, -0.9234318, 4.116952, -8.428158 +IMU, 122730, 0.02730548, -0.02525217, -0.01828047, -0.9285709, 4.971291, -8.773566 +IMU2, 122730, 0.05491648, -0.02577643, -0.01903021, -0.8362849, 4.997852, -8.799834 +IMU, 122750, -0.0157297, -0.04595441, -0.02119506, -1.166816, 3.87536, -9.001847 +IMU2, 122750, -0.03096906, -0.043933, -0.0303205, -1.137803, 4.31802, -9.101017 +IMU, 122770, 0.05157507, -0.03840284, -0.004578917, -1.124917, 3.490322, -8.855597 +IMU2, 122770, 0.008811887, -0.03453828, -0.00965735, -1.047438, 3.456508, -8.781701 +MAG, 122780, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122780, -248, -90, 277, 0, 0, 0, 0, 0, 0 +CTUN, 122791, 201, 0, 200, 0, -16.25, 0.08, 0.00, 0.00, 0, -1814 +ATT, 122791, 0.00, 74.49, 0.00, -9.40, 186.03, 184.30 +RCIN, 122791, 1503, 1504, 1065, 1512, 992, 992, 993, 992 +RCOU, 122791, 1440, 1210, 1351, 1495, 0, 0, 0, 0 +IMU, 122791, 0.04668631, -0.01971505, 0.0117337, -1.083549, 4.885886, -9.28522 +IMU2, 122791, 0.03990805, -0.02191106, 0.02344361, -1.181573, 4.499229, -9.117123 +IMU, 122810, -0.005991513, -0.02654248, 0.0005402497, -1.162072, 4.657893, -8.969583 +IMU2, 122810, 0.004218087, -0.0246352, 0.008486184, -1.042369, 4.872105, -8.906899 +IMU, 122830, -0.002959201, -0.03814752, 0.009658227, -0.9295572, 3.391807, -8.428908 +IMU2, 122830, -0.03321973, -0.05327644, 0.007764227, -0.9369167, 3.699824, -8.500721 +GPS, 3, 56703000, 1777, 11, 1.42, 14.1105915, 100.6192281, -16.94, -2.97, 0.74, 307.17, 0.15, 122840 +IMU, 122851, 0.04205284, -0.04130592, 0.02063645, -1.024873, 4.143146, -8.745243 +IMU2, 122851, 0.02894138, -0.04289242, 0.0229667, -0.9539324, 4.064108, -8.557685 +IMU, 122871, 0.02165997, -0.05586403, 0.01523274, -0.9718668, 4.861984, -8.856992 +IMU2, 122871, 0.03319605, -0.05907867, 0.01774855, -0.861238, 5.052306, -8.872653 +MAG, 122880, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122880, -248, -89, 277, 0, 0, 0, 0, 0, 0 +CTUN, 122890, 201, -2, 199, 0, -17.42, -0.16, 0.00, 0.00, 0, -1914 +DU32, 7, 262265 +CURR, 122890, 199, 9605, 1516, 720, 5322, 26.96793 +ATT, 122890, 0.00, 76.57, 0.00, -9.54, 186.03, 184.09 +RCIN, 122890, 1503, 1503, 1065, 1512, 993, 992, 992, 992 +RCOU, 122891, 1432, 1210, 1365, 1484, 0, 0, 0, 0 +IMU, 122891, -0.007804217, -0.05675782, 0.005777831, -1.1746, 3.877182, -8.864441 +IMU2, 122891, -0.02123788, -0.06336053, 0.007091075, -1.095763, 4.398545, -8.705472 +IMU, 122910, 0.05119922, -0.0334957, 0.01321835, -1.060874, 3.111233, -8.731457 +IMU2, 122910, 0.02617498, -0.04357101, 0.005456061, -1.087821, 3.203025, -8.434931 +IMU, 122930, 0.03337347, -0.03098672, 0.02182439, -1.253675, 4.511073, -9.01137 +IMU2, 122930, 0.02944102, -0.0465575, 0.02412766, -1.272482, 4.524562, -9.087445 +IMU, 122950, -0.04635703, -0.04162553, 0.01389792, -1.362108, 4.85456, -9.083702 +IMU2, 122950, -0.03388542, -0.04018033, 0.0196671, -1.263258, 5.10949, -9.24315 +IMU, 122970, -0.0459366, -0.03881286, 0.02733227, -0.91834, 3.459977, -8.580665 +IMU2, 122970, -0.07276607, -0.0497546, 0.01617003, -1.132074, 3.751625, -8.666393 +MAG, 122980, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 122980, -247, -87, 282, 0, 0, 0, 0, 0, 0 +CTUN, 122990, 201, -3, 198, 0, -18.65, -0.14, 0.00, 0.00, 0, -2016 +ATT, 122991, 0.00, 78.73, 0.00, -9.70, 186.03, 183.92 +RCIN, 122991, 1504, 1503, 1065, 1512, 992, 993, 992, 992 +RCOU, 122991, 1431, 1210, 1352, 1498, 0, 0, 0, 0 +IMU, 122991, -0.006361092, -0.007757459, 0.04190663, -0.8575115, 3.887897, -8.736903 +IMU2, 122991, -0.007283093, -0.005497419, 0.04190893, -0.8789358, 3.802011, -8.658555 +IMU, 123011, -0.03761484, 0.001422234, 0.03066221, -0.7555878, 4.52242, -8.84866 +IMU2, 123011, -0.03014749, 0.009491289, 0.04264164, -0.565872, 4.678783, -8.802482 +IMU, 123030, -0.0804902, -0.003337141, 0.01283955, -0.9383581, 3.837611, -9.047167 +IMU2, 123030, -0.1015471, -0.002662386, 0.02054749, -0.8180293, 4.280423, -8.977139 +GPS, 3, 56703200, 1777, 10, 1.99, 14.1105928, 100.6192256, -19.41, -3.09, 0.79, 307.17, 0.02, 123040 +IMU, 123051, -0.00925337, -0.01879727, 0.01002658, -1.034958, 3.221633, -8.65417 +IMU2, 123051, -0.05385352, -0.03260186, 0.01489383, -0.8560534, 3.316065, -8.373421 +IMU, 123070, 0.007581545, -0.06083293, 0.011324, -1.310547, 4.530807, -8.807231 +IMU2, 123070, -0.01088518, -0.06687832, 0.01253115, -1.255787, 4.396515, -8.751355 +MAG, 123080, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 123080, -247, -85, 281, 0, 0, 0, 0, 0, 0 +CTUN, 123090, 200, -4, 196, 0, -19.93, -0.07, 0.00, 0.00, 0, -2120 +ATT, 123090, 0.00, 80.52, 0.00, -9.86, 186.03, 183.75 +RCIN, 123090, 1503, 1504, 1064, 1512, 993, 992, 992, 992 +RCOU, 123090, 1432, 1210, 1366, 1480, 0, 0, 0, 0 +IMU, 123090, -0.05633277, -0.09600684, -0.002741202, -1.433153, 4.885421, -8.749609 +IMU2, 123090, -0.03208958, -0.09311152, 0.002115879, -1.256032, 5.091901, -8.991921 +IMU, 123110, -0.05784208, -0.1028306, 0.008563498, -1.126471, 3.881011, -8.431804 +IMU2, 123110, -0.06950248, -0.1186887, -0.003204012, -1.269523, 4.147892, -8.543129 +IMU, 123130, -0.007441917, -0.07037114, 0.02949282, -1.075972, 4.275474, -8.727318 +IMU2, 123130, 0.008265711, -0.06806241, 0.02028815, -1.029, 4.310304, -8.553785 +IMU, 123151, -0.0177033, -0.05709484, 0.03276781, -0.9953036, 4.9616, -8.70571 +IMU2, 123151, 0.0006425064, -0.06607085, 0.03188055, -0.9018078, 5.174588, -8.853257 +IMU, 123171, -0.05604141, -0.04039257, 0.02268425, -1.034639, 4.129023, -8.852354 +IMU2, 123171, -0.07004133, -0.04579435, 0.02509725, -0.9386121, 4.524492, -8.857354 +MAG, 123180, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 123180, -246, -88, 285, 0, 0, 0, 0, 0, 0 +CTUN, 123190, 196, -4, 192, 0, -21.25, -0.10, 0.00, 0.00, 0, -2228 +ATT, 123191, 0.00, 82.69, 0.00, -10.03, 186.03, 183.42 +RCIN, 123191, 1503, 1504, 1059, 1513, 992, 992, 993, 991 +RCOU, 123191, 1422, 1210, 1352, 1496, 0, 0, 0, 0 +IMU, 123191, 0.01603493, -0.01456985, 0.02618672, -1.036602, 3.026481, -8.615407 +IMU2, 123191, -0.01018874, -0.02282895, 0.02382831, -0.9618877, 3.121562, -8.264887 +IMU, 123210, 0.04186422, -0.01402949, 0.02184305, -1.403003, 4.40767, -8.990783 +IMU2, 123210, 0.02457519, -0.01076302, 0.02780118, -1.301492, 4.164771, -8.988515 +IMU, 123231, -0.007427176, -0.02538719, 0.005722054, -1.356934, 5.035402, -8.767863 +IMU2, 123231, 0.03727297, -0.02793521, 0.01518698, -1.369517, 5.012219, -8.98542 +IMU, 123250, -0.02329571, -0.04034476, -0.003374385, -1.12658, 3.892623, -8.387579 +IMU2, 123250, -0.04134599, -0.04840412, -0.01062868, -1.27392, 4.201605, -8.411218 +GPS, 3, 56703400, 1777, 10, 1.99, 14.1105939, 100.6192217, -22.34, -3.28, 1.10, 307.17, -0.05, 123261 +IMU, 123270, 0.02410541, -0.03318143, 0.002393056, -1.077008, 3.952428, -8.335003 +IMU2, 123270, 0.03607264, -0.03319681, -0.00251738, -1.014629, 3.88343, -8.161181 +MAG, 123280, 0, 0, 0, -86, 10, 139, 0, 0, 0 +MAG2, 123280, -245, -88, 288, 0, 0, 0, 0, 0, 0 +CTUN, 123290, 192, -2, 190, 0, -22.63, 0.03, 0.00, 0.00, 0, -2338 +ATT, 123290, 0.00, 84.78, 0.00, -10.10, 186.03, 183.25 +RCIN, 123290, 1503, 1504, 1055, 1512, 992, 993, 992, 992 +RCOU, 123291, 1422, 1210, 1354, 1489, 0, 0, 0, 0 +IMU, 123291, -0.004204655, -0.03553256, 0.002285741, -0.9683303, 4.985352, -8.741308 +IMU2, 123291, 0.01387082, -0.04162084, 0.003848672, -0.934172, 5.080159, -8.852489 +IMU, 123310, -0.05011934, -0.02450115, -0.006815219, -1.167364, 4.529291, -9.161108 +IMU2, 123310, -0.05317152, -0.01543067, -0.01260214, -1.018244, 4.98447, -9.10153 +IMU, 123330, 0.01233228, -0.01790007, 0.007976498, -1.262405, 3.584874, -8.746932 +IMU2, 123330, -0.03461868, -0.02196648, 0.00218105, -1.192196, 3.702729, -8.605768 +IMU, 123351, 0.03216823, -0.01323537, 0.02116856, -1.408839, 4.620263, -8.955957 +IMU2, 123351, 0.04534578, -0.008687048, 0.02165538, -1.38984, 4.628468, -9.112564 +IMU, 123370, -0.006822811, -0.02134612, 0.03136308, -1.161258, 5.343009, -8.82267 +IMU2, 123370, 0.002882307, -0.02342615, 0.04492819, -1.121574, 5.594732, -8.972331 +MAG, 123380, -389, 0, 120, -86, 10, 139, 0, 0, 0 +MAG2, 123380, -248, -85, 293, 0, 0, 0, 0, 0, 0 +CTUN, 123390, 0, 0, 0, 0, -24.05, 0.01, 0.00, 0.00, 0, -2452 +ATT, 123390, 0.00, 87.08, 0.00, -10.19, 183.11, 183.11 +RCIN, 123390, 1503, 1504, 1029, 1512, 993, 992, 992, 992 +RCOU, 123391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123391, 0.06364304, -0.02998074, 0.04327789, -1.078878, 3.936439, -8.502667 +IMU2, 123391, 0.02994697, -0.03528893, 0.0402716, -1.030933, 4.524731, -8.490604 +IMU, 123410, 0.1740303, -0.01399591, 0.05601315, -1.144966, 4.121819, -8.575219 +IMU2, 123410, 0.1721802, -0.01560627, 0.0592695, -1.066844, 4.092791, -8.54703 +IMU, 123431, 0.2091615, 0.005030133, 0.04947862, -1.206944, 5.246109, -8.892337 +IMU2, 123431, 0.2109154, 0.005344914, 0.05290591, -1.040338, 5.229698, -8.850446 +GPS, 3, 56703600, 1777, 10, 1.99, 14.1105938, 100.6192191, -24.92, -3.57, 1.12, 307.17, -0.06, 123440 +IMU, 123450, 0.2402408, 0.006070867, 0.02618402, -1.333677, 4.377191, -8.577825 +IMU2, 123450, 0.2374859, 0.008448107, 0.01672656, -1.263673, 4.738169, -8.855966 +IMU, 123470, 0.3261618, 0.05189636, 0.03595006, -1.237825, 4.434056, -8.452693 +IMU2, 123470, 0.3241948, 0.04329581, 0.01910707, -1.267649, 4.501615, -8.286452 +MAG, 123480, -386, 4, 121, -86, 10, 139, 0, 0, 0 +MAG2, 123480, -251, -78, 300, 0, 0, 0, 0, 0, 0 +CTUN, 123490, 0, 0, 0, 0, -25.52, 0.06, 0.00, 0.00, 0, -2567 +ATT, 123491, 0.00, 88.16, 0.00, -10.44, 183.23, 183.23 +RCIN, 123491, 1503, 1504, 1025, 1512, 993, 992, 992, 992 +RCOU, 123491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123491, 0.3141815, 0.057494, 0.02147848, -1.165875, 5.481636, -8.371037 +IMU2, 123491, 0.3496366, 0.04604575, 0.01336089, -1.27862, 5.621341, -8.719451 +IMU, 123510, 0.2994435, 0.09047022, -0.004001251, -1.055723, 3.980027, -8.846885 +IMU2, 123510, 0.2601603, 0.09827958, -0.01865278, -0.8655055, 4.524077, -8.862925 +IMU, 123530, 0.4126796, 0.09492038, 0.005398965, -1.074023, 3.98321, -8.364786 +IMU2, 123530, 0.4136848, 0.08696859, -0.008606298, -1.172132, 3.993513, -8.453793 +IMU, 123551, 0.4051137, 0.1332554, -0.03710408, -0.6812722, 4.670036, -8.760718 +IMU2, 123551, 0.4269657, 0.1267618, -0.03439674, -0.4568813, 4.686737, -8.610561 +IMU, 123570, 0.4215851, 0.09739988, -0.07591829, -1.010088, 3.276149, -8.845945 +IMU2, 123570, 0.3767421, 0.08279899, -0.0791134, -1.104948, 3.731874, -8.888198 +MAG, 123580, -389, 8, 120, -86, 10, 139, 0, 0, 0 +MAG2, 123580, -252, -72, 298, 0, 0, 0, 0, 0, 0 +CTUN, 123590, 0, 0, 0, 0, -27.04, -0.09, 0.00, 0.00, 0, -2681 +ATT, 123591, 0.00, 89.83, 0.00, -10.25, 183.79, 183.79 +RCIN, 123591, 1503, 1504, 1025, 1511, 993, 992, 992, 992 +RCOU, 123591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123591, 0.5042669, 0.06847307, -0.1039283, -1.164707, 4.365116, -8.962437 +IMU2, 123591, 0.5241218, 0.05400496, -0.1229258, -1.100339, 4.325109, -9.034883 +IMU, 123611, 0.4254343, 0.003325313, -0.1488243, -0.9980092, 4.561246, -9.376345 +IMU2, 123611, 0.4197843, -0.01285127, -0.1527239, -0.9976134, 4.814602, -9.504983 +IMU, 123630, 0.4619878, -0.05176982, -0.1619964, -1.017899, 3.049832, -8.859125 +IMU2, 123630, 0.4475812, -0.08639494, -0.172916, -1.172056, 3.179707, -8.767544 +GPS, 3, 56703800, 1777, 10, 1.99, 14.1105934, 100.6192181, -27.97, -3.76, 0.96, 307.17, -0.07, 123640 +IMU, 123650, 0.5051523, -0.08687326, -0.1909184, -1.003504, 3.458323, -9.278653 +IMU2, 123650, 0.5071556, -0.09606574, -0.2023271, -0.9360711, 3.524735, -9.306278 +IMU, 123670, 0.5013497, -0.07022492, -0.2346525, -1.307083, 2.57237, -8.97613 +IMU2, 123670, 0.4701032, -0.08594255, -0.235279, -1.209136, 2.716988, -8.800669 +MAG, 123680, -390, 14, 119, -86, 10, 139, 0, 0, 0 +MAG2, 123680, -252, -68, 296, 0, 0, 0, 0, 0, 0 +CTUN, 123690, 0, 0, 0, 0, -28.61, -0.17, 0.00, 0.00, 0, -2790 +ATT, 123690, 0.00, 92.01, 0.00, -9.26, 183.54, 183.54 +RCIN, 123690, 1503, 1504, 1025, 1512, 992, 993, 992, 992 +RCOU, 123690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123690, 0.4489642, -0.04485573, -0.2332839, -1.651662, 3.190909, -9.793008 +IMU2, 123690, 0.4295168, -0.04002207, -0.2401926, -1.733123, 3.407183, -9.776469 +IMU, 123710, 0.3637629, 0.02169627, -0.2422724, -1.193628, 3.140423, -9.334496 +IMU2, 123710, 0.3667182, 0.01352428, -0.2361846, -1.131999, 3.433488, -9.388017 +IMU, 123730, 0.3914517, 0.03084301, -0.2153358, -1.62751, 2.532774, -9.055321 +IMU2, 123730, 0.3825119, 0.03018438, -0.2117138, -1.74586, 2.583606, -9.08246 +IMU, 123750, 0.3430227, 0.05968434, -0.231509, -1.218585, 2.809718, -9.588828 +IMU2, 123750, 0.3392984, 0.04860977, -0.2146413, -1.142422, 2.89634, -9.541632 +IMU, 123770, 0.3200338, 0.08979329, -0.2152766, -1.864401, 2.358871, -9.86891 +IMU2, 123770, 0.3100983, 0.09051335, -0.212791, -1.864153, 2.496719, -9.69369 +MAG, 123780, -389, 13, 119, -86, 10, 139, 0, 0, 0 +MAG2, 123780, -253, -69, 298, 0, 0, 0, 0, 0, 0 +CTUN, 123790, 0, 0, 0, 0, -30.21, -0.22, 0.00, 0.00, 0, -2891 +ATT, 123791, 0.00, 93.44, 0.00, -8.07, 183.94, 183.94 +RCIN, 123791, 1504, 1503, 1026, 1512, 992, 993, 992, 992 +RCOU, 123791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123791, 0.2545149, 0.1088862, -0.1988601, -1.75923, 3.038763, -9.624741 +IMU2, 123791, 0.2604816, 0.103239, -0.1905349, -1.727675, 3.250914, -9.708367 +IMU, 123811, 0.2531273, 0.1417051, -0.1693949, -1.836405, 1.869325, -9.742012 +IMU2, 123811, 0.2308969, 0.1316001, -0.1643212, -1.822122, 2.134659, -9.479888 +IMU, 123830, 0.2553932, 0.1724485, -0.1363845, -1.478089, 2.452891, -9.529084 +IMU2, 123830, 0.2528834, 0.1615262, -0.1208059, -1.4253, 2.544604, -9.507276 +GPS, 3, 56704000, 1777, 10, 1.99, 14.1105921, 100.6192181, -31.19, -3.81, 0.83, 307.17, -0.13, 123840 +IMU, 123851, 0.2541674, 0.2064775, -0.1301521, -1.63655, 1.96719, -9.497205 +IMU2, 123851, 0.2528173, 0.1962845, -0.123991, -1.488159, 2.069249, -9.393333 +IMU, 123870, 0.2407233, 0.2296336, -0.08382627, -1.856719, 2.486893, -9.557608 +IMU2, 123870, 0.2521844, 0.2271065, -0.07768974, -1.866193, 2.51859, -9.706574 +MAG, 123880, -390, 12, 116, -86, 10, 139, 0, 0, 0 +MAG2, 123880, -254, -70, 294, 0, 0, 0, 0, 0, 0 +CTUN, 123890, 0, 0, 0, 0, -31.85, -0.10, 0.00, 0.00, 0, -2989 +DU32, 7, 262233 +CURR, 123890, 0, 10381, 1534, 120, 5306, 28.0594 +ATT, 123891, 0.00, 94.15, 0.00, -7.47, 185.13, 185.13 +RCIN, 123891, 1504, 1503, 1026, 1512, 992, 993, 992, 992 +RCOU, 123891, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123891, 0.2020765, 0.2561394, -0.07781245, -1.764841, 1.619954, -9.576117 +IMU2, 123891, 0.1848075, 0.2552181, -0.07447792, -1.818112, 1.875732, -9.38927 +IMU, 123910, 0.187288, 0.2805591, -0.06115693, -1.148018, 2.31106, -9.739393 +IMU2, 123910, 0.1735553, 0.2735142, -0.0539551, -1.108592, 2.448464, -9.703372 +IMU, 123930, 0.1577166, 0.2954369, -0.0731931, -0.9464693, 2.431584, -9.972739 +IMU2, 123930, 0.1559664, 0.2843863, -0.06917759, -0.8396049, 2.616656, -9.84715 +IMU, 123951, 0.1835432, 0.271976, -0.07022163, -1.025819, 2.705842, -9.451896 +IMU2, 123951, 0.191771, 0.259645, -0.06806202, -0.9860085, 2.871177, -9.48293 +IMU, 123970, 0.1963143, 0.2401258, -0.08654428, -0.6226766, 2.128463, -9.469437 +IMU2, 123970, 0.1839154, 0.2270137, -0.08114198, -0.5798436, 2.362175, -9.477533 +MAG, 123980, -395, 12, 107, -86, 10, 139, 0, 0, 0 +MAG2, 123980, -258, -70, 286, 0, 0, 0, 0, 0, 0 +CTUN, 123990, 0, 0, 0, 0, -33.51, -0.09, 0.00, 0.00, 0, -3089 +ATT, 123990, 0.00, 94.55, 0.00, -7.19, 186.67, 186.67 +RCIN, 123990, 1503, 1504, 1025, 1513, 992, 992, 993, 991 +RCOU, 123991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 123991, 0.2312638, 0.2121029, -0.06917498, -0.5005175, 2.288168, -9.343316 +IMU2, 123991, 0.2240795, 0.1947113, -0.06226697, -0.4316813, 2.322988, -9.320822 +IMU, 124011, 0.1846781, 0.1770429, -0.07047808, -0.5521708, 2.136196, -9.560685 +IMU2, 124011, 0.1706323, 0.164768, -0.06881078, -0.5332843, 2.353472, -9.592219 +IMU, 124030, 0.1684805, 0.1263078, -0.04467219, -0.5874451, 2.215943, -9.251404 +IMU2, 124030, 0.1418551, 0.1108554, -0.04003113, -0.5281093, 2.355119, -8.99485 +IMU, 124050, 0.1232673, 0.06938791, -0.04998618, -0.5019091, 1.982788, -9.101209 +IMU2, 124050, 0.1099561, 0.06361604, -0.05488431, -0.4679245, 2.167844, -8.931154 +GPS, 3, 56704200, 1777, 11, 1.93, 14.1105941, 100.6192145, -34.84, -3.78, 0.82, 307.17, -0.14, 124060 +IMU, 124070, 0.1164952, 0.02572945, -0.03793108, -0.3957313, 2.368861, -9.301864 +IMU2, 124070, 0.1191392, 0.01624389, -0.03606318, -0.3006602, 2.488201, -9.191626 +MAG, 124080, -398, 11, 100, -86, 10, 139, 0, 0, 0 +MAG2, 124080, -261, -69, 277, 0, 0, 0, 0, 0, 0 +CTUN, 124090, 0, 0, 0, 0, -35.18, -0.06, 0.00, 0.00, 0, -3186 +ATT, 124090, 0.00, 94.78, 0.00, -7.03, 187.23, 187.23 +RCIN, 124090, 1503, 1504, 1026, 1513, 992, 992, 993, 991 +RCOU, 124090, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124090, 0.08194517, 0.001446284, -0.0414243, -0.4422066, 1.950729, -9.422966 +IMU2, 124090, 0.07292243, -0.005895636, -0.04684228, -0.3518168, 2.137739, -9.399728 +IMU, 124110, 0.08088872, -0.02280226, -0.02706699, -0.3405564, 2.106317, -9.137671 +IMU2, 124110, 0.06533508, -0.03298128, -0.03185851, -0.3781151, 2.295452, -9.013756 +IMU, 124130, 0.05848244, -0.02949471, -0.03016867, -0.519916, 1.740112, -9.125987 +IMU2, 124130, 0.03551417, -0.03183499, -0.0366917, -0.5028955, 1.966394, -9.045195 +IMU, 124151, 0.01931011, -0.03968489, -0.02180996, -0.4312168, 2.333354, -9.017573 +IMU2, 124151, 0.01297318, -0.04606147, -0.02572882, -0.3508986, 2.450732, -8.978358 +IMU, 124170, 0.006101049, -0.0493395, -0.01714298, -0.5370484, 1.974408, -9.185822 +IMU2, 124170, -0.01048513, -0.05832528, -0.01934336, -0.4830287, 2.094759, -9.205865 +MAG, 124180, -400, 11, 99, -86, 10, 139, 0, 0, 0 +MAG2, 124180, -261, -70, 278, 0, 0, 0, 0, 0, 0 +CTUN, 124190, 0, 0, 0, 0, -36.88, -0.12, 0.00, 0.00, 0, -3280 +ATT, 124190, 0.00, 94.45, 0.00, -6.98, 187.14, 187.14 +RCIN, 124190, 1503, 1504, 1026, 1511, 992, 993, 992, 992 +RCOU, 124191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124191, -0.02000491, -0.05800029, -0.02753144, -0.3908171, 2.366986, -9.202068 +IMU2, 124191, -0.02490067, -0.06619585, -0.02164066, -0.2890516, 2.542569, -9.225578 +IMU, 124210, 0.005525088, -0.09088598, -0.03242238, -0.8693347, 2.208242, -9.092064 +IMU2, 124210, -0.002164714, -0.1086551, -0.03384673, -0.8304337, 2.281619, -9.066588 +IMU, 124230, 0.001884185, -0.1129146, -0.053835, -0.6062762, 2.388783, -9.316062 +IMU2, 124230, 0.008807406, -0.1294104, -0.0533888, -0.5037677, 2.604157, -9.187049 +IMU, 124250, 0.03398881, -0.1176285, -0.05030797, -0.8403156, 2.500767, -9.5103 +IMU2, 124250, 0.04366843, -0.1260757, -0.05568121, -0.8282583, 2.65324, -9.47875 +GPS, 3, 56704400, 1777, 11, 1.93, 14.1105971, 100.6192086, -38.24, -3.50, 1.07, 307.17, -0.29, 124260 +IMU, 124270, 0.04368337, -0.09668414, -0.06499241, -0.8654817, 2.243617, -9.447104 +IMU2, 124270, 0.04647755, -0.1037214, -0.06790011, -0.7623934, 2.387722, -9.509799 +MAG, 124280, -399, 11, 102, -86, 10, 139, 0, 0, 0 +MAG2, 124280, -261, -72, 282, 0, 0, 0, 0, 0, 0 +CTUN, 124290, 0, 0, 0, 0, -38.59, -0.10, 0.00, 0.00, 0, -3375 +ATT, 124290, 0.00, 94.12, 0.00, -6.75, 186.71, 186.71 +RCIN, 124290, 1503, 1504, 1025, 1512, 992, 992, 993, 992 +RCOU, 124291, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124291, 0.09185395, -0.09474425, -0.06803698, -0.8632323, 2.390431, -9.498599 +IMU2, 124291, 0.09722879, -0.09642725, -0.06355726, -0.8255169, 2.512276, -9.529674 +IMU, 124310, 0.1173991, -0.06810227, -0.0809015, -0.894812, 2.08762, -9.849269 +IMU2, 124310, 0.1071118, -0.06456398, -0.08954906, -0.8963284, 2.250588, -9.801407 +IMU, 124330, 0.1240045, -0.04616319, -0.07697618, -0.9267061, 2.353178, -9.771173 +IMU2, 124330, 0.1141889, -0.05165381, -0.06974868, -0.9544163, 2.505482, -9.674075 +IMU, 124351, 0.1280078, -0.02964891, -0.07041806, -1.16522, 1.803393, -9.64481 +IMU2, 124351, 0.1148764, -0.02949188, -0.07473294, -1.240636, 1.969518, -9.652501 +IMU, 124370, 0.09174532, -0.01302591, -0.08168343, -0.9550468, 2.240875, -9.602235 +IMU2, 124370, 0.08627485, -0.01652953, -0.08355505, -0.8981864, 2.393281, -9.674908 +MAG, 124380, -396, 8, 104, -86, 10, 139, 0, 0, 0 +MAG2, 124380, -259, -73, 283, 0, 0, 0, 0, 0, 0 +CTUN, 124390, 0, 0, 0, 0, -40.32, 0.04, 0.00, 0.00, 0, -3466 +ATT, 124391, 0.00, 94.23, 0.00, -6.41, 186.65, 186.65 +RCIN, 124391, 1503, 1503, 1027, 1512, 992, 993, 992, 992 +RCOU, 124391, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124391, 0.09649843, -0.01088369, -0.06781178, -1.234856, 2.193789, -9.792949 +IMU2, 124391, 0.0804094, -0.01155972, -0.07128785, -1.231646, 2.416811, -9.794872 +IMU, 124411, 0.07561171, -0.01090524, -0.08405469, -1.114588, 2.055108, -9.680913 +IMU2, 124411, 0.07247816, -0.01345743, -0.08466018, -1.049053, 2.329827, -9.691153 +IMU, 124430, 0.08555172, -0.02326359, -0.07869528, -1.180771, 2.202373, -9.478332 +IMU2, 124430, 0.08239006, -0.03241345, -0.06999188, -1.16448, 2.379428, -9.587965 +IMU, 124450, 0.1081422, -0.01977007, -0.08856471, -1.101415, 1.637083, -9.623309 +IMU2, 124450, 0.09018642, -0.02615882, -0.0874775, -1.163057, 1.810842, -9.416042 +GPS, 3, 56704600, 1777, 11, 1.93, 14.1106013, 100.6192023, -41.69, -3.40, 1.32, 301.95, -0.34, 124460 +IMU, 124471, 0.1256467, -0.002243135, -0.09649307, -0.8326613, 1.988664, -9.551085 +IMU2, 124471, 0.1228123, -0.006931346, -0.09718277, -0.7597195, 2.109104, -9.485934 +MAG, 124480, -395, 7, 106, -86, 10, 139, 0, 0, 0 +MAG2, 124480, -259, -75, 283, 0, 0, 0, 0, 0, 0 +CTUN, 124490, 0, 0, 0, 0, -42.05, -0.10, 0.00, 0.00, 0, -3555 +ATT, 124491, 0.00, 94.21, 0.00, -6.02, 186.77, 186.77 +RCIN, 124491, 1504, 1504, 1026, 1512, 992, 993, 992, 992 +RCOU, 124491, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124491, 0.0893598, 0.03123143, -0.08758125, -1.111266, 2.094621, -9.578073 +IMU2, 124491, 0.09145891, 0.03296746, -0.0914868, -1.181849, 2.27178, -9.594206 +IMU, 124510, 0.04625759, 0.04971865, -0.1016859, -1.171736, 2.054543, -9.592256 +IMU2, 124510, 0.03549256, 0.05074297, -0.09665325, -0.9962416, 2.326583, -9.410513 +IMU, 124530, 0.05076827, 0.03210916, -0.09609598, -1.202663, 1.885532, -9.445352 +IMU2, 124530, 0.05627268, 0.02978033, -0.09364604, -1.16764, 2.049491, -9.483685 +IMU, 124550, 0.0423492, 0.02130653, -0.1137941, -1.231923, 1.450665, -9.663721 +IMU2, 124550, 0.03336445, 0.02281481, -0.1077358, -1.217395, 1.629329, -9.5606 +IMU, 124571, 0.0505509, 0.00143487, -0.1136297, -1.104598, 1.89024, -9.751956 +IMU2, 124571, 0.04520645, 0.005562892, -0.1054757, -0.9931323, 1.956106, -9.75007 +MAG, 124580, -397, 6, 105, -86, 10, 139, 0, 0, 0 +MAG2, 124580, -259, -77, 282, 0, 0, 0, 0, 0, 0 +CTUN, 124590, 0, 0, 0, 0, -43.79, -0.07, 0.00, 0.00, 0, -3640 +ATT, 124590, 0.00, 93.90, 0.00, -5.50, 187.07, 187.07 +RCIN, 124590, 1503, 1504, 1028, 1512, 992, 992, 993, 991 +RCOU, 124591, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124591, 0.02003906, 0.002252333, -0.1025613, -1.138172, 1.994426, -9.491632 +IMU2, 124591, 0.01629454, -0.002532266, -0.1028935, -1.198382, 1.999054, -9.603089 +IMU, 124610, -0.01995115, 0.02199834, -0.1022358, -1.083593, 2.131942, -9.784894 +IMU2, 124610, -0.02307802, 0.02507462, -0.0962203, -1.035597, 2.29945, -9.763394 +IMU, 124631, -0.01030297, 0.015783, -0.07428963, -1.013337, 2.131745, -9.587505 +IMU2, 124631, 0.007745199, 0.009914607, -0.0711467, -1.020848, 2.304499, -9.720113 +GPS, 3, 56704800, 1777, 11, 1.93, 14.1106054, 100.6191971, -44.83, -3.46, 1.52, 299.31, -0.25, 124640 +IMU, 124650, -0.007751884, 0.02998463, -0.05907281, -0.9216791, 1.634356, -9.581984 +IMU2, 124650, -0.01584147, 0.03053621, -0.05781154, -0.9214046, 1.832451, -9.431826 +IMU, 124670, 0.0225361, 0.02442025, -0.03213274, -0.9617287, 1.860353, -9.438607 +IMU2, 124670, 0.03577067, 0.02323061, -0.0346, -0.9289138, 2.037978, -9.455422 +MAG, 124680, -396, 2, 104, -86, 10, 139, 0, 0, 0 +MAG2, 124680, -260, -79, 281, 0, 0, 0, 0, 0, 0 +CTUN, 124690, 0, 0, 0, 0, -45.53, -0.12, 0.00, 0.00, 0, -3724 +ATT, 124690, 0.00, 93.33, 0.00, -5.24, 187.33, 187.33 +RCIN, 124690, 1504, 1503, 1027, 1512, 992, 993, 992, 992 +RCOU, 124690, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124690, 0.0149405, 0.02243665, -0.01046106, -1.07217, 1.989259, -9.456819 +IMU2, 124690, 0.01635196, 0.01389376, -0.008008203, -1.060534, 2.137538, -9.517042 +IMU, 124710, 0.007816399, 0.02748489, -0.004448027, -1.082046, 2.021998, -9.839367 +IMU2, 124710, 9.734184E-05, 0.02186666, -0.002175001, -0.9540278, 2.210244, -9.86739 +IMU, 124730, 0.004298193, 0.004668612, 0.01649442, -1.007012, 2.211344, -9.478398 +IMU2, 124730, -0.001832716, 0.000838032, 0.0234437, -1.011993, 2.400176, -9.554301 +IMU, 124750, 0.02776469, -0.005127028, 0.01602066, -0.9398284, 1.840197, -9.475532 +IMU2, 124750, 0.02211187, -0.000316754, 0.01286514, -0.8962525, 1.975238, -9.470582 +IMU, 124770, 0.02740668, -0.01912059, 0.02053174, -0.7278113, 2.116418, -9.459224 +IMU2, 124770, 0.02481192, -0.02776858, 0.02212732, -0.7364732, 2.254546, -9.528422 +MAG, 124780, -397, 0, 104, -86, 10, 139, 0, 0, 0 +MAG2, 124780, -260, -81, 283, 0, 0, 0, 0, 0, 0 +CTUN, 124790, 0, 0, 0, 0, -47.28, -0.14, 0.00, 0.00, 0, -3806 +ATT, 124790, 0.00, 92.89, 0.00, -5.40, 187.40, 187.40 +RCIN, 124790, 1503, 1504, 1027, 1512, 993, 992, 992, 992 +RCOU, 124791, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124791, 0.0487286, -0.01742719, 0.03287468, -0.8730031, 2.02239, -9.649979 +IMU2, 124791, 0.0349171, -0.02113408, 0.02794369, -0.8627433, 2.185906, -9.563244 +IMU, 124810, 0.0279521, -0.00856081, 0.02173873, -0.9829618, 1.73559, -9.583595 +IMU2, 124810, 0.01512483, -0.007310117, 0.01848742, -0.9987487, 1.832819, -9.56201 +IMU, 124831, 0.01745647, -0.01103165, 0.02240632, -0.827952, 1.86999, -9.335504 +IMU2, 124831, 0.0006063785, -0.01467996, 0.02596214, -0.7435614, 2.06074, -9.247547 +IMU, 124851, 0.002428398, -0.02547261, 0.02450678, -0.9420162, 1.902169, -9.395121 +IMU2, 124851, -0.0004332159, -0.02847452, 0.02366173, -0.9586194, 2.041965, -9.357335 +GPS, 3, 56705000, 1777, 11, 1.93, 14.1106075, 100.6191941, -48.68, -3.63, 1.09, 299.31, -0.2, 124860 +IMU, 124870, -0.02700602, -0.03944201, 0.01776271, -0.838176, 2.011589, -9.480691 +IMU2, 124870, -0.04413154, -0.05579888, 0.01881386, -0.7863791, 2.204834, -9.421756 +MAG, 124880, -396, 2, 104, -86, 10, 139, 0, 0, 0 +MAG2, 124880, -260, -79, 282, 0, 0, 0, 0, 0, 0 +CTUN, 124890, 0, 0, 0, 0, -49.03, -0.04, 0.00, 0.00, 0, -3885 +DU32, 7, 262233 +CURR, 124890, 0, 10381, 1534, 119, 5322, 28.37431 +ATT, 124890, 0.00, 92.36, 0.00, -5.60, 187.31, 187.31 +RCIN, 124890, 1503, 1504, 1025, 1512, 993, 992, 992, 992 +RCOU, 124890, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124891, -0.02463084, -0.06007795, 0.0237191, -0.8428139, 2.070539, -9.563538 +IMU2, 124891, -0.03399976, -0.06463611, 0.0270499, -0.8133802, 2.211137, -9.596053 +IMU, 124911, 0.0008453857, -0.07006857, 0.02000163, -0.9772233, 1.734522, -9.610729 +IMU2, 124911, -0.01083499, -0.06992552, 0.0159936, -0.9184668, 1.850401, -9.522287 +IMU, 124930, -0.002723617, -0.07012093, 0.01547557, -0.810798, 1.90576, -9.493063 +IMU2, 124930, -0.02193773, -0.06800429, 0.01502165, -0.7992427, 2.046172, -9.403396 +IMU, 124950, -0.008125661, -0.06980061, 0.02361983, -0.9612436, 2.135863, -9.405401 +IMU2, 124950, -0.01467818, -0.06859745, 0.02541402, -0.9540974, 2.274982, -9.346336 +IMU, 124970, -0.004705684, -0.06988017, 0.01490572, -0.9916476, 1.754364, -9.484797 +IMU2, 124970, -0.02183456, -0.07398292, 0.01398337, -0.9655432, 1.908887, -9.355413 +MAG, 124980, -396, 2, 107, -86, 10, 139, 0, 0, 0 +MAG2, 124980, -259, -79, 284, 0, 0, 0, 0, 0, 0 +CTUN, 124990, 0, 0, 0, 0, -50.77, -0.02, 0.00, 0.00, 0, -3962 +ATT, 124990, 0.00, 91.85, 0.00, -5.75, 186.87, 186.87 +RCIN, 124990, 1503, 1504, 1025, 1512, 992, 993, 993, 991 +RCOU, 124991, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 124991, 0.001874039, -0.08447629, 0.01035666, -0.8313837, 1.963343, -9.466019 +IMU2, 124991, -0.002731096, -0.09590247, 0.008036528, -0.8377132, 2.126632, -9.393163 +IMU, 125010, 0.03378954, -0.0996695, 0.01251912, -1.022064, 2.013015, -9.375756 +IMU2, 125010, 0.03392633, -0.1009059, 0.008968482, -1.04624, 2.118252, -9.423483 +IMU, 125030, 0.01774545, -0.09685299, -0.0006423562, -1.041248, 1.804299, -9.614242 +IMU2, 125030, 0.004895043, -0.08949298, -0.006776583, -0.9382653, 2.018618, -9.667237 +GPS, 3, 56705200, 1777, 11, 1.93, 14.1106101, 100.6191903, -51.81, -3.80, 0.83, 299.31, -0.2, 125040 +IMU, 125051, 0.005174682, -0.09164371, -0.003570753, -1.160871, 1.980867, -9.570785 +IMU2, 125051, 0.006224982, -0.09607442, -0.0006875731, -1.084518, 2.121501, -9.560266 +IMU, 125070, 0.01452384, -0.09119785, -0.008284106, -1.367939, 1.871935, -9.449196 +IMU2, 125070, 0.006238118, -0.09348057, -0.01085889, -1.359161, 1.983339, -9.721893 +MAG, 125081, -394, 4, 109, -86, 10, 139, 0, 0, 0 +MAG2, 125081, -258, -77, 287, 0, 0, 0, 0, 0, 0 +CTUN, 125090, 0, 0, 0, 0, -52.51, 0.01, 0.00, 0.00, 0, -4036 +ATT, 125091, 0.00, 91.46, 0.00, -5.80, 186.33, 186.33 +RCIN, 125091, 1502, 1504, 1026, 1512, 992, 992, 993, 992 +RCOU, 125091, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 125091, 0.001813952, -0.08160252, -0.02488823, -1.0631, 1.832028, -9.340932 +IMU2, 125091, 0.0003004409, -0.08590154, -0.02375755, -1.03525, 2.025598, -9.314232 +IMU, 125110, 0.021246, -0.07175104, -0.02264027, -1.088385, 1.91841, -9.587788 +IMU2, 125110, 0.01098786, -0.07197793, -0.02518291, -1.073721, 2.02288, -9.67365 +IMU, 125130, 0.03463234, -0.04636079, -0.03060802, -1.221084, 1.79547, -9.778042 +IMU2, 125130, 0.03065075, -0.04599746, -0.03258538, -1.2475, 1.931882, -9.695873 +IMU, 125150, 0.01041876, -0.02491471, -0.04600776, -1.082186, 1.837803, -9.57405 +IMU2, 125150, -0.002467625, -0.02576911, -0.04537375, -1.099948, 1.947269, -9.438146 +IMU, 125171, 0.001126511, -0.01347687, -0.04751267, -1.198769, 1.877713, -9.40558 +IMU2, 125171, -0.003162172, -0.01422749, -0.05048951, -1.153666, 2.014159, -9.331002 +MAG, 125180, -394, 2, 112, -86, 10, 139, 0, 0, 0 +MAG2, 125180, -256, -80, 289, 0, 0, 0, 0, 0, 0 +CTUN, 125190, 0, 0, 0, 0, -54.23, 0.00, 0.00, 0.00, 0, -4107 +ATT, 125191, 0.00, 91.02, 0.00, -5.64, 186.16, 186.16 +RCIN, 125191, 1503, 1504, 1025, 1513, 992, 992, 993, 991 +RCOU, 125191, 1122, 1122, 1122, 1122, 0, 0, 0, 0 +IMU, 125191, -0.001921276, -0.01156685, -0.06012962, -1.350242, 1.79443, -9.578811 +IMU2, 125191, -0.003243731, -0.01071055, -0.05637529, -1.302584, 1.907837, -9.582116 +IMU, 125210, -0.01965771, -0.01934712, -0.07203884, -1.055922, 1.947788, -9.649301 +IMU2, 125210, -0.01838078, -0.02487617, -0.07532278, -1.015742, 2.09629, -9.687523 +IMU, 125230, -0.003269086, -0.02289573, -0.06722176, -1.107607, 2.013193, -9.496122 +IMU2, 125230, -0.003808955, -0.02938985, -0.05879949, -1.139975, 2.113212, -9.425806 +IMU, 125250, 0.01602939, -0.03228795, -0.06954374, -1.409379, 1.827114, -9.650491 +IMU2, 125250, 0.009164467, -0.04113919, -0.06790464, -1.360331, 1.930157, -9.634181 +GPS, 3, 56705400, 1777, 11, 1.93, 14.1106147, 100.619185, -55.59, -4.00, 0.98, 299.31, -0.18, 125260 +IMU, 125270, 0.0211044, -0.04707771, -0.07547536, -1.24588, 2.0423, -9.504646 +IMU2, 125270, 0.01970118, -0.05647173, -0.07288989, -1.291565, 2.193253, -9.443418 +MAG, 125280, -394, 0, 112, -86, 10, 139, 0, 0, 0 +MAG2, 125280, -257, -80, 290, 0, 0, 0, 0, 0, 0 +CTUN, 125290, 0, 0, 0, 0, -55.94, -0.02, 0.00, 0.00, 0, -4176 +ERR, 12, 1 +EV, 11 diff --git a/Tools/LogAnalyzer/logs/tradheli_brownout.log b/Tools/LogAnalyzer/logs/tradheli_brownout.log new file mode 100644 index 0000000000..81de0bcf8c --- /dev/null +++ b/Tools/LogAnalyzer/logs/tradheli_brownout.log @@ -0,0 +1,4197 @@ +58 + +ArduCopter V3.0.1 +Free RAM: 1273 +APM 2 +FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format +FMT, 129, 23, PARM, Nf, Name,Value +FMT, 130, 35, GPS, BIBcLLeeEe, Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs +FMT, 131, 27, IMU, ffffff, GyrX,GyrY,GyrZ,AccX,AccY,AccZ +FMT, 132, 67, MSG, Z, Message +FMT, 9, 19, CURR, hIhhhf, Thr,ThrInt,Volt,Curr,Vcc,CurrTot +FMT, 11, 13, MOT, hhhhh, Mot1,Mot2,Mot3,Mot4,GGain +FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch +FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit +FMT, 4, 25, CTUN, hcefhhhhh, ThrIn,SonAlt,BarAlt,WPAlt,NavThr,AngBst,CRate,ThrOut,DCRate +FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ +FMT, 6, 17, PM, BBBHHIhB, RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr +FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng +FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw +FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng +FMT, 3, 6, MODE, Mh, Mode,ThrCrs +FMT, 10, 3, STRT, , +FMT, 13, 4, EV, B, Id +FMT, 20, 6, D16, Bh, Id,Value +FMT, 21, 6, DU16, BH, Id,Value +FMT, 22, 8, D32, Bi, Id,Value +FMT, 23, 8, DU32, BI, Id,Value +FMT, 24, 8, DFLT, Bf, Id,Value +FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain +FMT, 16, 15, DMP, ccccCC, DCMRoll,DMPRoll,DCMPtch,DMPPtch,DCMYaw,DMPYaw +FMT, 18, 25, CAM, ILLeccC, GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw +FMT, 19, 5, ERR, BB, Subsys,ECode +PARM, SYSID_SW_MREV, 120.000000 +PARM, SYSID_SW_TYPE, 10.000000 +PARM, SYSID_THISMAV, 1.000000 +PARM, SYSID_MYGCS, 255.000000 +PARM, SERIAL3_BAUD, 57.000000 +PARM, TELEM_DELAY, 0.000000 +PARM, RTL_ALT, 0.000000 +PARM, SONAR_ENABLE, 1.000000 +PARM, SONAR_TYPE, 1.000000 +PARM, SONAR_GAIN, 0.200000 +PARM, BATT_MONITOR, 3.000000 +PARM, FS_BATT_ENABLE, 1.000000 +PARM, FS_GPS_ENABLE, 1.000000 +PARM, FS_GCS_ENABLE, 0.000000 +PARM, VOLT_DIVIDER, 10.495580 +PARM, AMP_PER_VOLT, 27.320000 +PARM, BATT_CAPACITY, 2250.000000 +PARM, MAG_ENABLE, 1.000000 +PARM, FLOW_ENABLE, 0.000000 +PARM, LOW_VOLT, 9.800000 +PARM, SUPER_SIMPLE, 0.000000 +PARM, RTL_ALT_FINAL, 0.000000 +PARM, BATT_VOLT_PIN, 13.000000 +PARM, BATT_CURR_PIN, 12.000000 +PARM, RSSI_PIN, -1.000000 +PARM, THR_ACC_ENABLE, 1.000000 +PARM, WP_YAW_BEHAVIOR, 1.000000 +PARM, WP_TOTAL, 8.000000 +PARM, WP_INDEX, 0.000000 +PARM, CIRCLE_RADIUS, 14.000000 +PARM, CIRCLE_RATE, 5.000000 +PARM, RTL_LOIT_TIME, 1000.000000 +PARM, LAND_SPEED, 100.000000 +PARM, PILOT_VELZ_MAX, 250.000000 +PARM, THR_MIN, 130.000000 +PARM, THR_MAX, 1000.000000 +PARM, FS_THR_ENABLE, 0.000000 +PARM, FS_THR_VALUE, 975.000000 +PARM, TRIM_THROTTLE, 474.000000 +PARM, THR_MID, 500.000000 +PARM, FLTMODE1, 6.000000 +PARM, FLTMODE2, 0.000000 +PARM, FLTMODE3, 9.000000 +PARM, FLTMODE4, 5.000000 +PARM, FLTMODE5, 6.000000 +PARM, FLTMODE6, 3.000000 +PARM, SIMPLE, 0.000000 +PARM, LOG_BITMASK, 830.000000 +PARM, TOY_RATE, 1.000000 +PARM, ESC, 0.000000 +PARM, TUNE, 0.000000 +PARM, TUNE_LOW, 10.000000 +PARM, TUNE_HIGH, 75.000000 +PARM, FRAME, 0.000000 +PARM, CH7_OPT, 5.000000 +PARM, CH8_OPT, 0.000000 +PARM, ARMING_CHECK, 1.000000 +PARM, HS1_MIN, 1000.000000 +PARM, HS1_TRIM, 1550.000000 +PARM, HS1_MAX, 2000.000000 +PARM, HS1_REV, 1.000000 +PARM, HS1_DZ, 0.000000 +PARM, HS2_MIN, 1000.000000 +PARM, HS2_TRIM, 1470.000000 +PARM, HS2_MAX, 2000.000000 +PARM, HS2_REV, -1.000000 +PARM, HS2_DZ, 0.000000 +PARM, HS3_MIN, 1000.000000 +PARM, HS3_TRIM, 1475.000000 +PARM, HS3_MAX, 2000.000000 +PARM, HS3_REV, 1.000000 +PARM, HS3_DZ, 0.000000 +PARM, HS4_MIN, 1239.000000 +PARM, HS4_TRIM, 1471.000000 +PARM, HS4_MAX, 1730.000000 +PARM, HS4_REV, 1.000000 +PARM, HS4_DZ, 0.000000 +PARM, RATE_PIT_FF, 0.020000 +PARM, RATE_RLL_FF, 0.020000 +PARM, RATE_YAW_FF, 0.050000 +PARM, RC1_MIN, 1102.000000 +PARM, RC1_TRIM, 1521.000000 +PARM, RC1_MAX, 1944.000000 +PARM, RC1_REV, 1.000000 +PARM, RC1_DZ, 30.000000 +PARM, RC2_MIN, 1102.000000 +PARM, RC2_TRIM, 1522.000000 +PARM, RC2_MAX, 1944.000000 +PARM, RC2_REV, 1.000000 +PARM, RC2_DZ, 30.000000 +PARM, RC3_MIN, 1101.000000 +PARM, RC3_TRIM, 1386.000000 +PARM, RC3_MAX, 1944.000000 +PARM, RC3_REV, 1.000000 +PARM, RC3_DZ, 10.000000 +PARM, RC4_MIN, 1102.000000 +PARM, RC4_TRIM, 1521.000000 +PARM, RC4_MAX, 1944.000000 +PARM, RC4_REV, 1.000000 +PARM, RC4_DZ, 15.000000 +PARM, RC5_MIN, 1161.000000 +PARM, RC5_TRIM, 1522.000000 +PARM, RC5_MAX, 1813.000000 +PARM, RC5_REV, 1.000000 +PARM, RC5_DZ, 0.000000 +PARM, RC5_FUNCTION, 0.000000 +PARM, RC6_MIN, 1101.000000 +PARM, RC6_TRIM, 1102.000000 +PARM, RC6_MAX, 1944.000000 +PARM, RC6_REV, 1.000000 +PARM, RC6_DZ, 0.000000 +PARM, RC6_FUNCTION, 0.000000 +PARM, RC7_MIN, 1101.000000 +PARM, RC7_TRIM, 1102.000000 +PARM, RC7_MAX, 1944.000000 +PARM, RC7_REV, 1.000000 +PARM, RC7_DZ, 0.000000 +PARM, RC7_FUNCTION, 0.000000 +PARM, RC8_MIN, 1102.000000 +PARM, RC8_TRIM, 1102.000000 +PARM, RC8_MAX, 1944.000000 +PARM, RC8_REV, 1.000000 +PARM, RC8_DZ, 0.000000 +PARM, RC8_FUNCTION, 0.000000 +PARM, RC10_MIN, 1100.000000 +PARM, RC10_TRIM, 1500.000000 +PARM, RC10_MAX, 1900.000000 +PARM, RC10_REV, 1.000000 +PARM, RC10_DZ, 0.000000 +PARM, RC10_FUNCTION, 0.000000 +PARM, RC11_MIN, 1100.000000 +PARM, RC11_TRIM, 1500.000000 +PARM, RC11_MAX, 1900.000000 +PARM, RC11_REV, 1.000000 +PARM, RC11_DZ, 0.000000 +PARM, RC11_FUNCTION, 0.000000 +PARM, RC_SPEED, 125.000000 +PARM, ACRO_P, 4.500000 +PARM, AXIS_ENABLE, 1.000000 +PARM, ACRO_BAL_ROLL, 50.000000 +PARM, ACRO_BAL_PITCH, 50.000000 +PARM, ACRO_TRAINER, 1.000000 +PARM, LED_MODE, 9.000000 +PARM, RATE_RLL_P, 0.060000 +PARM, RATE_RLL_I, 0.250000 +PARM, RATE_RLL_D, 0.000000 +PARM, RATE_RLL_IMAX, 500.000000 +PARM, RATE_PIT_P, 0.064000 +PARM, RATE_PIT_I, 0.150000 +PARM, RATE_PIT_D, 0.000000 +PARM, RATE_PIT_IMAX, 500.000000 +PARM, RATE_YAW_P, 0.100000 +PARM, RATE_YAW_I, 0.035000 +PARM, RATE_YAW_D, 0.001000 +PARM, RATE_YAW_IMAX, 2000.000000 +PARM, LOITER_LAT_P, 1.000000 +PARM, LOITER_LAT_I, 0.500000 +PARM, LOITER_LAT_D, 0.000000 +PARM, LOITER_LAT_IMAX, 400.000000 +PARM, LOITER_LON_P, 1.000000 +PARM, LOITER_LON_I, 0.500000 +PARM, LOITER_LON_D, 0.000000 +PARM, LOITER_LON_IMAX, 400.000000 +PARM, THR_RATE_P, 3.000000 +PARM, THR_RATE_I, 0.000000 +PARM, THR_RATE_D, 0.001000 +PARM, THR_RATE_IMAX, 300.000000 +PARM, THR_ACCEL_P, 0.250000 +PARM, THR_ACCEL_I, 0.600000 +PARM, THR_ACCEL_D, 0.001000 +PARM, THR_ACCEL_IMAX, 500.000000 +PARM, OF_RLL_P, 2.500000 +PARM, OF_RLL_I, 0.500000 +PARM, OF_RLL_D, 0.120000 +PARM, OF_RLL_IMAX, 100.000000 +PARM, OF_PIT_P, 2.500000 +PARM, OF_PIT_I, 0.500000 +PARM, OF_PIT_D, 0.120000 +PARM, OF_PIT_IMAX, 100.000000 +PARM, STB_RLL_P, 4.500000 +PARM, STB_RLL_I, 0.000000 +PARM, STB_RLL_IMAX, 800.000000 +PARM, STB_PIT_P, 3.500000 +PARM, STB_PIT_I, 0.000000 +PARM, STB_PIT_IMAX, 800.000000 +PARM, STB_YAW_P, 3.500000 +PARM, STB_YAW_I, 0.000000 +PARM, STB_YAW_IMAX, 800.000000 +PARM, THR_ALT_P, 0.250000 +PARM, THR_ALT_I, 0.020000 +PARM, THR_ALT_IMAX, 300.000000 +PARM, HLD_LAT_P, 1.000000 +PARM, HLD_LAT_I, 0.000000 +PARM, HLD_LAT_IMAX, 3000.000000 +PARM, HLD_LON_P, 1.000000 +PARM, HLD_LON_I, 0.000000 +PARM, HLD_LON_IMAX, 3000.000000 +PARM, CAM_TRIGG_TYPE, 0.000000 +PARM, CAM_DURATION, 10.000000 +PARM, CAM_SERVO_ON, 1300.000000 +PARM, CAM_SERVO_OFF, 1100.000000 +PARM, COMPASS_OFS_X, -73.707489 +PARM, COMPASS_OFS_Y, 23.727873 +PARM, COMPASS_OFS_Z, 76.562508 +PARM, COMPASS_DEC, 0.016268 +PARM, COMPASS_LEARN, 0.000000 +PARM, COMPASS_USE, 1.000000 +PARM, COMPASS_AUTODEC, 1.000000 +PARM, COMPASS_MOTCT, 0.000000 +PARM, COMPASS_MOT_X, 0.000000 +PARM, COMPASS_MOT_Y, 0.000000 +PARM, COMPASS_MOT_Z, 0.000000 +PARM, COMPASS_ORIENT, 8.000000 +PARM, INS_PRODUCT_ID, 88.000000 +PARM, INS_ACCSCAL_X, 1.000000 +PARM, INS_ACCSCAL_Y, 1.000000 +PARM, INS_ACCSCAL_Z, 1.000000 +PARM, INS_ACCOFFS_X, -0.048499 +PARM, INS_ACCOFFS_Y, 0.088398 +PARM, INS_ACCOFFS_Z, 0.353774 +PARM, INS_GYROFFS_X, -0.020699 +PARM, INS_GYROFFS_Y, 0.003874 +PARM, INS_GYROFFS_Z, 0.000502 +PARM, INS_MPU6K_FILTER, 10.000000 +PARM, INAV_TC_XY, 2.500000 +PARM, INAV_TC_Z, 5.000000 +PARM, WPNAV_SPEED, 1100.000000 +PARM, WPNAV_RADIUS, 274.320010 +PARM, WPNAV_SPEED_UP, 250.000000 +PARM, WPNAV_SPEED_DN, 150.000000 +PARM, WPNAV_LOIT_SPEED, 500.000000 +PARM, WPNAV_ACCEL, 150.000000 +PARM, SR0_RAW_SENS, 2.000000 +PARM, SR0_EXT_STAT, 2.000000 +PARM, SR0_RC_CHAN, 2.000000 +PARM, SR0_RAW_CTRL, 0.000000 +PARM, SR0_POSITION, 3.000000 +PARM, SR0_EXTRA1, 10.000000 +PARM, SR0_EXTRA2, 10.000000 +PARM, SR0_EXTRA3, 2.000000 +PARM, SR0_PARAMS, 0.000000 +PARM, SR3_RAW_SENS, 0.000000 +PARM, SR3_EXT_STAT, 0.000000 +PARM, SR3_RC_CHAN, 0.000000 +PARM, SR3_RAW_CTRL, 0.000000 +PARM, SR3_POSITION, 0.000000 +PARM, SR3_EXTRA1, 0.000000 +PARM, SR3_EXTRA2, 0.000000 +PARM, SR3_EXTRA3, 0.000000 +PARM, SR3_PARAMS, 0.000000 +PARM, AHRS_GPS_GAIN, 1.000000 +PARM, AHRS_GPS_USE, 1.000000 +PARM, AHRS_YAW_P, 0.100000 +PARM, AHRS_RP_P, 0.100000 +PARM, AHRS_WIND_MAX, 0.000000 +PARM, AHRS_TRIM_X, 0.000000 +PARM, AHRS_TRIM_Y, 0.000000 +PARM, AHRS_TRIM_Z, 0.000000 +PARM, AHRS_ORIENTATION, 0.000000 +PARM, AHRS_COMP_BETA, 0.100000 +PARM, AHRS_GPS_MINSATS, 6.000000 +PARM, MNT_MODE, 0.000000 +PARM, MNT_RETRACT_X, 0.000000 +PARM, MNT_RETRACT_Y, 0.000000 +PARM, MNT_RETRACT_Z, 0.000000 +PARM, MNT_NEUTRAL_X, 0.000000 +PARM, MNT_NEUTRAL_Y, 0.000000 +PARM, MNT_NEUTRAL_Z, 0.000000 +PARM, MNT_CONTROL_X, 0.000000 +PARM, MNT_CONTROL_Y, 0.000000 +PARM, MNT_CONTROL_Z, 0.000000 +PARM, MNT_STAB_ROLL, 0.000000 +PARM, MNT_STAB_TILT, 0.000000 +PARM, MNT_STAB_PAN, 0.000000 +PARM, MNT_RC_IN_ROLL, 0.000000 +PARM, MNT_ANGMIN_ROL, -4500.000000 +PARM, MNT_ANGMAX_ROL, 4500.000000 +PARM, MNT_RC_IN_TILT, 0.000000 +PARM, MNT_ANGMIN_TIL, -4500.000000 +PARM, MNT_ANGMAX_TIL, 4500.000000 +PARM, MNT_RC_IN_PAN, 0.000000 +PARM, MNT_ANGMIN_PAN, -4500.000000 +PARM, MNT_ANGMAX_PAN, 4500.000000 +PARM, MNT_JSTICK_SPD, 0.000000 +PARM, GND_ABS_PRESS, 101505.170000 +PARM, GND_TEMP, 29.660503 +PARM, SCHED_DEBUG, 0.000000 +PARM, FENCE_ENABLE, 1.000000 +PARM, FENCE_TYPE, 3.000000 +PARM, FENCE_ACTION, 1.000000 +PARM, FENCE_ALT_MAX, 25.908001 +PARM, FENCE_RADIUS, 91.440002 +PARM, H_SV1_POS, -60.000000 +PARM, H_SV2_POS, 60.000000 +PARM, H_SV3_POS, 180.000000 +PARM, H_ROL_MAX, 4500.000000 +PARM, H_PIT_MAX, 4500.000000 +PARM, H_COL_MIN, 1364.000000 +PARM, H_COL_MAX, 1678.000000 +PARM, H_COL_MID, 1558.000000 +PARM, H_GYR_ENABLE, 0.000000 +PARM, H_SWASH_TYPE, 0.000000 +PARM, H_GYR_GAIN, 1350.000000 +PARM, H_SV_MAN, 0.000000 +PARM, H_PHANG, 0.000000 +PARM, H_COLYAW, 5.000000 +PARM, H_GOV_SETPOINT, 1625.000000 +PARM, H_RSC_MODE, 2.000000 +PARM, H_RSC_RATE, 0.000000 +PARM, H_FLYBAR_MODE, 0.000000 +PARM, H_STAB_COL_MIN, 30.000000 +PARM, H_STAB_COL_MAX, 90.000000 +D32, 9, 21588 +CMD, 8, 0, 16, 0, 0, 0.00, 24.2398206, 54.5793101 +EV, 10 +EV, 15 +GPS, 3, 308900200, 10, 1.49, 24.2398205, 54.5793101, 0.19, 9.48, 0.01, 347.24 +CTUN, 336, 0.27, 0.03, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.23, 0.00, 0.75, 0.00, 215.88, 215.88 +GPS, 3, 308906400, 10, 1.49, 24.2398189, 54.5793105, 0.18, 9.42, 0.01, 347.24 +CTUN, 337, 0.27, 0.03, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.29, 0.00, 0.78, 0.00, 215.88, 215.88 +CTUN, 337, 0.27, 0.12, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.78, 0.00, 215.88, 215.88 +GPS, 3, 308906600, 10, 1.49, 24.2398189, 54.5793105, 0.17, 9.41, 0.01, 347.24 +CTUN, 336, 0.27, 0.11, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.78, 0.00, 215.87, 215.88 +CTUN, 337, 0.21, -0.01, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.78, 0.00, 215.88, 215.88 +GPS, 3, 308906800, 10, 1.49, 24.2398189, 54.5793105, 0.15, 9.41, 0.00, 347.24 +CTUN, 337, 0.26, 0.05, 0.000000, 0, 0, 0, 337, 0 +DU32, 7, 393469 +CURR, 337, 2021, 1232, 0, 4772, 0.000000 +ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.88, 215.88 +CTUN, 336, 0.21, 0.04, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.88, 215.88 +GPS, 3, 308907000, 10, 1.49, 24.2398188, 54.5793106, 0.14, 9.42, 0.01, 347.24 +CTUN, 337, 0.21, 0.01, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.88, 215.88 +CTUN, 337, 0.21, 0.02, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.88, 215.88 +GPS, 3, 308907200, 10, 1.49, 24.2398187, 54.5793106, 0.12, 9.42, 0.01, 347.24 +CTUN, 336, 0.21, 0.03, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.88, 215.88 +CTUN, 337, 0.19, -0.02, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.89, 215.88 +GPS, 3, 308907400, 10, 1.49, 24.2398187, 54.5793106, 0.11, 9.42, 0.01, 347.24 +CTUN, 337, 0.19, 0.04, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.79, 0.00, 215.89, 215.88 +CTUN, 336, 0.19, -0.02, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.89, 215.88 +GPS, 3, 308907600, 10, 1.49, 24.2398187, 54.5793106, 0.09, 9.43, 0.01, 347.24 +CTUN, 337, 0.19, 0.01, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.80, 0.00, 215.90, 215.88 +CTUN, 337, 0.15, -0.02, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 +GPS, 3, 308907800, 10, 1.49, 24.2398186, 54.5793107, 0.08, 9.43, 0.01, 347.24 +CTUN, 336, 0.16, 0.07, 0.000000, 0, 0, -1, 337, 0 +DU32, 7, 393469 +CURR, 336, 5387, 1237, 0, 4772, 0.000000 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 +CTUN, 336, 0.16, 0.02, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 +GPS, 3, 308908000, 10, 1.49, 24.2398186, 54.5793107, 0.07, 9.44, 0.02, 347.24 +CTUN, 337, 0.16, 0.00, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 +CTUN, 337, 0.15, -0.12, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 +GPS, 3, 308908200, 10, 1.49, 24.2398185, 54.5793107, 0.05, 9.44, 0.01, 347.24 +CTUN, 336, 0.15, -0.02, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.90, 215.88 +CTUN, 336, 0.15, 0.04, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 +PM, 0, 0, 50, 6, 1000, 6118488, 15, 0 +GPS, 3, 308908400, 10, 1.49, 24.2398184, 54.5793107, 0.04, 9.44, 0.01, 347.24 +CTUN, 337, 0.15, -0.04, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 +CTUN, 336, 0.15, -0.05, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 +GPS, 3, 308908600, 10, 1.49, 24.2398184, 54.5793108, 0.02, 9.45, 0.02, 347.24 +CTUN, 336, 0.16, 0.00, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 +CTUN, 337, 0.16, 0.06, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 +GPS, 3, 308908800, 10, 1.49, 24.2398184, 54.5793108, 0.02, 9.44, 0.02, 347.24 +CTUN, 337, 0.17, -0.01, 0.000000, 0, 0, -2, 337, 0 +DU32, 7, 393469 +CURR, 337, 8753, 1236, 0, 4752, 0.000000 +ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 +CTUN, 336, 0.16, -0.01, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.80, 0.00, 215.91, 215.88 +GPS, 3, 308909000, 10, 1.49, 24.2398183, 54.5793108, 0.01, 9.44, 0.02, 347.24 +CTUN, 336, 0.16, -0.06, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.81, 0.00, 215.91, 215.88 +CTUN, 337, 0.16, 0.05, 0.000000, 0, 0, -3, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.80, 0.00, 215.91, 215.88 +MODE, LOITER, 494 +GPS, 3, 308909200, 10, 1.49, 24.2398183, 54.5793108, 0.00, 9.44, 0.01, 347.24 +NTUN, 0.00, 0.00, 0.024055, -0.020616, -3.706598, 0.999391, -3.688661, 1.017262, 0.000000, 0.000000, 0.00, 0.00 +CTUN, 337, 0.17, 0.00, 0.000000, 0, 0, -3, 337, 0 +ATT, 0.00, 0.26, 0.00, 0.80, 0.00, 215.91, 215.88 +NTUN, 0.00, 3.18, 0.025694, -0.125327, -1.037081, -0.125327, -3.474234, 1.032693, 28.695177, -12.247182, 1.56, 0.93 +CTUN, 336, 0.16, -0.01, -0.159600, 0, 0, -2, 335, -40 +ATT, 0.00, 0.28, 0.00, 0.81, 0.00, 215.91, 215.88 +GPS, 3, 308909400, 10, 1.49, 24.2398182, 54.5793109, 0.00, 9.44, 0.01, 347.24 +NTUN, 0.00, 2.90, 0.131245, -0.247736, 0.131245, -0.247736, -3.246917, 1.014269, 14.567575, -2.211969, 0.60, 0.61 +CTUN, 337, 0.16, -0.03, -0.181600, 0, 0, -2, 332, -40 +ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 +NTUN, 0.00, 3.01, 0.301338, -0.452011, 0.301338, -0.452011, -3.025889, 1.048491, 4.684094, -3.022526, 0.30, 0.11 +CTUN, 337, 0.16, 0.07, -0.221000, 0, 0, -2, 329, -39 +ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 +GPS, 3, 308909600, 10, 1.49, 24.2398181, 54.5793109, 0.00, 9.45, 0.01, 347.24 +NTUN, 0.00, 3.04, 0.469120, -0.641418, 0.469120, -0.641418, -2.853666, 0.977797, 4.677818, -2.894073, 0.29, 0.12 +CTUN, 337, 0.17, -0.06, -0.252200, 0, 0, -2, 326, -39 +ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 +NTUN, 0.00, 3.08, 0.685371, -0.787907, 0.685371, -0.787907, -2.664129, 0.955439, 5.162514, -2.464882, 0.29, 0.15 +CTUN, 336, 0.17, 0.05, -0.311600, 0, 0, -2, 325, -40 +ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 +GPS, 3, 308909800, 10, 1.49, 24.2398181, 54.5793109, -0.01, 9.45, 0.01, 347.24 +NTUN, 0.01, 3.12, 0.875168, -0.926881, 0.875168, -0.926881, -2.503617, 0.984931, 4.897964, -2.389742, 0.28, 0.14 +CTUN, 337, 0.17, 0.05, -0.343600, 0, 0, -3, 322, -40 +DU32, 7, 393457 +CURR, 337, 12072, 1232, 0, 4752, 0.000000 +ATT, 0.00, 0.27, 0.00, 0.81, 0.00, 215.91, 215.88 +NTUN, 0.01, 3.13, 0.993700, -1.035828, 0.993700, -1.035828, -2.198121, 0.921508, 5.185322, -2.089468, 0.27, 0.17 +CTUN, 337, 0.17, -0.03, -0.374800, 0, 0, -3, 319, -39 +ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.91, 215.88 +GPS, 3, 308910000, 10, 1.49, 24.2398180, 54.5793110, -0.01, 9.46, 0.01, 347.24 +NTUN, 0.01, 3.13, 1.101871, -1.160008, 1.101871, -1.160008, -1.963457, 0.927190, 5.071004, -3.229513, 0.32, 0.12 +MODE, STABILIZE, 494 +CTUN, 336, 0.19, 0.01, -0.406000, 0, 0, -3, 316, 0 +ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.92, 215.88 +CTUN, 336, 0.19, 0.02, 0.000000, 0, 0, -3, 336, 0 +GPS, 3, 308910200, 10, 1.49, 24.2398180, 54.5793110, -0.01, 9.46, 0.01, 347.24 +ATT, 0.00, 0.29, 0.00, 0.82, 0.00, 215.92, 215.88 +CTUN, 337, 0.19, -0.03, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.29, 0.00, 0.82, 0.00, 215.92, 215.88 +CTUN, 336, 0.19, -0.05, 0.000000, 0, 0, -2, 337, 0 +GPS, 3, 308910400, 10, 1.49, 24.2398179, 54.5793110, -0.02, 9.46, 0.01, 347.24 +ATT, 0.00, 0.29, 0.00, 0.81, 0.00, 215.92, 215.88 +CTUN, 336, 0.19, 0.00, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.92, 215.88 +CTUN, 337, 0.15, 0.06, 0.000000, 0, 0, -3, 337, 0 +GPS, 3, 308910600, 10, 1.49, 24.2398179, 54.5793110, -0.02, 9.46, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.93, 215.88 +CTUN, 336, 0.19, -0.07, 0.000000, 0, 0, -3, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.93, 215.88 +CTUN, 336, 0.19, -0.02, 0.000000, 0, 0, -3, 336, 0 +GPS, 3, 308910800, 10, 1.49, 24.2398178, 54.5793111, -0.03, 9.46, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.93, 215.88 +CTUN, 337, 0.19, 0.09, 0.000000, 0, 0, -3, 337, 0 +DU32, 7, 393469 +CURR, 336, 15400, 1231, 0, 4752, 0.000000 +ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.93, 215.88 +CTUN, 336, 0.19, 0.01, 0.000000, 0, 0, -2, 337, 0 +GPS, 3, 308911000, 10, 1.49, 24.2398178, 54.5793111, -0.02, 9.46, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.93, 215.88 +CTUN, 336, 0.19, 0.01, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.94, 215.88 +CTUN, 337, 0.19, -0.02, 0.000000, 0, 0, -2, 337, 0 +GPS, 3, 308911200, 10, 1.49, 24.2398177, 54.5793111, -0.03, 9.47, 0.00, 347.24 +ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.94, 215.88 +CTUN, 337, 0.19, 0.03, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.28, 0.00, 0.82, 0.00, 215.94, 215.88 +CTUN, 336, 0.15, 0.09, 0.000000, 0, 0, -2, 336, 0 +GPS, 3, 308911400, 10, 1.49, 24.2398177, 54.5793112, -0.02, 9.48, 0.02, 347.24 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.95, 215.88 +CTUN, 337, 0.19, -0.05, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.95, 215.88 +CTUN, 337, 0.19, 0.02, 0.000000, 0, 0, -2, 337, 0 +GPS, 3, 308911600, 10, 1.49, 24.2398176, 54.5793112, -0.03, 9.48, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.95, 215.88 +CTUN, 336, 0.19, -0.01, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.95, 215.88 +CTUN, 337, 0.16, 0.08, 0.000000, 0, 0, -2, 337, 0 +GPS, 3, 308911800, 10, 1.49, 24.2398175, 54.5793112, -0.03, 9.48, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.96, 215.88 +CTUN, 337, 0.19, -0.01, 0.000000, 0, 0, -2, 337, 0 +DU32, 7, 393469 +CURR, 336, 18767, 1238, 0, 4772, 0.000000 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.96, 215.88 +CTUN, 336, 0.19, -0.02, 0.000000, 0, 0, -2, 336, 0 +GPS, 3, 308912000, 10, 1.49, 24.2398174, 54.5793113, -0.03, 9.49, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.96, 215.88 +CTUN, 336, 0.21, 0.10, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.96, 215.88 +CTUN, 337, 0.19, -0.01, 0.000000, 0, 0, -2, 337, 0 +GPS, 3, 308912200, 10, 1.49, 24.2398174, 54.5793113, -0.02, 9.49, 0.00, 347.24 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.96, 215.88 +CTUN, 336, 0.19, 0.07, 0.000000, 0, 0, -2, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.97, 215.88 +CTUN, 336, 0.15, 0.03, 0.000000, 0, 0, -2, 336, 0 +GPS, 3, 308912400, 10, 1.49, 24.2398173, 54.5793113, -0.02, 9.49, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.97, 215.88 +CTUN, 337, 0.16, 0.09, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.97, 215.88 +CTUN, 336, 0.15, 0.05, 0.000000, 0, 0, -2, 336, 0 +GPS, 3, 308912600, 10, 1.49, 24.2398172, 54.5793114, -0.01, 9.49, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 215.98, 215.88 +CTUN, 336, 0.16, 0.06, 0.000000, 0, 0, -2, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.98, 215.88 +CTUN, 337, 0.16, -0.01, 0.000000, 0, 0, -1, 337, 0 +GPS, 3, 308912800, 10, 1.49, 24.2398172, 54.5793114, -0.01, 9.49, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.98, 215.88 +CTUN, 336, 0.16, -0.01, 0.000000, 0, 0, -1, 336, 0 +DU32, 7, 393469 +CURR, 337, 22132, 1240, 0, 4752, 0.000000 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 215.98, 215.88 +CTUN, 337, 0.15, 0.05, 0.000000, 0, 0, -1, 337, 0 +GPS, 3, 308913000, 10, 1.49, 24.2398171, 54.5793114, -0.01, 9.50, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.99, 215.88 +CTUN, 337, 0.16, -0.03, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 215.99, 215.88 +CTUN, 336, 0.16, 0.01, 0.000000, 0, 0, -1, 336, 0 +GPS, 3, 308913200, 10, 1.49, 24.2398170, 54.5793114, -0.01, 9.50, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.99, 215.88 +CTUN, 337, 0.16, 0.04, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.99, 215.88 +CTUN, 336, 0.15, 0.09, 0.000000, 0, 0, -1, 336, 0 +GPS, 3, 308913400, 10, 1.49, 24.2398170, 54.5793114, -0.01, 9.50, 0.00, 347.24 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 216.00, 215.88 +CTUN, 336, 0.16, 0.03, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 216.00, 215.88 +CTUN, 337, 0.16, 0.04, 0.000000, 0, 0, -1, 337, 0 +GPS, 3, 308913600, 10, 1.49, 24.2398169, 54.5793115, 0.00, 9.50, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 216.00, 215.88 +CTUN, 336, 0.16, 0.04, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.01, 215.88 +CTUN, 336, 0.15, 0.06, 0.000000, 0, 0, -1, 336, 0 +GPS, 3, 308913800, 10, 1.49, 24.2398169, 54.5793115, 0.00, 9.51, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.01, 215.88 +CTUN, 337, 0.16, 0.05, 0.000000, 0, 0, -1, 337, 0 +DU32, 7, 393469 +CURR, 336, 25498, 1232, 0, 4793, 0.000000 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.01, 215.88 +CTUN, 336, 0.16, 0.11, 0.000000, 0, 0, -1, 336, 0 +GPS, 3, 308914000, 10, 1.49, 24.2398168, 54.5793115, 0.00, 9.50, 0.01, 347.24 +ATT, 0.00, 0.28, 0.00, 0.84, 0.00, 216.02, 215.88 +CTUN, 337, 0.16, 0.10, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.02, 215.88 +CTUN, 337, 0.15, 0.03, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 216.03, 215.88 +GPS, 3, 308914200, 10, 1.49, 24.2398168, 54.5793116, 0.00, 9.51, 0.01, 347.24 +CTUN, 336, 0.15, 0.00, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 216.03, 215.88 +CTUN, 337, 0.15, 0.03, 0.000000, 0, 0, -1, 337, 0 +GPS, 3, 308914400, 10, 1.49, 24.2398167, 54.5793116, 0.00, 9.51, 0.01, 347.24 +ATT, 0.00, 0.27, 0.00, 0.84, 0.00, 216.03, 215.88 +CTUN, 336, 0.15, 0.09, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.27, 0.00, 0.83, 0.00, 216.04, 215.88 +CTUN, 336, 0.15, 0.05, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308914600, 10, 1.49, 24.2398167, 54.5793116, 0.01, 9.51, 0.01, 347.24 +ATT, 0.00, 0.26, 0.00, 0.83, 0.00, 216.04, 215.88 +CTUN, 337, 0.15, 0.06, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 216.04, 215.88 +CTUN, 336, 0.15, 0.02, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308914800, 10, 1.49, 24.2398166, 54.5793117, 0.01, 9.51, 0.01, 347.24 +ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 216.04, 215.88 +CTUN, 337, 0.15, 0.10, 0.000000, 0, 0, 0, 337, 0 +DU32, 7, 393469 +CURR, 337, 28863, 1238, 0, 4752, 0.000000 +ATT, 0.00, 0.25, 0.00, 0.83, 0.00, 216.04, 215.88 +CTUN, 337, 0.15, 0.06, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308915000, 10, 1.49, 24.2398166, 54.5793117, 0.02, 9.51, 0.01, 347.24 +ATT, 0.00, 0.26, 0.00, 0.83, 0.00, 216.04, 215.88 +CTUN, 336, 0.20, 0.12, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.26, 0.00, 0.83, 0.00, 216.05, 215.88 +CTUN, 337, 0.20, 0.12, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308915200, 10, 1.49, 24.2398165, 54.5793117, 0.03, 9.52, 0.02, 347.24 +ATT, 0.00, 0.25, 0.00, 0.85, 0.00, 215.97, 215.88 +CTUN, 336, 0.22, 0.03, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.28, 0.00, 0.79, 0.00, 215.96, 215.88 +CTUN, 336, 0.22, 0.03, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308915400, 10, 1.49, 24.2398165, 54.5793117, 0.03, 9.52, 0.01, 347.24 +ATT, 0.00, 0.30, 0.00, 0.79, 0.00, 215.97, 215.88 +CTUN, 337, 0.35, 0.01, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.76, 0.00, 215.98, 215.88 +CTUN, 337, 0.35, 0.17, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308915600, 10, 1.49, 24.2398164, 54.5793117, 0.03, 9.52, 0.02, 347.24 +ATT, 0.00, 0.24, 0.00, 0.80, 0.00, 215.96, 215.88 +CTUN, 337, 0.35, 0.10, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.23, 0.00, 0.82, 0.00, 215.95, 215.88 +CTUN, 337, 0.35, 0.10, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308915800, 10, 1.49, 24.2398164, 54.5793118, 0.04, 9.53, 0.02, 347.24 +ATT, 0.00, 0.22, 0.00, 0.82, 0.00, 215.95, 215.88 +CTUN, 336, 0.35, 0.00, 0.000000, 0, 0, 0, 336, 0 +DU32, 7, 393469 +CURR, 337, 32229, 1235, 0, 4752, 0.000000 +ATT, 0.00, 0.23, 0.00, 0.81, 0.00, 215.95, 215.88 +CTUN, 336, 0.35, 0.14, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308916000, 10, 1.49, 24.2398164, 54.5793118, 0.04, 9.53, 0.02, 347.24 +ATT, 0.00, 0.22, 0.00, 0.82, 0.00, 215.94, 215.88 +CTUN, 337, 0.35, 0.09, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.24, 0.00, 0.82, 0.00, 215.94, 215.88 +CTUN, 337, 0.35, 0.11, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308916200, 10, 1.49, 24.2398163, 54.5793118, 0.05, 9.55, 0.02, 347.24 +ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 215.94, 215.88 +CTUN, 336, 0.35, -0.05, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.25, 0.00, 0.81, 0.00, 215.94, 215.88 +CTUN, 336, 0.35, 0.17, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308916400, 10, 1.49, 24.2398163, 54.5793118, 0.05, 9.55, 0.04, 347.24 +ATT, 0.00, 0.25, 0.00, 0.80, 0.00, 215.94, 215.88 +CTUN, 337, 0.35, 0.24, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.26, 0.00, 0.81, 0.00, 215.94, 215.88 +CTUN, 337, 0.35, 0.09, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308916600, 10, 1.49, 24.2398163, 54.5793118, 0.06, 9.56, 0.03, 347.24 +ATT, 0.00, 0.27, 0.00, 0.82, 0.00, 215.94, 215.88 +CTUN, 337, 0.35, 0.09, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.25, 0.00, 0.84, 0.00, 215.93, 215.88 +CTUN, 337, 0.35, 0.04, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308916800, 10, 1.49, 24.2398163, 54.5793118, 0.07, 9.56, 0.00, 347.24 +ATT, 0.00, 0.20, 0.00, 0.85, 0.00, 215.91, 215.88 +CTUN, 336, 0.35, 0.10, 0.000000, 0, 0, 0, 337, 0 +DU32, 7, 393469 +CURR, 337, 35594, 1230, 0, 4772, 0.000000 +ATT, 0.00, 0.24, 0.00, 0.84, 0.00, 215.92, 215.88 +CTUN, 336, 0.35, 0.07, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308917000, 10, 1.49, 24.2398162, 54.5793119, 0.07, 9.56, 0.02, 347.24 +ATT, 0.00, 0.23, 0.00, 0.84, 0.00, 215.91, 215.88 +CTUN, 337, 0.35, 0.05, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.21, 0.00, 0.82, 0.00, 215.91, 215.88 +CTUN, 337, 0.35, 0.16, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308917200, 10, 1.49, 24.2398160, 54.5793119, 0.07, 9.57, 0.05, 347.24 +ATT, 0.00, 0.26, 0.00, 0.81, 0.00, 215.91, 215.88 +CTUN, 336, 0.35, 0.11, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.20, 0.00, 0.84, 0.00, 215.89, 215.88 +CTUN, 336, 0.35, 0.11, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308917400, 10, 1.49, 24.2398160, 54.5793120, 0.08, 9.58, 0.03, 347.24 +ATT, 0.00, 0.23, 0.00, 0.80, 0.00, 215.91, 215.88 +CTUN, 337, 0.35, 0.04, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.21, 0.00, 0.85, 0.00, 215.89, 215.88 +CTUN, 336, 0.35, -0.03, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308917600, 10, 1.49, 24.2398159, 54.5793120, 0.07, 9.60, 0.02, 347.24 +ATT, 0.00, 0.28, 0.00, 0.83, 0.00, 215.90, 215.88 +CTUN, 337, 0.35, 0.06, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.19, 0.00, 0.86, 0.00, 215.87, 215.88 +CTUN, 337, 0.35, 0.02, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308917800, 10, 1.49, 24.2398159, 54.5793120, 0.07, 9.62, 0.01, 347.24 +ATT, 0.00, 0.26, 0.00, 0.82, 0.00, 215.89, 215.88 +CTUN, 336, 0.35, 0.11, 0.000000, 0, 0, 0, 337, 0 +DU32, 7, 393469 +CURR, 337, 38959, 1229, 0, 4772, 0.000000 +ATT, 0.00, 0.21, 0.00, 0.78, 0.00, 215.89, 215.88 +CTUN, 336, 0.35, 0.00, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308918000, 10, 1.49, 24.2398158, 54.5793121, 0.07, 9.64, 0.04, 347.24 +ATT, 0.00, 0.11, 0.00, 0.87, 0.00, 215.81, 215.88 +CTUN, 337, 0.35, 0.14, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.17, 0.00, 0.87, 0.00, 215.80, 215.88 +CTUN, 337, 0.35, 0.00, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308918200, 10, 1.49, 24.2398157, 54.5793121, 0.07, 9.66, 0.02, 347.24 +ATT, 0.00, 0.23, 0.00, 0.76, 0.00, 215.77, 215.88 +CTUN, 337, 0.35, 0.03, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.38, 0.00, 0.64, 0.00, 215.69, 215.88 +CTUN, 337, 0.35, 0.08, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308918400, 10, 1.49, 24.2398156, 54.5793121, 0.06, 9.67, 0.03, 347.24 +PM, 0, 0, 51, 5, 1000, 10908, 10, 0 +ATT, 0.00, 0.36, 0.00, 0.67, 0.00, 215.42, 215.88 +CTUN, 336, 0.35, 0.07, 0.000000, 0, 0, -1, 336, 0 +ATT, 0.00, 0.28, 0.00, 0.71, 0.00, 215.20, 215.88 +CTUN, 336, 0.34, 0.04, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308918600, 10, 1.49, 24.2398155, 54.5793121, 0.06, 9.68, 0.01, 347.24 +ATT, 0.00, 0.08, 0.00, 0.85, 0.00, 215.05, 215.88 +CTUN, 337, 0.35, 0.06, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.01, 0.00, 0.97, 0.00, 214.86, 215.88 +CTUN, 337, 0.35, 0.00, 0.000000, 0, 0, -1, 337, 0 +GPS, 3, 308918800, 10, 1.49, 24.2398154, 54.5793122, 0.06, 9.69, 0.01, 347.24 +ATT, 0.00, 0.25, 0.00, 0.89, 0.00, 214.92, 215.88 +CTUN, 336, 0.69, 0.14, 0.000000, 0, 0, 0, 337, 0 +DU32, 7, 393469 +CURR, 337, 42325, 1216, 0, 4752, 0.000000 +ATT, 0.00, 0.02, 0.00, 0.91, 0.00, 214.91, 215.88 +CTUN, 336, 0.69, -0.08, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308919000, 10, 1.49, 24.2398154, 54.5793122, 0.06, 9.69, 0.01, 347.24 +ATT, 0.00, 0.25, 0.00, 0.94, 0.00, 214.89, 215.88 +CTUN, 337, 0.69, -0.07, 0.000000, 0, 0, 0, 336, 0 +ATT, 0.00, 0.04, 0.00, 0.94, 0.00, 214.88, 215.88 +CTUN, 337, 0.69, -0.05, 0.000000, 0, 0, 0, 336, 0 +GPS, 3, 308919200, 10, 1.49, 24.2398153, 54.5793122, 0.04, 9.69, 0.02, 347.24 +ATT, 0.00, 0.12, 0.00, 0.90, 0.00, 214.91, 215.88 +CTUN, 337, 1.25, 0.00, 0.000000, 0, 0, 0, 337, 0 +ATT, 0.00, 0.20, 0.00, 0.92, 0.00, 214.89, 215.88 +CTUN, 337, 0.69, -0.03, 0.000000, 0, 0, 0, 337, 0 +GPS, 3, 308919400, 10, 1.49, 24.2398153, 54.5793122, 0.03, 9.70, 0.01, 347.24 +ATT, 0.00, 0.14, 0.00, 0.91, 0.00, 214.88, 215.88 +CTUN, 336, 0.69, -0.08, 0.000000, 0, 0, -1, 337, 0 +ATT, 0.00, 0.01, 0.00, 0.92, 0.00, 214.88, 215.88 +CTUN, 336, 0.69, -0.16, 0.000000, 0, 0, 2, 336, 0 +GPS, 3, 308919600, 10, 1.49, 24.2398152, 54.5793123, 0.02, 9.71, 0.01, 347.24 +ATT, 0.00, 0.03, 0.00, 0.87, 0.00, 214.99, 215.88 +CTUN, 337, 1.19, -0.05, 0.000000, 0, 0, 2, 336, 0 +ATT, 0.00, 0.02, 0.00, 0.88, 0.00, 215.15, 215.88 +CTUN, 337, 0.88, 0.00, 0.000000, 0, 0, 3, 337, 0 +GPS, 3, 308919800, 10, 1.49, 24.2398151, 54.5793123, 0.01, 9.71, 0.01, 347.24 +ATT, 0.00, 0.13, 0.00, 0.84, 0.00, 215.28, 215.88 +CTUN, 336, 0.88, -0.10, 0.000000, 0, 0, 3, 337, 0 +DU32, 7, 393469 +CURR, 337, 45691, 1220, 0, 4772, 0.000000 +ATT, 0.00, 0.00, 0.00, 0.82, 0.00, 215.37, 215.88 +CTUN, 337, 0.49, -0.06, 0.000000, 0, 0, 3, 337, 0 +GPS, 3, 308920000, 10, 1.49, 24.2398151, 54.5793123, 0.01, 9.72, 0.00, 347.24 +ATT, 0.00, 0.10, 0.00, 0.80, 0.00, 215.44, 215.88 +CTUN, 336, 0.64, -0.08, 0.000000, 0, 0, 5, 337, 0 +ATT, 0.00, 0.00, 0.00, 0.78, 0.00, 215.54, 215.88 +CTUN, 336, 0.49, -0.04, 0.000000, 0, 0, 3, 336, 0 +GPS, 3, 308920200, 10, 1.49, 24.2398150, 54.5793123, 0.01, 9.72, 0.00, 347.24 +ATT, 0.00, 0.20, 0.00, 0.71, 0.00, 215.97, 215.88 +CTUN, 337, 0.49, -0.09, 0.000000, 0, 0, 5, 336, 0 +ATT, 0.00, -0.10, 0.00, 0.66, 0.00, 216.60, 215.88 +CTUN, 337, 0.43, -0.09, 0.000000, 0, 0, 5, 337, 0 +GPS, 3, 308920400, 10, 1.49, 24.2398150, 54.5793124, 0.01, 9.73, 0.02, 347.24 +ATT, 0.00, -0.06, 0.00, 0.70, 0.00, 217.03, 215.88 +CTUN, 337, 0.43, -0.18, 0.000000, 0, 0, 2, 336, 0 +ATT, 0.00, -0.09, 0.00, 0.69, 0.00, 217.94, 215.88 +CTUN, 337, 0.41, -0.02, 0.000000, 0, 0, 6, 337, 0 +GPS, 3, 308920600, 10, 1.49, 24.2398149, 54.5793124, 0.00, 9.73, 0.01, 347.24 +ATT, 0.00, -0.06, 0.00, 0.65, 0.00, 218.82, 215.88 +CTUN, 336, 0.41, -0.16, 0.000000, 0, 0, 8, 336, 0 +ATT, 0.00, -0.13, 0.00, 0.64, 0.00, 219.48, 215.88 +CTUN, 336, 0.41, -0.11, 0.000000, 0, 0, 7, 337, 0 +GPS, 3, 308920800, 10, 1.49, 24.2398149, 54.5793125, 0.00, 9.74, 0.02, 347.24 +ATT, 0.00, -0.24, 0.00, 0.69, 0.00, 220.07, 215.88 +CTUN, 337, 0.68, -0.09, 0.000000, 0, 0, 6, 336, 0 +DU32, 7, 393469 +CURR, 336, 49056, 1201, 0, 4752, 0.000000 +ATT, 0.00, -0.17, 0.00, 0.66, 0.00, 220.69, 215.88 +CTUN, 337, 0.41, -0.20, 0.000000, 0, 0, 5, 336, 0 +GPS, 3, 308921000, 10, 1.49, 24.2398148, 54.5793126, 0.00, 9.74, 0.02, 347.24 +ATT, 0.00, 0.05, 0.00, 0.62, 0.00, 221.21, 215.88 +CTUN, 337, 0.41, -0.22, 0.000000, 0, 0, 10, 337, 0 +ATT, 0.00, 0.00, 0.00, 0.58, 0.00, 221.55, 215.88 +CTUN, 337, 0.22, -0.19, 0.000000, 0, 0, 13, 337, 0 +GPS, 3, 308921200, 10, 1.49, 24.2398147, 54.5793126, 0.00, 9.75, 0.01, 347.24 +ATT, 0.00, -0.22, 0.00, 0.61, 0.00, 222.01, 215.88 +CTUN, 336, 0.33, -0.08, 0.000000, 0, 0, 11, 337, 0 +ATT, 0.00, 0.08, 0.00, 0.58, 0.00, 222.34, 215.88 +CTUN, 336, 0.24, -0.23, 0.000000, 0, 0, 10, 336, 0 +GPS, 3, 308921400, 10, 1.49, 24.2398146, 54.5793126, 0.01, 9.75, 0.02, 347.24 +ATT, 0.00, -0.17, 0.00, 0.55, 0.00, 223.00, 215.88 +CTUN, 337, 0.33, -0.06, 0.000000, 0, 0, 13, 337, 0 +ATT, 0.00, -0.14, 0.00, 0.55, 0.00, 224.15, 215.88 +CTUN, 337, 0.29, -0.17, 0.000000, 0, 0, 14, 337, 0 +GPS, 3, 308921600, 10, 1.49, 24.2398145, 54.5793127, 0.02, 9.76, 0.02, 347.24 +ATT, 0.00, -0.12, 0.00, 0.48, 0.00, 225.74, 215.88 +CTUN, 336, 0.29, -0.39, 0.000000, 0, 0, 20, 337, 0 +ATT, 0.00, -0.42, 0.00, 0.48, 0.00, 227.00, 217.00 +CTUN, 336, 0.29, -0.12, 0.000000, 0, 0, 16, 337, 0 +GPS, 3, 308921800, 10, 1.49, 24.2398144, 54.5793128, 0.02, 9.77, 0.03, 347.24 +ATT, 0.00, -0.45, 0.00, 0.49, 0.00, 227.95, 217.95 +CTUN, 337, 0.36, -0.14, 0.000000, 0, 0, 16, 336, 0 +DU32, 7, 393469 +CURR, 337, 52423, 1180, 0, 4772, 0.000000 +ATT, 0.00, -0.38, 0.00, 0.45, 0.00, 228.77, 218.77 +CTUN, 337, 0.29, -0.20, 0.000000, 0, 0, 16, 336, 0 +GPS, 3, 308922000, 10, 1.49, 24.2398144, 54.5793129, 0.04, 9.79, 0.04, 347.24 +ATT, 0.00, -0.33, 0.00, 0.47, 0.00, 229.63, 219.63 +CTUN, 337, 0.33, -0.27, 0.000000, 0, 0, 18, 337, 0 +MODE, AUTO, 501 +ATT, 0.00, -0.35, 0.00, 0.47, 0.00, 230.26, 220.26 +CTUN, 336, 0.29, -0.25, 0.000000, 0, 0, 15, 337, 0 +CMD, 8, 1, 22, 1, 0, 7.62, 0.0000000, 0.0000000 +GPS, 3, 308922200, 10, 1.49, 24.2398143, 54.5793129, 0.03, 9.80, 0.03, 347.24 +ATT, -0.27, -0.38, 0.40, 0.46, 0.00, 230.74, 220.75 +NTUN, 0.00, 0.00, 11.218952, -3.977892, 11.218952, -3.977892, 10.711962, -2.335319, 0.000000, -1.000000, 0.03, -0.04 +CTUN, 336, 0.29, 0.25, 0.040093, 0, 0, 18, 475, 0 +ATT, 0.03, -0.69, -0.04, 0.71, 0.00, 229.13, 220.75 +NTUN, 0.00, 2.30, 10.713371, -4.404589, 10.713371, -4.404589, 13.511226, -0.950545, -7.055809, -7.266968, -0.03, -0.59 +CTUN, 337, 0.24, -0.39, 0.103789, 0, 0, 19, 475, 0 +GPS, 3, 308922400, 10, 1.49, 24.2398142, 54.5793129, 0.06, 9.80, 0.01, 347.24 +NTUN, 0.01, 2.23, 10.114662, -4.769110, 10.114662, -4.769110, 9.784394, 1.857668, -5.927813, -9.609119, 0.12, -0.64 +ATT, 0.12, -0.40, -0.64, 0.44, 0.00, 227.60, 220.75 +CTUN, 337, 0.29, -0.07, 0.219127, 0, 0, 21, 474, 0 +NTUN, 0.02, 2.61, 11.860283, -7.375818, 11.860283, -7.375818, -32.844906, 41.576733, 63.283371, -75.808990, 5.70, -0.72 +ATT, 5.70, -0.36, -0.72, 0.39, 0.00, 227.01, 220.75 +CTUN, 337, 0.25, -0.23, 0.385470, 0, 0, 22, 461, 0 +GPS, 3, 308922600, 10, 1.49, 24.2398142, 54.5793129, 0.07, 9.80, 0.03, 347.24 +NTUN, 0.10, 3.01, 17.227455, -13.677666, 17.227455, -13.677666, -57.575172, 73.119659, 132.671720, -156.018480, 11.72, -1.31 +CTUN, 337, 0.29, -0.22, 0.600166, 0, 0, 19, 448, 0 +ATT, 11.72, -0.14, -1.31, 0.30, 0.00, 226.57, 220.75 +NTUN, 0.20, 3.07, 24.158928, -21.701262, 24.158928, -21.701262, -63.983826, 77.550827, 167.314730, -191.235960, 14.47, -1.32 +CTUN, 337, 0.25, 0.00, 0.850166, 0, 0, 30, 465, 0 +ATT, 14.47, 0.05, -1.32, 0.17, 0.00, 226.15, 220.75 +GPS, 3, 308922800, 10, 1.49, 24.2398141, 54.5793129, 0.09, 9.79, 0.00, 347.24 +NTUN, 0.32, 3.08, 30.639336, -29.468784, 30.639336, -29.468784, -60.517593, 79.337593, 169.162450, -201.906160, 14.96, -1.53 +CTUN, 337, 0.25, -0.06, 1.102666, 0, 0, -5, 559, 0 +ATT, 14.96, 0.81, -1.53, -0.03, 0.00, 224.97, 220.75 +DU32, 7, 393457 +CURR, 337, 56271, 1193, 0, 4772, 0.000000 +NTUN, 0.32, 3.08, 36.171207, -36.663116, 36.171207, -36.663116, -55.220253, 79.798508, 165.318730, -210.943330, 15.20, -1.62 +CTUN, 336, 0.21, -0.34, 1.325662, 0, 0, -32, 584, 0 +ATT, 15.20, 3.82, -1.62, -0.91, 0.00, 223.10, 220.75 +GPS, 3, 308923000, 10, 1.49, 24.2398141, 54.5793129, 0.04, 9.79, 0.02, 347.24 +NTUN, 0.43, 3.08, 40.619099, -43.098080, 40.619099, -43.098080, -48.493973, 77.544411, 156.928190, -213.999630, 15.06, -1.62 +CTUN, 336, 0.22, -0.69, 1.495320, 0, 0, -80, 668, 0 +ATT, 15.06, 9.83, -1.62, -0.76, 0.00, 220.03, 220.75 +NTUN, 0.51, 3.08, 43.333050, -48.299927, 43.333050, -48.299927, -37.055912, 72.857292, 133.870800, -207.503430, 14.05, -1.51 +CTUN, 336, 0.22, -1.29, 1.629664, 0, 2, -123, 720, 0 +GPS, 3, 308923200, 10, 1.49, 24.2398141, 54.5793128, -0.23, 9.80, 0.08, 347.24 +ATT, 14.05, 12.60, -1.51, -0.55, 0.00, 215.68, 220.75 +NTUN, 0.58, 3.06, 44.808475, -52.193821, 44.808475, -52.193821, -35.111961, 69.787422, 124.754260, -200.938930, 13.54, -0.72 +CTUN, 337, 0.27, -1.39, 1.771228, 0, 2, -105, 704, 0 +ATT, 13.54, 13.52, -0.72, -0.37, 0.00, 211.73, 220.75 +NTUN, 0.62, 3.05, 46.255318, -55.617573, 46.255318, -55.617573, -45.501850, 79.744339, 141.468410, -217.237520, 14.80, 0.43 +CTUN, 337, 0.27, -0.77, 1.905869, 0, 4, -113, 772, 0 +GPS, 3, 308923400, 10, 1.49, 24.2398144, 54.5793123, -0.56, 9.85, 0.30, 319.33 +ATT, 14.80, 14.20, 0.43, -0.22, 0.00, 208.85, 218.85 +NTUN, 0.67, 3.05, 48.271881, -59.620163, 48.271881, -59.620163, -50.871349, 89.512306, 159.965970, -243.629610, 16.49, 1.40 +CTUN, 337, 0.27, -0.60, 2.068352, 0, 3, -89, 734, 0 +ATT, 16.49, 16.11, 1.40, -0.33, 0.00, 205.41, 215.41 +NTUN, 0.71, 3.04, 49.271904, -61.951389, 49.271904, -61.951389, -38.100204, 64.007118, 142.000230, -210.312260, 14.33, 2.32 +CTUN, 337, 0.21, -0.12, 2.252397, 0, 5, -70, 755, 0 +GPS, 3, 308923600, 10, 1.49, 24.2398150, 54.5793112, -0.72, 10.00, 0.73, 306.76 +NTUN, 0.72, 3.04, 48.655746, -60.892334, 48.655746, -60.892334, -28.088583, 37.604218, 118.838420, -153.409450, 10.67, 3.42 +ATT, 10.67, 17.76, 3.42, -0.88, 0.00, 199.71, 209.71 +CTUN, 336, 0.27, 0.30, 2.449948, 0, 6, -54, 767, 0 +NTUN, 0.68, 3.05, 46.551796, -55.633720, 46.551796, -55.633720, -19.507681, 5.990871, 97.168808, -77.934525, 5.94, 4.15 +ATT, 5.94, 16.97, 4.15, 0.10, 0.00, 195.99, 205.99 +CTUN, 337, 0.27, 0.59, 2.665683, 0, 6, -32, 777, 0 +GPS, 3, 308923800, 10, 1.49, 24.2398158, 54.5793091, -0.70, 10.25, 1.24, 300.06 +NTUN, 0.59, 3.08, 43.153175, -46.478767, 43.153175, -46.478767, -11.677929, -20.816683, 75.013794, -4.450470, 1.17, 4.22 +CTUN, 337, 0.43, 1.01, 2.904601, 0, 4, -7, 782, 0 +ATT, 1.17, 13.00, 4.22, 1.26, 0.00, 190.75, 200.75 +NTUN, 0.47, 3.13, 38.527103, -33.728680, 38.527103, -33.728680, -6.010324, -38.518227, 54.739281, 60.500877, -3.08, 3.62 +CTUN, 336, 0.43, 1.11, 3.154601, 0, 2, 17, 757, 0 +ATT, -3.08, 9.62, 3.62, 1.78, 0.00, 185.95, 195.95 +GPS, 3, 308924000, 10, 1.49, 24.2398171, 54.5793063, -0.51, 10.58, 1.69, 298.24 +NTUN, 0.32, 3.25, 32.901154, -19.003736, 32.901154, -19.003736, -1.999703, -49.658333, 37.297527, 106.791500, -6.12, 2.40 +CTUN, 336, 0.74, 1.29, 3.407101, 0, 1, 35, 774, 0 +ATT, -6.12, 5.27, 2.40, 1.47, 0.00, 179.42, 189.42 +DU32, 7, 393457 +CURR, 336, 64256, 1182, 0, 4772, 0.000000 +NTUN, 0.21, 3.52, 26.379150, -3.019579, 26.379150, -3.019579, 2.681522, -52.334209, 17.779968, 141.841570, -8.27, 0.58 +CTUN, 337, 0.74, 1.43, 3.657101, 0, 0, 53, 756, 0 +ATT, -8.27, 1.95, 0.58, 0.36, 0.00, 174.20, 184.20 +GPS, 3, 308924200, 10, 1.49, 24.2398184, 54.5793029, -0.22, 10.96, 1.98, 296.41 +NTUN, 0.19, 0.42, 19.461609, 13.211496, 19.461609, 13.211496, 2.641173, -49.726601, 8.509491, 159.703700, -9.22, -0.86 +CTUN, 337, 1.11, 1.51, 3.909601, 0, 0, 67, 764, 0 +ATT, -9.22, -0.57, -0.86, -1.05, 0.00, 168.40, 178.40 +NTUN, 0.30, 0.75, 12.316704, 29.346365, 12.316704, 29.346365, 2.225170, -42.407974, -0.449051, 172.348680, -9.71, -2.26 +CTUN, 336, 1.11, 1.72, 4.159601, 0, 0, 81, 747, 0 +GPS, 3, 308924400, 10, 1.49, 24.2398194, 54.5792996, 0.11, 11.43, 1.85, 294.24 +ATT, -9.71, -1.76, -2.26, -2.22, 0.00, 163.64, 173.64 +NTUN, 0.45, 0.88, 5.230618, 44.963272, 5.230618, 44.963272, 0.001821, -35.019409, -3.860863, 179.169070, -9.82, -3.31 +CTUN, 337, 1.48, 1.82, 4.409601, 0, 0, 91, 738, 0 +ATT, -9.82, -2.90, -3.31, -3.59, 0.00, 158.77, 168.77 +NTUN, 0.60, 0.95, -1.634468, 60.041031, -1.634468, 60.041031, -0.001427, -28.209909, -6.971146, 186.284730, -9.84, -4.38 +CTUN, 336, 1.48, 1.61, 4.662101, 0, 0, 99, 739, 0 +GPS, 3, 308924600, 10, 1.49, 24.2398205, 54.5792968, 0.48, 11.92, 1.62, 294.03 +NTUN, 0.74, 0.98, -8.212360, 73.966217, -8.212360, 73.966217, -3.756350, -18.413843, -8.778923, 184.251860, -9.30, -5.22 +ATT, -9.30, -3.57, -5.22, -4.75, 0.00, 153.21, 163.21 +CTUN, 337, 2.09, 1.77, 4.912101, 0, 0, 96, 743, 0 +NTUN, 0.88, 1.01, -14.399727, 86.876389, -14.399727, 86.876389, -5.825308, -9.867271, -8.873665, 183.101720, -8.80, -5.92 +ATT, -8.80, -4.30, -5.92, -5.27, 0.00, 148.58, 158.58 +CTUN, 337, 2.09, 1.97, 5.162101, 0, 1, 95, 755, 0 +GPS, 3, 308924800, 10, 1.49, 24.2398215, 54.5792945, 0.80, 12.47, 1.35, 295.04 +NTUN, 1.01, 1.03, -20.399529, 98.552238, -20.399529, 98.552238, -7.452480, 2.692262, -11.403973, 173.602480, -7.78, -6.38 +ATT, -7.78, -3.98, -6.38, -6.82, 0.00, 143.21, 153.21 +CTUN, 336, 2.60, 2.37, 5.414601, 0, 1, 90, 748, 0 +NTUN, 1.12, 1.04, -26.136154, 108.671780, -26.136154, 108.671780, -9.283962, 12.756130, -13.945713, 164.217620, -6.68, -6.80 +ATT, -6.68, -2.19, -6.80, -7.40, 0.00, 137.88, 147.88 +CTUN, 336, 2.60, 2.31, 5.662101, 0, 1, 95, 750, 0 +GPS, 3, 308925000, 10, 1.49, 24.2398222, 54.5792931, 1.16, 12.98, 0.86, 296.31 +NTUN, 1.21, 1.05, -31.199333, 117.238420, -31.199333, 117.238420, -14.625351, 20.909149, -7.130482, 152.818180, -5.79, -6.71 +CTUN, 336, 2.60, 2.40, 5.914601, 0, 1, 94, 745, 0 +ATT, -5.79, -1.57, -6.71, -7.17, 0.00, 130.78, 140.78 +DU32, 7, 393457 +CURR, 337, 70992, 1190, 0, 4793, 0.000000 +NTUN, 1.21, 1.05, -35.632408, 124.528680, -35.632408, 124.528680, -18.183670, 29.583235, -2.891830, 143.180790, -4.95, -6.67 +CTUN, 336, 2.60, 2.36, 6.167102, 0, 1, 96, 757, 0 +ATT, -4.95, -1.63, -6.67, -6.83, 0.00, 125.26, 135.26 +GPS, 3, 308925200, 9, 1.75, 24.2398225, 54.5792924, 1.49, 13.47, 0.39, 296.63 +NTUN, 1.31, 1.06, -39.379242, 130.261660, -39.379242, 130.261660, -19.753963, 39.608944, 0.531662, 128.329790, -4.03, -6.27 +CTUN, 336, 3.55, 2.62, 6.417102, 0, 0, 90, 757, 0 +ATT, -4.03, -0.47, -6.27, -6.37, 0.00, 119.93, 129.93 +NTUN, 1.37, 1.07, -42.720036, 134.703310, -42.720036, 134.703310, -21.511440, 44.773178, 1.592064, 119.416500, -3.25, -6.13 +CTUN, 337, 3.55, 2.74, 6.667102, 0, 0, 97, 754, 0 +ATT, -3.25, 0.73, -6.13, -5.58, 0.00, 114.31, 124.31 +GPS, 3, 308925400, 9, 1.75, 24.2398226, 54.5792924, 1.79, 13.94, 0.08, 296.63 +NTUN, 1.42, 1.08, -45.298603, 137.802640, -45.298603, 137.802640, -26.134127, 48.733604, 10.214325, 109.993350, -2.90, -5.73 +CTUN, 337, 3.98, 2.70, 6.917102, 0, 0, 93, 764, 0 +ATT, -2.90, 0.19, -5.73, -4.61, 0.00, 107.84, 117.84 +NTUN, 1.46, 1.08, -47.455734, 139.961940, -47.455734, 139.961940, -25.275766, 53.548508, 10.428688, 102.593020, -2.25, -5.56 +CTUN, 336, 3.98, 2.77, 7.167101, 0, 0, 100, 759, 0 +GPS, 3, 308925600, 9, 1.75, 24.2398227, 54.5792929, 2.10, 14.41, 0.28, 332.29 +ATT, -2.25, 1.29, -5.56, -3.70, 0.00, 102.13, 112.13 +NTUN, 1.48, 1.08, -49.309723, 140.972290, -49.309723, 140.972290, -28.058275, 57.373024, 13.643677, 92.003418, -1.80, -5.10 +CTUN, 336, 4.48, 2.89, 7.419602, 0, 0, 108, 741, 0 +ATT, -1.80, 0.60, -5.10, -2.00, 0.00, 95.91, 105.91 +NTUN, 1.49, 1.09, -50.613499, 141.347290, -50.613476, 141.347230, -30.500196, 55.526684, 18.962471, 90.749390, -1.59, -5.16 +CTUN, 337, 4.48, 2.99, 7.620000, 0, 0, 116, 750, 0 +GPS, 3, 308925800, 9, 1.75, 24.2398227, 54.5792940, 2.40, 14.92, 0.55, 70.72 +NTUN, 1.50, 1.09, -51.421017, 140.849030, -51.421017, 140.849030, -29.381805, 53.628754, 20.924591, 88.018005, -1.27, -5.11 +ATT, -1.27, 0.39, -5.11, -1.46, 0.00, 90.05, 100.05 +CTUN, 337, 4.95, 3.11, 7.620000, 0, 0, 115, 747, 0 +NTUN, 1.49, 1.10, -52.096004, 139.980100, -52.096004, 139.980100, -31.509203, 51.498936, 23.250122, 90.310730, -0.92, -5.35 +ATT, -0.92, 0.69, -5.35, -0.55, 0.00, 84.79, 94.79 +CTUN, 337, 4.95, 3.33, 7.620000, 0, 0, 118, 747, 0 +GPS, 3, 308926000, 9, 1.75, 24.2398225, 54.5792956, 2.71, 15.41, 0.78, 88.33 +NTUN, 1.49, 1.10, -52.243824, 138.460830, -52.243824, 138.460830, -32.563969, 47.538269, 28.536440, 89.957703, -0.74, -5.44 +ATT, -0.74, 0.14, -5.44, -0.04, 0.00, 78.57, 88.57 +CTUN, 337, 5.39, 3.45, 7.620000, 0, 0, 118, 745, 0 +DU32, 7, 393457 +CURR, 337, 78518, 1160, 0, 4793, 0.000000 +NTUN, 1.47, 1.10, -52.255611, 136.714970, -52.255611, 136.714970, -32.073730, 43.795528, 27.882126, 94.541351, -0.16, -5.73 +ATT, -0.16, 0.10, -5.73, -0.53, 0.00, 73.89, 83.89 +CTUN, 337, 5.39, 4.04, 7.620000, 0, 0, 114, 758, 0 +GPS, 3, 308926200, 9, 1.75, 24.2398222, 54.5792973, 3.03, 15.90, 0.90, 95.35 +NTUN, 1.46, 1.10, -52.129230, 134.307950, -52.129230, 134.307950, -30.638874, 40.429138, 27.251297, 94.168190, 0.27, -5.70 +CTUN, 337, 5.89, 4.20, 7.620000, 0, 0, 112, 752, 0 +ATT, 0.27, 0.03, -5.70, -0.13, 0.00, 69.34, 79.34 +NTUN, 1.43, 1.11, -52.000767, 131.609650, -52.000767, 131.609650, -29.517799, 38.308655, 25.271917, 95.284126, 0.74, -5.69 +CTUN, 336, 5.89, 4.27, 7.620000, 0, 0, 117, 742, 0 +ATT, 0.74, 0.38, -5.69, 0.62, 0.00, 66.11, 76.11 +GPS, 3, 308926400, 9, 1.75, 24.2398220, 54.5792992, 3.38, 16.38, 0.98, 96.46 +NTUN, 1.41, 1.11, -51.653019, 128.308790, -51.653019, 128.308790, -31.440739, 34.503742, 28.512604, 93.658005, 0.85, -5.63 +CTUN, 336, 6.37, 4.26, 7.620000, 0, 0, 119, 728, 0 +ATT, 0.85, 0.61, -5.63, 1.29, 0.00, 62.14, 72.14 +NTUN, 1.37, 1.12, -50.923923, 124.796460, -50.923923, 124.796460, -35.667393, 30.531456, 36.218765, 98.224464, 0.93, -6.02 +CTUN, 337, 6.36, 4.41, 7.620000, 0, 0, 122, 713, 0 +GPS, 3, 308926600, 9, 1.75, 24.2398219, 54.5793012, 3.72, 16.80, 1.05, 96.14 +ATT, 0.93, 0.84, -6.02, 0.72, 0.00, 58.49, 68.49 +NTUN, 1.33, 1.12, -49.743343, 120.744250, -49.743343, 120.744250, -40.779099, 26.487364, 46.805801, 96.477844, 0.67, -6.20 +CTUN, 336, 6.37, 4.65, 7.620000, 0, 0, 125, 705, 0 +ATT, 0.67, 1.27, -6.20, -0.29, 0.00, 55.75, 65.75 +NTUN, 1.28, 1.12, -48.143864, 116.237610, -48.143864, 116.237610, -43.524288, 27.768135, 54.994797, 90.933624, 0.34, -6.17 +CTUN, 336, 6.37, 4.90, 7.620000, 0, 0, 121, 700, 0 +GPS, 3, 308926800, 9, 1.75, 24.2398217, 54.5793032, 4.06, 17.27, 1.01, 95.51 +ATT, 0.34, 0.99, -6.17, -0.34, 0.00, 54.99, 64.97 +NTUN, 1.23, 1.12, -46.206898, 110.840710, -46.206898, 110.840710, -46.630077, 29.135546, 62.177879, 79.565384, -0.31, -5.87 +CTUN, 336, 6.40, 5.13, 7.620000, 0, 0, 120, 692, 0 +ATT, -0.31, 0.03, -5.87, 0.42, 0.00, 55.29, 64.97 +NTUN, 1.16, 1.12, -43.860149, 104.948150, -43.860149, 104.948150, -50.085506, 28.113409, 73.467484, 73.074371, -1.10, -5.93 +CTUN, 337, 6.37, 5.41, 7.620000, 0, 0, 108, 692, 0 +GPS, 3, 308927000, 9, 1.75, 24.2398214, 54.5793053, 4.40, 17.71, 1.10, 97.63 +NTUN, 1.10, 1.12, -41.227871, 98.620377, -41.227871, 98.620377, -55.015835, 22.805412, 83.322784, 71.722260, -1.74, -6.15 +ATT, -1.74, -0.15, -6.15, 0.87, 0.00, 56.51, 64.97 +CTUN, 336, 6.38, 5.46, 7.620000, 0, 0, 104, 694, 0 +NTUN, 1.02, 1.12, -38.109997, 92.186981, -38.109997, 92.186981, -58.721611, 20.467167, 96.178741, 69.666046, -2.47, -6.45 +ATT, -2.47, -0.48, -6.45, 0.64, 0.00, 56.90, 64.97 +CTUN, 337, 6.38, 6.00, 7.620000, 0, 0, 90, 689, 0 +GPS, 3, 308927200, 10, 1.49, 24.2398210, 54.5793073, 4.72, 18.15, 1.05, 100.52 +DU32, 7, 393457 +CURR, 337, 85641, 1159, 0, 4813, 0.000000 +NTUN, 0.95, 1.12, -34.733585, 85.588089, -34.733585, 85.588089, -60.522694, 18.144802, 104.429810, 67.664436, -2.92, -6.62 +ATT, -2.92, -0.64, -6.62, 0.36, 0.00, 56.78, 64.97 +CTUN, 337, 6.38, 5.98, 7.620000, 0, 0, 87, 696, 0 +NTUN, 0.87, 1.11, -31.123348, 78.877258, -31.123348, 78.877258, -63.045300, 16.728363, 115.102370, 64.891693, -3.53, -6.82 +ATT, -3.53, -1.14, -6.82, 0.32, 0.00, 56.76, 64.97 +CTUN, 336, 4.85, 6.34, 7.620000, 0, 0, 74, 699, 0 +GPS, 3, 308927400, 10, 1.49, 24.2398206, 54.5793095, 5.01, 18.53, 1.12, 102.55 +NTUN, 0.77, 1.10, -27.452015, 71.775650, -27.452015, 71.775650, -65.387444, 12.132516, 123.349840, 61.687050, -4.07, -6.91 +CTUN, 337, 5.82, 6.61, 7.620000, 0, 0, 69, 703, 0 +ATT, -4.07, -2.28, -6.91, -0.15, 0.00, 56.83, 64.97 +NTUN, 0.77, 1.10, -23.884335, 64.599396, -23.884335, 64.599396, -64.279190, 10.584182, 127.676800, 57.237457, -4.42, -6.83 +CTUN, 337, 5.82, 6.81, 7.620000, 0, 0, 58, 705, 0 +ATT, -4.42, -2.81, -6.83, -0.39, 0.00, 57.05, 64.97 +GPS, 3, 308927600, 10, 1.49, 24.2398199, 54.5793115, 5.33, 18.88, 1.12, 105.99 +NTUN, 0.67, 1.10, -20.357830, 57.300983, -20.357830, 57.300983, -62.516785, 7.539318, 131.265050, 54.015877, -4.68, -6.80 +CMD, 8, 2, 16, 1, 0, 7.62, 24.2398304, 54.5793472 +CTUN, 337, 6.31, 6.91, 7.620000, 0, 0, 54, 717, 0 +ATT, -3.09, -3.05, -0.55, -0.58, 0.00, 56.89, 66.77 +NTUN, 0.00, 0.69, -15.613808, 52.703514, -15.613808, 52.703514, -59.282318, 6.241214, 145.970520, 80.480499, -4.54, -8.54 +CTUN, 337, 6.31, 7.17, 7.620000, 0, 0, 46, 703, 0 +ATT, -4.54, -2.91, -8.54, -0.34, 0.00, 56.81, 69.72 +GPS, 3, 308927800, 9, 1.75, 24.2398194, 54.5793134, 5.60, 19.19, 1.05, 107.00 +NTUN, 4.30, 0.68, -10.121582, 50.594215, -10.121582, 50.594215, -57.730812, 4.638804, 160.477020, 105.693950, -4.54, -10.15 +CTUN, 336, 6.31, 7.37, 7.620000, 0, 0, 42, 727, 0 +ATT, -4.54, -4.49, -10.15, 0.71, 0.00, 58.72, 69.72 +NTUN, 4.24, 0.68, -3.537167, 51.296951, -3.537167, 51.296951, -54.789848, -2.309740, 177.844150, 145.027360, -4.64, -12.37 +CTUN, 336, 3.58, 7.44, 7.620000, 0, 0, 36, 714, 0 +GPS, 3, 308928000, 10, 1.49, 24.2398190, 54.5793154, 5.88, 19.47, 1.05, 105.62 +ATT, -4.64, -3.70, -12.37, -2.10, 0.00, 60.14, 69.72 +NTUN, 4.18, 0.67, 3.965332, 55.457954, 3.965332, 55.457954, -49.233303, -4.116338, 190.553910, 187.794140, -4.16, -14.72 +CTUN, 336, 4.63, 7.53, 7.620000, 0, 0, 41, 713, 0 +ATT, -4.16, -2.41, -14.72, -4.75, 0.00, 59.52, 69.72 +NTUN, 4.12, 0.66, 11.225163, 59.944443, 11.225163, 59.944443, -42.349426, 1.907382, 192.331620, 194.318070, -3.89, -15.12 +CTUN, 337, 4.63, 7.62, 7.620000, 0, 0, 34, 714, 0 +GPS, 3, 308928200, 10, 1.49, 24.2398186, 54.5793171, 6.16, 19.72, 0.89, 105.29 +DU32, 7, 393457 +CURR, 336, 92052, 1164, 0, 4752, 0.000000 +NTUN, 4.05, 0.66, 18.320229, 64.669800, 18.320229, 64.669800, -36.724842, 9.730409, 193.559480, 194.327030, -3.95, -15.15 +ATT, -3.95, -2.02, -15.15, -6.20, 0.00, 59.51, 69.72 +CTUN, 337, 6.05, 7.64, 7.620000, 0, 0, 32, 720, 0 +NTUN, 3.96, 0.65, 25.009930, 68.819839, 25.009930, 68.819839, -30.619263, 17.709455, 194.572740, 188.919590, -4.21, -14.91 +ATT, -4.21, -2.24, -14.91, -6.98, 0.00, 59.76, 69.72 +CTUN, 336, 6.05, 7.81, 7.620000, 0, 0, 25, 723, 0 +GPS, 3, 308928400, 10, 1.49, 24.2398184, 54.5793191, 6.39, 19.98, 1.02, 100.04 +PM, 0, 0, 50, 40, 1001, 11692, 7, 0 +NTUN, 3.87, 0.64, 31.593376, 73.129684, 31.593376, 73.129684, -22.604809, 27.677116, 194.834470, 186.098450, -4.29, -14.79 +ATT, -4.29, -2.15, -14.79, -7.78, 0.00, 59.75, 69.72 +CTUN, 337, 6.35, 7.91, 7.620000, 0, 1, 20, 734, 0 +NTUN, 3.76, 0.64, 38.097515, 77.597168, 38.097515, 77.597168, -14.265009, 38.502377, 193.397420, 183.232510, -4.33, -14.61 +ATT, -4.33, -2.08, -14.61, -8.12, 0.00, 59.77, 69.72 +CTUN, 337, 6.35, 7.82, 7.620000, 0, 1, 15, 725, 0 +GPS, 3, 308928600, 10, 1.49, 24.2398186, 54.5793212, 6.59, 20.20, 1.06, 91.04 +NTUN, 3.64, 0.63, 44.217991, 81.987923, 44.217991, 81.987923, -7.039289, 50.184177, 192.204760, 176.907550, -4.36, -14.30 +CTUN, 336, 6.38, 7.76, 7.620000, 0, 1, 16, 726, 0 +ATT, -4.36, -2.22, -14.30, -8.04, 0.00, 59.28, 69.72 +NTUN, 3.51, 0.63, 50.014851, 86.482742, 50.014851, 86.482742, 0.730065, 59.651535, 188.394650, 173.503160, -4.24, -14.04 +CTUN, 337, 6.38, 7.90, 7.620000, 0, 1, 11, 734, 0 +ATT, -4.24, -2.49, -14.04, -7.88, 0.00, 59.47, 69.72 +GPS, 3, 308928800, 10, 1.49, 24.2398189, 54.5793237, 6.76, 20.38, 1.30, 87.22 +NTUN, 3.36, 0.62, 55.584438, 91.010704, 55.584438, 91.010704, 9.358702, 71.236969, 186.695880, 168.279620, -4.38, -13.73 +CTUN, 337, 6.38, 7.91, 7.620000, 0, 1, 7, 735, 0 +ATT, -4.38, -2.56, -13.73, -7.51, 0.00, 59.40, 69.72 +NTUN, 3.20, 0.62, 60.955303, 95.611542, 60.955303, 95.611542, 18.277100, 81.382446, 182.708650, 165.008380, -4.22, -13.48 +CTUN, 336, 6.37, 7.74, 7.620000, 0, 1, 7, 730, 0 +GPS, 3, 308929000, 10, 1.49, 24.2398197, 54.5793265, 6.91, 20.51, 1.44, 79.50 +ATT, -4.22, -2.49, -13.48, -7.41, 0.00, 58.91, 69.72 +NTUN, 3.03, 0.61, 65.961838, 100.484850, 65.961838, 100.484850, 25.566374, 92.053909, 179.065340, 161.733060, -4.01, -13.26 +CTUN, 336, 6.38, 7.93, 7.620000, 0, 1, 3, 737, 0 +ATT, -4.01, -1.96, -13.26, -7.72, 0.00, 58.40, 69.72 +NTUN, 2.84, 0.60, 70.604034, 105.514630, 70.604034, 105.514630, 32.901661, 100.880840, 172.962340, 158.799850, -3.69, -12.97 +CTUN, 336, 6.37, 8.27, 7.620000, 0, 1, 2, 738, 0 +GPS, 3, 308929200, 10, 1.49, 24.2398206, 54.5793296, 7.03, 20.65, 1.68, 74.80 +NTUN, 2.65, 0.60, 75.120743, 110.933170, 75.120743, 110.933170, 41.976795, 113.830530, 170.167080, 157.185330, -3.57, -12.82 +ATT, -3.57, -2.18, -12.82, -7.86, 0.00, 58.20, 69.72 +CTUN, 337, 6.37, 8.18, 7.620000, 0, 1, 3, 727, 0 +DU32, 7, 393457 +CURR, 336, 99318, 1154, 0, 4752, 0.000000 +NTUN, 2.42, 0.59, 79.471603, 116.699040, 79.471603, 116.699040, 54.062313, 124.512560, 161.508610, 155.658690, -3.22, -12.49 +ATT, -3.22, -4.07, -12.49, -7.72, 0.00, 58.42, 69.72 +CTUN, 337, 6.37, 8.31, 7.620000, 0, 1, 12, 708, 0 +GPS, 3, 308929400, 10, 1.49, 24.2398219, 54.5793333, 7.18, 20.75, 1.96, 72.40 +NTUN, 2.17, 0.58, 83.586761, 124.314700, 83.586761, 124.314700, 73.631790, 134.633610, 143.744140, 169.402590, -2.31, -12.56 +ATT, -2.31, -4.26, -12.56, -6.88, 0.00, 60.83, 69.72 +CTUN, 337, 6.37, 8.04, 7.620000, 0, 0, 30, 672, 0 +NTUN, 1.90, 0.57, 87.237000, 133.331740, 87.087151, 133.102710, 80.975159, 141.036850, 135.003890, 184.880100, -2.01, -12.99 +ATT, -2.01, -2.97, -12.99, -5.41, 0.00, 63.27, 69.72 +CTUN, 337, 6.37, 8.06, 7.620000, 0, 0, 39, 682, 0 +GPS, 3, 308929600, 10, 1.49, 24.2398234, 54.5793373, 7.36, 20.88, 2.16, 69.40 +NTUN, 1.64, 0.57, 87.993027, 136.345060, 87.740974, 135.954500, 84.271759, 147.272370, 103.538240, 121.517910, -2.37, -8.94 +CTUN, 336, 6.37, 8.34, 7.620000, 0, 0, 37, 669, 0 +ATT, -2.37, -2.44, -8.94, -5.40, 0.00, 64.53, 69.72 +NTUN, 1.64, 0.57, 76.037827, 113.121060, 76.037827, 113.121060, 88.433815, 153.776950, -33.872749, -164.073610, -2.34, 9.41 +CTUN, 337, 6.37, 8.88, 7.620000, 0, 0, 37, 678, 0 +ATT, -2.34, -1.33, 9.41, -5.19, 0.00, 64.33, 69.72 +GPS, 3, 308929800, 10, 1.49, 24.2398255, 54.5793415, 7.54, 21.04, 2.43, 64.46 +NTUN, 1.33, 0.55, 63.812515, 89.206543, 63.812515, 89.206543, 89.953163, 164.993390, -56.253113, -216.145200, -2.45, 12.60 +CMD, 8, 6, 16, 1, 0, 7.62, 24.2398128, 54.5793536 +CTUN, 337, 6.40, 8.07, 7.620000, 0, 0, 29, 666, 0 +ATT, -1.27, -1.94, -3.87, 0.06, 0.00, 65.11, 66.12 +NTUN, 0.00, 1.31, 48.562218, 65.493164, 48.562218, 65.493164, 86.377777, 166.580000, -97.993042, -242.785920, -0.68, 14.93 +CTUN, 337, 6.37, 8.02, 7.620000, 0, 0, 32, 670, 0 +GPS, 3, 308930000, 10, 1.49, 24.2398277, 54.5793460, 7.70, 21.17, 2.56, 63.22 +ATT, -0.68, -5.29, 14.93, 5.91, 0.00, 65.88, 60.12 +NTUN, 1.93, 1.38, 31.086990, 43.820007, 31.086990, 43.820007, 87.398422, 144.648850, -144.517460, -230.920780, 2.19, 15.38 +CTUN, 336, 6.37, 9.37, 7.620000, 0, 0, 47, 629, 0 +ATT, 2.19, -2.32, 15.38, 6.52, 0.00, 64.14, 54.12 +NTUN, 1.88, 1.47, 10.479088, 24.978851, 10.479088, 24.978851, 83.557144, 135.620450, -195.079030, -216.411560, 4.28, 16.02 +CTUN, 337, 6.36, 9.75, 7.620000, 0, 0, 47, 636, 0 +GPS, 3, 308930200, 10, 1.49, 24.2398299, 54.5793504, 7.93, 21.28, 2.52, 62.57 +ATT, 4.28, -2.21, 16.02, 13.14, 0.00, 60.14, 48.12 +NTUN, 1.88, 1.54, -11.980812, 8.366272, -11.980812, 8.366272, 69.740768, 117.344190, -223.375240, -195.480970, 5.18, 16.05 +CTUN, 337, 6.36, 10.07, 7.620000, 0, 0, 47, 619, 0 +DU32, 7, 393457 +CURR, 336, 105315, 1172, 0, 4772, 0.000000 +ATT, 5.18, -3.59, 16.05, 16.37, 0.00, 57.15, 42.12 +NTUN, 1.91, 1.61, -33.380829, -5.255310, -33.380829, -5.255310, 57.101727, 85.864799, -229.000170, -155.215820, 5.84, 14.63 +CTUN, 337, 6.35, 10.36, 7.620000, 0, 0, 52, 587, 0 +GPS, 3, 308930400, 10, 1.49, 24.2398318, 54.5793546, 8.19, 21.45, 2.38, 62.71 +ATT, 5.84, -1.66, 14.63, 17.45, 0.00, 53.70, 36.12 +NTUN, 1.96, 1.68, -54.081150, -15.671112, -54.081150, -15.671112, 37.389668, 56.837921, -227.003200, -107.158020, 6.29, 12.85 +CTUN, 336, 6.36, 10.55, 7.620000, 0, 0, 57, 569, 0 +ATT, 6.29, -0.27, 12.85, 18.62, 0.00, 49.20, 30.12 +NTUN, 2.01, 1.72, -74.059990, -23.124451, -74.059990, -23.124451, 15.630918, 34.957474, -220.810290, -65.795433, 6.59, 11.34 +CTUN, 336, 6.36, 10.87, 7.620000, 0, 0, 54, 565, 0 +GPS, 3, 308930600, 10, 1.49, 24.2398332, 54.5793580, 8.55, 21.61, 1.91, 63.37 +ATT, 6.59, -0.21, 11.34, 19.58, 0.00, 45.13, 24.12 +NTUN, 2.06, 1.76, -92.830406, -28.438477, -92.830406, -28.438477, -5.757162, 14.400352, -212.704160, -31.140259, 6.92, 10.06 +CTUN, 337, 6.37, 10.98, 7.620000, 0, 0, 43, 561, 0 +ATT, 6.92, 1.03, 10.06, 18.64, 0.00, 42.10, 18.12 +NTUN, 2.07, 1.79, -110.903880, -31.204193, -110.903880, -31.204193, -30.422009, -4.934965, -202.734710, 8.342834, 7.65, 8.57 +CTUN, 337, 6.37, 11.07, 7.620000, 0, 0, 41, 535, 0 +GPS, 3, 308930800, 10, 1.49, 24.2398340, 54.5793602, 8.92, 21.78, 1.23, 64.51 +ATT, 7.65, 3.00, 8.57, 17.79, 0.00, 38.27, 12.12 +NTUN, 2.07, 1.81, -128.744720, -31.539124, -128.744720, -31.539124, -58.692818, -18.163364, -191.642000, 45.683857, 8.40, 7.27 +CTUN, 337, 6.38, 11.12, 7.620000, 0, 0, 35, 532, 0 +ATT, 8.40, 4.00, 7.27, 17.15, 0.00, 33.89, 6.12 +NTUN, 2.04, 1.82, -145.596950, -30.031494, -145.596950, -30.031494, -83.956619, -25.139088, -177.522340, 72.076294, 8.68, 6.42 +CTUN, 337, 6.38, 11.24, 7.620000, 0, 0, 22, 539, 0 +GPS, 3, 308931000, 10, 1.49, 24.2398341, 54.5793616, 9.25, 21.91, 0.70, 69.88 +ATT, 8.68, 5.41, 6.42, 15.86, 0.00, 30.11, 0.12 +NTUN, 1.98, 1.84, -162.174530, -27.363251, -161.545910, -27.257187, -107.806610, -29.126593, -163.489590, 89.743073, 8.78, 5.83 +CTUN, 337, 6.38, 11.28, 7.620000, 0, 0, 9, 541, 0 +ATT, 8.78, 5.90, 5.83, 14.90, 0.00, 25.69, 0.00 +NTUN, 1.90, 1.85, -178.638640, -23.845093, -176.108830, -23.507406, -128.553410, -26.891155, -145.187240, 102.126540, 8.60, 5.20 +CTUN, 337, 6.38, 11.19, 7.620000, 0, 0, 0, 543, 0 +GPS, 3, 308931200, 10, 1.49, 24.2398331, 54.5793623, 9.49, 22.00, 0.66, 103.42 +ATT, 8.60, 6.06, 5.20, 13.88, 0.00, 22.29, 0.00 +NTUN, 1.81, 1.87, -176.289000, -25.799622, -174.072040, -25.475174, -150.171250, -26.392176, 42.367889, 42.322323, 1.36, -3.20 +CTUN, 337, 6.40, 11.29, 7.620000, 0, 0, -19, 551, 0 +ATT, 1.36, 5.75, -3.20, 12.86, 0.00, 20.31, 0.00 +NTUN, 1.70, 1.89, -163.574740, -30.749634, -162.774860, -30.599264, -167.056750, -20.210482, 162.971800, -0.240902, -3.22, -8.85 +DU32, 7, 393457 +CURR, 336, 111454, 1167, 0, 4772, 0.000000 +CTUN, 336, 6.38, 11.30, 7.620000, 0, 0, -38, 565, 0 +GPS, 3, 308931400, 10, 1.49, 24.2398314, 54.5793629, 9.67, 22.01, 1.01, 145.69 +ATT, -3.22, 3.19, -8.85, 10.66, 0.00, 19.86, 0.00 +CMD, 8, 7, 16, 1, 0, 7.62, 24.2398000, 54.5793472 +NTUN, 0.00, 1.98, -167.815110, -44.318542, -166.260770, -43.908058, -183.294240, -21.215260, 28.485981, -93.770233, -5.61, 0.30 +CTUN, 337, 6.40, 11.34, 7.620000, 0, 0, -50, 577, 0 +ATT, -5.61, 1.84, 0.30, 7.88, 0.00, 20.17, 354.00 +NTUN, 2.99, 2.00, -173.453980, -58.942780, -170.582630, -57.967037, -190.984310, -18.184553, 23.781464, -121.589780, -7.04, 1.11 +CTUN, 337, 6.38, 11.09, 7.620000, 0, 0, -58, 591, 0 +GPS, 3, 308931600, 10, 1.49, 24.2398290, 54.5793631, 9.76, 21.96, 1.37, 162.38 +ATT, -7.04, -2.38, 1.11, 9.75, 0.00, 19.31, 348.00 +NTUN, 2.86, 2.02, -180.739150, -74.414978, -175.782970, -72.374390, -206.945450, -22.415274, 27.996521, -137.073520, -7.93, 1.07 +CTUN, 336, 6.38, 11.12, 7.620000, 0, 0, -70, 599, 0 +ATT, -7.93, -6.72, 1.07, 8.90, 0.00, 17.63, 342.00 +NTUN, 2.71, 2.04, -189.804350, -89.696442, -181.905560, -85.963684, -216.787050, -38.525570, 24.380306, -128.547470, -7.47, 0.76 +CTUN, 336, 6.38, 11.06, 7.620000, 0, 0, -80, 606, 0 +GPS, 3, 308931800, 10, 1.49, 24.2398261, 54.5793633, 9.79, 21.83, 1.70, 170.74 +ATT, -7.47, -8.16, 0.76, 8.80, 0.00, 13.52, 336.00 +NTUN, 2.55, 2.06, -200.380250, -104.190090, -188.741990, -98.138649, -227.904390, -53.881424, 23.635742, -114.749650, -6.73, 0.02 +CTUN, 336, 6.38, 10.89, 7.620000, 0, 0, -79, 617, 0 +ATT, -6.73, -10.85, 0.02, 8.62, 0.00, 6.83, 330.00 +NTUN, 2.38, 2.08, -202.978960, -113.658260, -189.741930, -106.246170, -238.361180, -71.817581, 93.099617, -65.272484, -4.19, -5.09 +CTUN, 336, 6.38, 10.74, 7.620000, 0, 0, -84, 621, 0 +GPS, 3, 308932000, 10, 1.49, 24.2398230, 54.5793629, 9.77, 21.58, 1.84, 179.72 +ATT, -4.19, -12.15, -5.09, 7.34, 0.00, 359.63, 324.00 +NTUN, 2.18, 2.10, -181.830180, -110.309780, -173.755230, -105.411010, -254.641270, -90.763802, 300.481750, 43.435951, 3.43, -16.88 +CTUN, 337, 6.38, 10.88, 7.620000, 0, 0, -85, 632, 0 +ATT, 3.43, -12.43, -16.88, 5.38, 0.00, 350.72, 318.00 +MODE, LAND, 500 +NTUN, 1.97, 2.12, 6.865845, 1.784973, -255.146000, -100.600240, -267.450870, -108.417140, 12.000000, 7.000000, 0.54, -0.60 +CTUN, 337, 6.37, 10.73, 0.000000, 0, 0, -87, 646, 0 +GPS, 3, 308932200, 10, 1.49, 24.2398193, 54.5793620, 9.73, 21.35, 2.15, 186.89 +ATT, 0.00, -10.79, 0.00, 0.91, 0.00, 342.17, 339.87 +NTUN, 0.07, 0.15, 5.278854, -0.743225, -242.299560, -95.950035, -269.809720, -126.400400, 155.192430, 77.041656, 7.20, -7.03 +CTUN, 336, 6.37, 10.62, 0.000000, 0, 0, -84, 645, 0 +ATT, 0.00, -9.01, 0.00, 1.61, 0.00, 339.79, 339.87 +NTUN, 0.05, 0.14, 5.244492, -0.045349, -228.692900, -88.467850, -271.216310, -143.849470, 181.066590, 133.821850, 10.81, -7.23 +CTUN, 336, 6.37, 10.64, 0.000000, 0, 0, -79, 641, 0 +GPS, 3, 308932400, 10, 1.49, 24.2398153, 54.5793604, 9.68, 21.13, 2.40, 192.95 +ATT, 0.00, -7.38, 0.00, 2.50, 0.00, 341.28, 339.87 +DU32, 7, 393457 +CURR, 337, 117547, 1180, 0, 4772, 0.000000 +NTUN, 0.05, 0.18, 7.314941, 2.483826, -213.595280, -79.459663, -284.514130, -151.675030, 226.976260, 169.081860, 13.25, -9.46 +CTUN, 336, 6.37, 10.49, 0.000000, 0, 0, -77, 631, 0 +ATT, 0.00, -3.69, 0.00, -0.40, 0.00, 343.29, 339.87 +NTUN, 0.07, 0.23, 11.000992, 6.615356, -197.343860, -69.078796, -283.198520, -158.640630, 256.905150, 203.780850, 15.28, -10.89 +CTUN, 336, 6.37, 10.26, 0.000000, 0, 0, -71, 631, 0 +GPS, 3, 308932600, 10, 1.49, 24.2398108, 54.5793576, 9.63, 20.89, 2.87, 202.45 +ATT, 0.00, -0.16, 0.00, -0.22, 0.00, 344.11, 339.87 +NTUN, 0.12, 0.28, 15.761566, 12.138824, -180.707760, -57.649094, -280.881040, -155.360000, 282.360930, 228.297030, 16.78, -12.12 +CTUN, 337, 6.37, 10.12, 0.000000, 0, 0, -73, 628, 0 +ATT, 0.00, 1.48, 0.00, -0.59, 0.00, 345.04, 339.87 +NTUN, 0.19, 0.32, 21.697449, 18.164276, -163.430760, -45.983185, -278.193180, -153.425980, 307.770080, 245.659090, 17.84, -13.49 +CTUN, 336, 6.37, 10.11, 0.000000, 0, 0, -67, 626, 0 +GPS, 3, 308932800, 9, 1.75, 24.2398061, 54.5793543, 9.56, 20.65, 3.09, 208.60 +ATT, 0.00, 4.00, 0.00, -2.81, 0.00, 345.94, 339.87 +NTUN, 0.28, 0.34, 28.414459, 25.049957, -145.774670, -33.657001, -271.690400, -146.692580, 327.812680, 263.041410, 18.78, -14.57 +CTUN, 336, 6.37, 9.99, 0.000000, 0, 0, -74, 626, 0 +ATT, 0.00, 6.41, 0.00, -3.87, 0.00, 346.40, 339.87 +NTUN, 0.37, 0.36, 35.487930, 31.974701, -128.362690, -21.590446, -261.400240, -136.131500, 341.119870, 267.665560, 19.05, -15.37 +GPS, 3, 308933000, 9, 1.75, 24.2398014, 54.5793507, 9.48, 20.41, 3.16, 211.17 +CTUN, 336, 6.37, 9.74, 0.000000, 0, 0, -69, 630, 0 +ATT, 0.00, 7.81, 0.00, -5.25, 0.00, 346.77, 339.87 +NTUN, 0.47, 0.38, 42.816177, 39.074921, -111.161160, -9.579796, -251.653370, -124.193830, 353.015230, 273.106510, 19.37, -16.00 +CTUN, 337, 6.37, 9.61, 0.000000, 0, 0, -78, 642, 0 +ATT, 0.00, 9.08, 0.00, -7.50, 0.00, 346.93, 339.87 +NTUN, 0.57, 0.39, 49.697113, 45.916412, -94.756958, 1.998055, -233.535320, -114.304320, 348.417850, 275.632170, 19.34, -15.77 +GPS, 3, 308933200, 10, 1.49, 24.2397969, 54.5793475, 9.35, 20.16, 3.00, 212.09 +CTUN, 336, 6.37, 9.38, 0.000000, 0, 0, -76, 644, 0 +NTUN, 0.67, 0.39, 56.098145, 52.584900, -79.355499, 13.142868, -214.462810, -101.377850, 344.014590, 276.448120, 19.27, -15.56 +ATT, 0.00, 9.93, 0.00, -8.47, 0.00, 347.05, 339.87 +CTUN, 336, 6.38, 9.18, 0.000000, 0, 0, -80, 640, 0 +NTUN, 0.76, 0.40, 61.610992, 58.665222, -65.247238, 23.498081, -195.747280, -88.610329, 333.082610, 271.552120, 18.78, -15.14 +ATT, 0.00, 10.67, 0.00, -9.47, 0.00, 347.39, 339.87 +GPS, 3, 308933400, 10, 1.49, 24.2397929, 54.5793444, 9.20, 19.90, 2.74, 213.54 +CTUN, 337, 6.37, 9.13, 0.000000, 0, 1, -81, 655, 0 +DU32, 7, 393457 +CURR, 336, 123949, 1199, 0, 4752, 0.000000 +NTUN, 0.85, 0.41, 66.097809, 64.531677, -52.469711, 33.487885, -176.021730, -73.919937, 317.510160, 267.908940, 18.24, -14.51 +ATT, 0.00, 11.47, 0.00, -10.58, 0.00, 347.87, 339.87 +CTUN, 336, 6.37, 8.83, 0.000000, 0, 0, -83, 641, 0 +NTUN, 0.92, 0.42, 69.365814, 69.639557, -41.366165, 42.492733, -151.981890, -59.308189, 294.035460, 258.048490, 17.36, -13.45 +ATT, 0.00, 11.67, 0.00, -11.69, 0.00, 348.16, 339.87 +GPS, 3, 308933600, 9, 1.75, 24.2397896, 54.5793418, 9.02, 19.63, 2.28, 213.97 +CTUN, 336, 6.37, 8.75, 0.000000, 0, 1, -76, 654, 0 +NTUN, 0.98, 0.43, 71.015961, 74.200226, -32.158249, 50.812225, -125.982610, -45.941948, 262.167480, 250.371220, 16.44, -12.04 +ATT, 0.00, 11.66, 0.00, -12.13, 0.00, 349.06, 339.87 +CTUN, 336, 6.37, 8.51, 0.000000, 0, 1, -77, 647, 0 +NTUN, 1.02, 0.44, 71.102661, 77.953064, -24.928711, 58.117523, -103.207430, -30.797054, 232.295380, 237.052980, 15.22, -10.91 +ATT, 0.00, 10.88, 0.00, -11.99, 0.00, 350.45, 340.45 +GPS, 3, 308933800, 9, 1.75, 24.2397869, 54.5793395, 8.83, 19.36, 1.87, 215.59 +CTUN, 336, 6.31, 8.39, 0.000000, 0, 1, -74, 663, 0 +NTUN, 1.05, 0.46, 70.009033, 81.320648, -19.200928, 64.877708, -82.247559, -18.192736, 205.277830, 230.601850, 14.39, -9.86 +ATT, 0.00, 9.86, 0.00, -12.12, 0.00, 352.00, 342.00 +CTUN, 337, 6.36, 8.31, 0.000000, 0, 1, -75, 651, 0 +NTUN, 1.07, 0.48, 67.424316, 84.177826, -15.206047, 71.007217, -61.032948, -6.837453, 171.553270, 221.688200, 13.47, -8.40 +ATT, 0.00, 9.32, 0.00, -11.56, 0.00, 353.57, 343.57 +GPS, 3, 308934000, 9, 1.75, 24.2397851, 54.5793377, 8.65, 19.07, 1.38, 217.18 +CTUN, 336, 6.36, 8.31, 0.000000, 0, 1, -71, 657, 0 +NTUN, 1.07, 0.50, 63.759369, 86.524658, -12.714813, 76.415802, -40.372002, 3.469611, 141.163970, 214.632170, 12.78, -7.05 +ATT, 0.00, 8.18, 0.00, -10.66, 0.00, 355.03, 345.03 +CTUN, 336, 6.36, 7.96, 0.000000, 0, 0, -65, 639, 0 +NTUN, 1.07, 0.53, 58.878906, 88.574432, -11.594521, 81.450020, -23.527332, 12.611626, 111.092000, 208.843730, 12.18, -5.73 +ATT, 0.00, 7.26, 0.00, -10.02, 0.00, 356.76, 346.76 +GPS, 3, 308934200, 9, 1.75, 24.2397840, 54.5793364, 8.46, 18.81, 0.88, 219.92 +CTUN, 336, 6.36, 8.02, 0.000000, 0, 0, -63, 641, 0 +NTUN, 1.06, 0.56, 53.121094, 90.519745, -11.624313, 86.244141, -7.828726, 21.051466, 85.705025, 206.466540, 11.87, -4.66 +ATT, 0.00, 6.49, 0.00, -8.93, 0.00, 358.60, 348.60 +CTUN, 337, 6.36, 7.99, 0.000000, 0, 0, -56, 638, 0 +NTUN, 1.04, 0.60, 46.675934, 92.180145, -12.655930, 90.596939, 1.618477, 28.938814, 63.683838, 201.527980, 11.51, -3.71 +ATT, 0.00, 6.03, 0.00, -7.46, 0.00, 0.12, 350.12 +GPS, 3, 308934400, 9, 1.75, 24.2397836, 54.5793354, 8.29, 18.55, 0.57, 231.55 +CTUN, 337, 5.51, 7.87, 0.000000, 0, 0, -60, 639, 0 +NTUN, 1.03, 0.64, 39.874176, 93.648529, -14.287754, 93.648529, 13.458117, 33.666645, 43.681755, 189.515900, 10.81, -2.77 +ATT, 0.00, 5.31, 0.00, -6.59, 0.00, 1.30, 351.30 +DU32, 7, 393457 +CURR, 337, 130402, 1189, 0, 4772, 0.000000 +CTUN, 337, 5.51, 7.75, 0.000000, 0, 0, -51, 627, 0 +NTUN, 1.01, 0.68, 32.636597, 94.837799, -16.538673, 94.837799, 21.639561, 38.231819, 24.713671, 170.774950, 9.75, -1.89 +ATT, 0.00, 5.08, 0.00, -5.45, 0.00, 2.76, 352.76 +GPS, 3, 308934600, 10, 1.49, 24.2397837, 54.5793346, 8.13, 18.28, 0.38, 248.64 +CTUN, 337, 5.51, 7.68, 0.000000, 0, 0, -51, 620, 0 +NTUN, 1.00, 0.72, 25.289978, 95.943085, -19.219536, 95.943085, 27.341030, 42.245224, 9.920582, 170.164510, 9.75, -1.31 +ATT, 0.00, 4.84, 0.00, -3.96, 0.00, 4.39, 354.39 +CTUN, 336, 5.82, 7.51, 0.000000, 0, 0, -45, 613, 0 +NTUN, 0.99, 0.77, 17.969055, 96.826263, -21.992500, 96.826263, 27.795399, 46.195755, 3.544907, 166.744340, 9.56, -1.21 +ATT, 0.00, 4.66, 0.00, -2.32, 0.00, 6.10, 356.10 +GPS, 3, 308934800, 10, 1.49, 24.2397841, 54.5793343, 7.98, 18.07, 0.27, 277.16 +CTUN, 337, 5.82, 7.44, 0.000000, 0, 0, -49, 609, 0 +NTUN, 0.98, 0.81, 11.092133, 97.333496, -24.571152, 97.333496, 28.234222, 49.305347, 0.213486, 164.072330, 9.41, -1.22 +ATT, 0.00, 4.81, 0.00, -0.87, 0.00, 7.40, 357.40 +CTUN, 337, 6.37, 7.24, 0.000000, 0, 0, -50, 620, 0 +NTUN, 0.97, 0.85, 4.970306, 97.436096, -26.588131, 97.436096, 24.313164, 53.603748, 4.830208, 157.026000, 8.96, -1.57 +ATT, 0.00, 4.80, 0.00, 0.17, 0.00, 8.12, 358.12 +GPS, 3, 308935000, 10, 1.49, 24.2397847, 54.5793341, 7.81, 17.80, 0.33, 311.43 +CTUN, 336, 6.37, 7.13, 0.000000, 0, 0, -54, 613, 0 +NTUN, 0.97, 0.88, -0.428253, 97.205231, -28.027359, 97.205231, 19.956686, 56.961964, 11.750217, 152.714200, 8.66, -1.95 +ATT, 0.00, 4.30, 0.00, 0.92, 0.00, 8.19, 358.23 +CTUN, 337, 6.40, 6.91, 0.000000, 0, 0, -53, 618, 0 +NTUN, 0.97, 0.91, -4.877777, 96.671753, -28.734922, 96.671753, 12.385397, 61.856934, 22.924366, 145.665220, 8.18, -2.48 +ATT, 0.00, 3.68, 0.00, 1.71, 0.00, 7.75, 358.23 +GPS, 3, 308935200, 10, 1.49, 24.2397854, 54.5793340, 7.62, 17.54, 0.38, 332.86 +CTUN, 336, 6.38, 6.91, 0.000000, 0, 0, -48, 587, 0 +NTUN, 0.96, 0.93, -8.548340, 95.905273, -28.831913, 95.905273, 5.545835, 62.362228, 34.030094, 143.335210, 8.01, -2.98 +ATT, 0.00, 2.53, 0.00, 1.72, 0.00, 6.84, 358.23 +CTUN, 336, 6.40, 6.74, 0.000000, 0, 0, -44, 601, 0 +NTUN, 0.96, 0.95, -11.390503, 95.243042, -28.261314, 95.243042, 3.248413, 61.916893, 42.705986, 146.377690, 8.16, -3.42 +ATT, 0.00, 3.24, 0.00, 1.03, 0.00, 6.33, 358.23 +GPS, 3, 308935400, 10, 1.49, 24.2397857, 54.5793343, 7.45, 17.28, 0.23, 345.08 +CTUN, 337, 6.40, 6.51, 0.000000, 0, 0, -41, 584, 0 +NTUN, 0.95, 0.97, -13.599121, 94.237396, -27.178154, 94.237396, 0.272123, 65.489029, 49.724361, 139.043110, 7.71, -3.75 +ATT, 0.00, 3.27, 0.00, 1.75, 0.00, 6.12, 358.23 +DU32, 7, 393457 +CURR, 337, 136511, 1173, 0, 4752, 0.000000 +CTUN, 337, 6.40, 6.48, 0.000000, 0, 0, -44, 599, 0 +NTUN, 0.95, 0.98, -14.917664, 92.849945, -25.385639, 92.849945, -6.976023, 67.602180, 64.925148, 134.125490, 7.32, -4.61 +ATT, 0.00, 2.89, 0.00, 2.20, 0.00, 6.27, 358.23 +GPS, 3, 308935600, 10, 1.49, 24.2397858, 54.5793345, 7.26, 17.07, 0.12, 345.08 +CTUN, 337, 6.40, 6.28, 0.000000, 0, 0, -39, 583, 0 +NTUN, 0.94, 0.99, -15.265991, 91.394714, -22.733198, 91.394714, -13.428787, 68.948967, 82.261795, 131.591780, 7.08, -5.58 +ATT, 0.00, 2.73, 0.00, 2.17, 0.00, 6.14, 358.23 +CTUN, 336, 6.40, 6.11, 0.000000, 0, 0, -44, 590, 0 +NTUN, 0.92, 0.99, -14.701508, 89.773895, -19.332689, 89.773895, -18.008480, 69.035248, 98.005089, 128.791810, 6.84, -6.46 +ATT, 0.00, 2.22, 0.00, 1.48, 0.00, 6.06, 358.23 +GPS, 3, 308935800, 10, 1.49, 24.2397860, 54.5793347, 7.06, 16.81, 0.13, 345.08 +CTUN, 336, 6.40, 6.03, 0.000000, 0, 0, -39, 579, 0 +NTUN, 0.90, 0.98, -13.698700, 88.212189, -15.621479, 88.212189, -19.382402, 69.336479, 105.112110, 128.382930, 6.76, -6.87 +ATT, 0.00, 2.01, 0.00, 1.16, 0.00, 6.19, 358.23 +CTUN, 336, 6.40, 5.81, 0.000000, 0, 0, -45, 594, 0 +NTUN, 0.89, 0.98, -12.332245, 86.655731, -12.332245, 86.655731, -22.826569, 69.345764, 108.566670, 127.589530, 6.65, -7.10 +ATT, 0.00, 1.70, 0.00, 1.10, 0.00, 6.51, 358.23 +GPS, 3, 308936000, 10, 1.49, 24.2397858, 54.5793353, 6.84, 16.55, 0.34, 84.93 +CTUN, 337, 6.36, 5.86, 0.000000, 0, 0, -41, 577, 0 +NTUN, 0.87, 0.97, -10.699188, 84.961853, -10.699188, 84.961853, -26.083317, 68.087486, 97.330566, 126.061220, 6.59, -6.50 +ATT, 0.00, 1.50, 0.00, 0.82, 0.00, 6.97, 358.23 +CTUN, 336, 6.36, 5.78, 0.000000, 0, 0, -45, 588, 0 +NTUN, 0.85, 0.96, -8.858917, 83.240479, -8.858917, 83.240479, -27.531891, 67.593369, 103.402710, 125.786250, 6.49, -6.89 +ATT, 0.00, 1.85, 0.00, 0.31, 0.00, 7.37, 358.23 +GPS, 3, 308936200, 9, 1.75, 24.2397855, 54.5793357, 6.64, 16.30, 0.25, 100.40 +CTUN, 336, 5.96, 5.54, 0.000000, 0, 0, -41, 571, 0 +NTUN, 0.83, 0.94, -6.848846, 81.440948, -6.848846, 81.440948, -27.918331, 68.914413, 109.100710, 123.004700, 6.26, -7.21 +ATT, 0.00, 2.02, 0.00, 0.70, 0.00, 7.47, 358.23 +CTUN, 337, 5.96, 5.47, 0.000000, 0, 0, -43, 582, 0 +NTUN, 0.81, 0.93, -4.607361, 79.389923, -4.607361, 79.389923, -31.404415, 70.774139, 118.192920, 116.692820, 5.89, -7.64 +ATT, 0.00, 1.23, 0.00, 1.34, 0.00, 6.96, 358.23 +GPS, 3, 308936400, 9, 1.75, 24.2397851, 54.5793361, 6.43, 16.05, 0.35, 124.20 +CTUN, 337, 5.84, 5.50, 0.000000, 0, 0, -38, 563, 0 +NTUN, 0.79, 0.91, -1.914215, 77.416412, -1.914215, 77.416412, -34.727791, 68.077415, 129.931460, 118.264890, 6.08, -8.19 +ATT, 0.00, 0.41, 0.00, 0.65, 0.00, 5.76, 358.23 +DU32, 7, 393457 +CURR, 337, 142348, 1192, 0, 4772, 0.000000 +CTUN, 337, 5.84, 5.22, 0.000000, 0, 0, -36, 563, 0 +NTUN, 0.77, 0.89, 0.804749, 75.797760, 0.804749, 75.797760, -35.649529, 63.985107, 135.920430, 124.973740, 6.46, -8.55 +ATT, 0.00, 1.50, 0.00, -0.21, 0.00, 5.55, 358.23 +GPS, 3, 308936600, 10, 1.49, 24.2397845, 54.5793367, 6.24, 15.80, 0.44, 132.28 +CTUN, 336, 5.62, 5.08, 0.000000, 0, 0, -39, 567, 0 +NTUN, 0.75, 0.87, 3.775482, 74.042847, 3.775482, 74.042847, -35.072098, 66.663742, 143.007420, 119.273610, 6.11, -8.90 +ATT, 0.00, 2.53, 0.00, -1.10, 0.00, 5.49, 358.23 +CTUN, 336, 5.62, 5.14, 0.000000, 0, 0, -49, 589, 0 +NTUN, 0.74, 0.84, 6.872345, 71.898071, 6.872345, 71.898071, -34.268810, 69.199142, 148.662000, 110.764600, 5.70, -9.11 +ATT, 0.00, 1.90, 0.00, -2.62, 0.00, 4.67, 358.23 +GPS, 3, 308936800, 9, 1.75, 24.2397839, 54.5793372, 6.01, 15.54, 0.46, 138.96 +CTUN, 336, 5.43, 4.99, 0.000000, 0, 0, -61, 596, 0 +NTUN, 0.72, 0.82, 9.712585, 69.573730, 9.712585, 69.573730, -29.920835, 68.384697, 146.121190, 107.986720, 5.57, -8.93 +ATT, 0.00, 0.84, 0.00, -4.12, 0.00, 4.52, 358.23 +CTUN, 337, 5.43, 4.90, 0.000000, 0, 0, -65, 591, 0 +NTUN, 0.70, 0.80, 11.938751, 67.355743, 11.938751, 67.355743, -22.952904, 66.251701, 137.261660, 109.820130, 5.78, -8.39 +ATT, 0.00, -0.59, 0.00, -4.76, 0.00, 4.12, 358.23 +GPS, 3, 308937000, 9, 1.75, 24.2397832, 54.5793379, 5.76, 15.27, 0.58, 140.12 +CTUN, 337, 5.16, 4.64, 0.000000, 0, 0, -63, 576, 0 +NTUN, 0.68, 0.78, 13.581512, 65.320587, 13.581512, 65.320587, -16.018938, 60.011101, 127.593550, 115.442860, 6.17, -7.84 +ATT, 0.00, -1.38, 0.00, -4.49, 0.00, 3.85, 358.23 +CTUN, 336, 5.16, 4.54, 0.000000, 0, 0, -57, 582, 0 +NTUN, 0.66, 0.77, 14.652527, 63.741150, 14.652527, 63.741150, -8.425225, 54.713730, 116.604100, 124.362010, 6.74, -7.23 +ATT, 0.00, -0.91, 0.00, -4.76, 0.00, 3.73, 358.23 +GPS, 3, 308937200, 9, 1.96, 24.2397827, 54.5793384, 5.51, 15.02, 0.40, 136.27 +CTUN, 336, 4.91, 4.38, 0.000000, 0, 0, -54, 571, 0 +NTUN, 0.65, 0.76, 15.140289, 62.522156, 15.140289, 62.522156, -0.145216, 52.151695, 103.877620, 129.810060, 7.19, -6.42 +ATT, 0.00, -0.10, 0.00, -5.09, 0.00, 2.92, 358.23 +CTUN, 337, 4.91, 4.26, 0.000000, 0, 0, -44, 562, 0 +NTUN, 0.64, 0.76, 14.660767, 61.578979, 14.660767, 61.578979, 7.529474, 50.221642, 86.298798, 133.753170, 7.52, -5.35 +ATT, 0.00, 0.47, 0.00, -4.43, 0.00, 2.37, 358.23 +GPS, 3, 308937400, 9, 1.75, 24.2397825, 54.5793389, 5.29, 14.72, 0.30, 130.30 +CTUN, 336, 4.49, 4.16, 0.000000, 0, 0, -40, 559, 0 +NTUN, 0.63, 0.77, 13.482819, 60.569397, 13.482819, 60.569397, 14.008894, 48.894077, 72.101532, 133.802200, 7.57, -4.53 +ATT, 0.00, 0.19, 0.00, -3.69, 0.00, 2.50, 358.23 +DU32, 7, 393457 +CURR, 337, 148075, 1201, 0, 4752, 0.000000 +CTUN, 336, 4.49, 4.06, 0.000000, 0, 0, -35, 557, 0 +NTUN, 0.62, 0.78, 11.819977, 59.742462, 11.819977, 59.742462, 20.045444, 45.371513, 59.371582, 139.730650, 7.89, -3.89 +ATT, 0.00, 0.70, 0.00, -3.96, 0.00, 3.14, 358.23 +GPS, 3, 308937600, 10, 1.49, 24.2397823, 54.5793394, 5.08, 14.50, 0.24, 122.35 +CTUN, 336, 4.39, 3.89, 0.000000, 0, 0, -37, 571, 0 +NTUN, 0.60, 0.80, 9.844604, 58.777740, 9.844604, 58.777740, 26.232363, 46.758007, 47.441856, 136.448300, 7.66, -3.39 +ATT, 0.00, 1.63, 0.00, -3.60, 0.00, 4.66, 358.23 +CTUN, 336, 4.39, 3.72, 0.000000, 0, 0, -39, 570, 0 +NTUN, 0.59, 0.82, 7.531525, 57.593140, 7.531525, 57.593140, 29.516319, 48.554981, 37.869202, 132.153990, 7.41, -2.95 +ATT, 0.00, 0.66, 0.00, -3.07, 0.00, 5.74, 358.23 +GPS, 3, 308937800, 10, 1.49, 24.2397826, 54.5793395, 4.85, 14.28, 0.15, 122.35 +CTUN, 337, 4.16, 3.65, 0.000000, 0, 0, -43, 574, 0 +NTUN, 0.58, 0.84, 4.802307, 56.572906, 4.802307, 56.572906, 33.333317, 44.252026, 25.707825, 136.797670, 7.69, -2.43 +ATT, 0.00, -0.16, 0.00, -3.69, 0.00, 6.82, 358.23 +CTUN, 336, 4.16, 3.53, 0.000000, 0, 0, -42, 565, 0 +NTUN, 0.56, 0.88, 1.516693, 55.984070, 1.516693, 55.984070, 40.628223, 42.229950, 7.469170, 143.169940, 8.16, -1.54 +ATT, 0.00, 0.11, 0.00, -3.16, 0.00, 7.76, 358.23 +GPS, 3, 308938000, 10, 1.49, 24.2397830, 54.5793400, 4.63, 14.05, 0.29, 77.94 +CTUN, 336, 3.94, 3.40, 0.000000, 0, 0, -43, 572, 0 +NTUN, 0.56, 0.91, -2.077026, 55.243713, -2.077026, 55.243713, 43.141460, 41.185658, -4.937195, 143.596440, 8.28, -0.89 +ATT, 0.00, 0.22, 0.00, -1.82, 0.00, 8.27, 358.27 +CTUN, 336, 3.94, 3.29, 0.000000, 0, 0, -38, 558, 0 +NTUN, 0.55, 0.95, -5.860077, 54.556335, -5.860077, 54.556335, 44.269722, 39.948460, -13.830505, 144.126220, 8.38, -0.47 +ATT, 0.00, 0.50, 0.00, -1.12, 0.00, 8.55, 358.68 +GPS, 3, 308938200, 10, 1.49, 24.2397834, 54.5793401, 4.40, 13.81, 0.27, 46.29 +CTUN, 337, 3.72, 3.08, 0.000000, 0, 0, -32, 553, 0 +NTUN, 0.55, 0.95, -9.548706, 54.129852, -9.548706, 54.129852, 44.182812, 37.278896, -18.521080, 149.777390, 8.74, -0.23 +ATT, 0.00, 1.32, 0.00, -0.51, 0.00, 8.74, 358.74 +CTUN, 337, 3.72, 3.14, 0.000000, 0, 0, -26, 546, 0 +NTUN, 0.54, 1.00, -13.086761, 53.888397, -13.086761, 53.888397, 43.559422, 36.528595, -23.030251, 153.609360, 9.00, 0.00 +GPS, 3, 308938400, 10, 1.49, 24.2397841, 54.5793403, 4.20, 13.56, 0.32, 27.98 +ATT, 0.00, 2.32, 0.00, 0.00, 0.00, 8.28, 358.74 +CTUN, 337, 3.50, 2.92, 0.000000, 0, 0, -28, 561, 0 +PM, 0, 0, 50, 37, 1000, 12000, 6, 0 +NTUN, 0.55, 1.04, -16.510620, 53.507690, -16.510620, 53.507690, 41.685608, 37.841629, -26.584431, 151.154480, 8.89, 0.25 +DU32, 7, 393457 +CURR, 336, 153699, 1204, 0, 4772, 0.000000 +ATT, 0.00, 3.16, 0.00, 0.61, 0.00, 8.13, 358.74 +CTUN, 336, 3.50, 2.83, 0.000000, 0, 0, -29, 556, 0 +NTUN, 0.55, 1.07, -19.629059, 52.912964, -19.629059, 52.912964, 38.479633, 40.651348, -25.875629, 146.111620, 8.59, 0.37 +GPS, 3, 308938600, 10, 1.49, 24.2397847, 54.5793405, 3.99, 13.35, 0.37, 21.69 +ATT, 0.00, 4.10, 0.00, 1.73, 0.00, 7.47, 358.74 +CTUN, 336, 3.30, 2.81, 0.000000, 0, 0, -36, 579, 0 +NTUN, 0.56, 1.10, -22.380035, 51.914703, -22.380035, 51.914703, 30.972786, 43.579845, -20.509766, 139.017400, 8.14, 0.15 +ATT, 0.00, 3.77, 0.00, 2.23, 0.00, 6.74, 358.74 +CTUN, 337, 3.30, 2.73, 0.000000, 0, 0, -47, 584, 0 +NTUN, 0.56, 1.13, -24.445404, 50.547791, -24.445404, 50.547791, 27.158907, 46.469486, -14.653687, 131.330870, 7.66, -0.02 +GPS, 3, 308938800, 10, 1.49, 24.2397852, 54.5793408, 3.76, 13.14, 0.33, 23.60 +ATT, 0.00, 2.66, 0.00, 2.04, 0.00, 6.61, 358.74 +CTUN, 336, 3.09, 2.62, 0.000000, 0, 0, -58, 594, 0 +NTUN, 0.56, 1.16, -26.009369, 48.984833, -26.009369, 48.984833, 21.122009, 45.795444, -7.484800, 128.525180, 7.46, -0.37 +ATT, 0.00, 1.76, 0.00, 2.36, 0.00, 5.84, 358.74 +CTUN, 337, 3.09, 2.58, 0.000000, 0, 0, -57, 592, 0 +NTUN, 0.55, 1.18, -26.998901, 47.322968, -26.998901, 47.322968, 16.864998, 46.322334, 0.104675, 125.381350, 7.24, -0.74 +GPS, 3, 308939000, 10, 1.49, 24.2397855, 54.5793412, 3.55, 12.86, 0.24, 35.61 +ATT, 0.00, 0.62, 0.00, 2.25, 0.00, 5.41, 358.74 +CTUN, 337, 2.88, 2.29, 0.000000, 0, 0, -53, 582, 0 +NTUN, 0.54, 1.20, -27.370239, 45.829224, -27.370239, 45.829224, 8.371254, 43.411045, 12.286621, 128.062560, 7.35, -1.34 +ATT, 0.00, 0.57, 0.00, 1.64, 0.00, 4.62, 358.74 +CTUN, 336, 2.88, 2.20, 0.000000, 0, 0, -50, 583, 0 +NTUN, 0.53, 1.20, -27.268860, 44.615692, -27.268860, 44.615692, 5.727310, 39.461590, 18.003756, 133.984830, 7.67, -1.63 +GPS, 3, 308939200, 10, 1.49, 24.2397857, 54.5793417, 3.27, 12.60, 0.23, 53.35 +ATT, 0.00, 1.51, 0.00, 1.08, 0.00, 3.79, 358.74 +CTUN, 337, 2.61, 2.03, 0.000000, 0, 0, -52, 588, 0 +NTUN, 0.52, 1.21, -26.954163, 43.449860, -26.954163, 43.449860, 3.767017, 38.894253, 21.178761, 134.223910, 7.69, -1.76 +ATT, 0.00, 1.35, 0.00, 1.43, 0.00, 3.73, 358.74 +CTUN, 337, 2.61, 1.92, 0.000000, 0, 0, -51, 593, 0 +NTUN, 0.51, 1.21, -26.317749, 42.166718, -26.317749, 42.166718, 0.403590, 38.446316, 27.239349, 132.420180, 7.57, -2.06 +GPS, 3, 308939400, 10, 1.49, 24.2397854, 54.5793422, 3.03, 12.39, 0.29, 86.22 +ATT, 0.00, 0.65, 0.00, 1.70, 0.00, 3.71, 358.74 +CTUN, 337, 2.36, 1.71, 0.000000, 0, 0, -50, 588, 0 +NTUN, 0.49, 1.21, -25.004639, 40.821198, -25.004639, 40.821198, -6.464251, 37.426674, 41.131104, 131.544800, 7.46, -2.91 +ATT, 0.00, -0.01, 0.00, 1.73, 0.00, 3.64, 358.74 +CTUN, 336, 2.36, 1.71, 0.000000, 0, 0, -44, 583, 0 +DU32, 7, 393457 +CURR, 337, 159566, 1176, 0, 4793, 0.000000 +NTUN, 0.47, 1.21, -23.049469, 39.589783, -23.049469, 39.589783, -10.855576, 34.284595, 52.551697, 134.685850, 7.60, -3.58 +GPS, 3, 308939600, 10, 1.49, 24.2397853, 54.5793425, 2.81, 12.12, 0.17, 106.40 +ATT, 0.00, -0.26, 0.00, 1.49, 0.00, 4.39, 358.74 +CTUN, 336, 2.15, 1.67, 0.000000, 0, 0, -36, 580, 0 +NTUN, 0.45, 1.19, -20.798431, 38.708038, -20.798431, 38.708038, -15.830733, 30.484425, 63.510376, 142.182560, 7.95, -4.31 +ATT, 0.00, 0.07, 0.00, 1.44, 0.00, 4.39, 358.74 +CTUN, 336, 2.15, 1.42, 0.000000, 0, 0, -36, 579, 0 +NTUN, 0.43, 1.16, -18.234680, 38.116364, -18.234680, 38.116364, -17.011360, 27.436670, 69.637512, 147.083250, 8.17, -4.74 +GPS, 3, 308939800, 10, 1.49, 24.2397849, 54.5793428, 2.60, 11.87, 0.24, 135.45 +CTUN, 336, 1.96, 1.38, 0.000000, 0, 0, -27, 578, 0 +ATT, 0.00, 0.69, 0.00, 1.18, 0.00, 4.13, 358.74 +NTUN, 0.42, 1.13, -15.189453, 37.732452, -15.189453, 37.732452, -23.002716, 26.413218, 82.452271, 151.160890, 8.40, -5.41 +CTUN, 337, 1.96, 1.34, 0.000000, 0, 0, -29, 575, 0 +ATT, 0.00, 1.54, 0.00, 0.94, 0.00, 4.08, 358.74 +NTUN, 0.40, 1.09, -11.869965, 37.414276, -11.869965, 37.414276, -26.902416, 25.487455, 93.866226, 151.849750, 8.40, -6.06 +GPS, 3, 308940000, 10, 1.49, 24.2397844, 54.5793429, 2.39, 11.66, 0.26, 150.86 +CTUN, 336, 1.75, 1.34, 0.000000, 0, 0, -28, 587, 0 +ATT, 0.00, 2.07, 0.00, 0.64, 0.00, 2.93, 358.74 +NTUN, 0.39, 1.03, -8.160583, 37.080750, -8.160583, 37.080750, -28.213224, 26.787987, 104.093810, 151.664730, 8.47, -6.50 +CTUN, 336, 1.75, 1.11, 0.000000, 0, 0, -36, 589, 0 +ATT, 0.00, 2.60, 0.00, 0.19, 0.00, 2.81, 358.74 +NTUN, 0.37, 0.97, -4.270325, 36.648102, -4.270325, 36.648102, -30.492025, 27.198334, 112.902590, 149.673520, 8.36, -6.96 +GPS, 3, 308940200, 10, 1.49, 24.2397838, 54.5793432, 2.19, 11.47, 0.35, 157.05 +CTUN, 336, 1.56, 0.88, 0.000000, 0, 0, -34, 597, 0 +ATT, 0.00, 2.45, 0.00, -0.37, 0.00, 2.31, 358.74 +NTUN, 0.36, 0.91, -0.234924, 35.880585, -0.234924, 35.880585, -29.992992, 28.788401, 118.954450, 144.400820, 8.09, -7.24 +CTUN, 340, 1.56, 1.12, 0.000000, 0, 0, -44, 603, 0 +ATT, 0.00, 2.35, 0.00, -0.94, 0.00, 1.66, 358.74 +NTUN, 0.35, 0.85, 3.774384, 34.958954, 3.774384, 34.958954, -31.335699, 30.099003, 127.093080, 140.783690, 7.95, -7.60 +GPS, 3, 308940400, 10, 1.49, 24.2397831, 54.5793433, 1.99, 11.31, 0.37, 164.18 +MODE, STABILIZE, 500 +CTUN, 474, 1.39, 0.95, 0.000000, 0, 0, -47, 617, 0 +ATT, 0.00, 1.67, 0.00, -1.32, 0.00, 1.64, 358.74 +EV, 16 +CTUN, 723, 1.39, 0.68, 0.000000, 0, 0, -53, 635, 0 +ATT, 0.00, -1.29, 0.00, -1.58, 0.00, 0.97, 358.74 +DU32, 7, 426237 +CURR, 723, 165522, 1191, 0, 4732, 0.000000 +GPS, 3, 308940600, 10, 1.49, 24.2397822, 54.5793436, 1.75, 11.07, 0.52, 161.97 +CTUN, 723, 1.18, 0.23, 0.000000, 0, 0, -34, 723, 0 +ATT, 0.00, -2.32, 0.00, 0.44, 0.00, 359.68, 358.74 +CTUN, 737, 1.18, 0.15, 0.000000, 0, 0, 6, 737, 0 +ATT, 0.00, -3.86, 0.00, 2.83, 0.00, 355.08, 358.74 +GPS, 3, 308940800, 10, 1.49, 24.2397815, 54.5793438, 1.60, 10.84, 0.47, 165.42 +CTUN, 746, 0.95, 0.22, 0.000000, 0, 0, 43, 741, 0 +ATT, 0.00, -5.25, 0.00, 2.86, 0.00, 349.60, 358.74 +CTUN, 749, 0.95, 0.21, 0.000000, 0, 0, 75, 749, 0 +ATT, 0.00, -4.92, 0.00, 1.51, 0.00, 345.39, 355.39 +GPS, 3, 308941000, 10, 1.49, 24.2397804, 54.5793439, 1.56, 10.76, 0.50, 172.01 +CTUN, 757, 0.95, 0.03, 0.000000, 0, 0, 112, 757, 0 +ATT, 0.00, -3.71, 0.00, 1.07, 0.00, 342.21, 352.21 +CTUN, 763, 0.96, 0.53, 0.000000, 0, 0, 145, 763, 0 +ATT, 0.00, -2.96, 0.00, 1.49, 0.00, 339.35, 349.35 +GPS, 3, 308941200, 10, 1.49, 24.2397791, 54.5793433, 1.66, 10.82, 0.76, 191.07 +CTUN, 764, 0.96, 0.35, 0.000000, 0, 0, 174, 764, 0 +ATT, 0.00, -2.51, 0.00, 1.86, 0.00, 336.23, 346.23 +CTUN, 763, 1.07, 0.62, 0.000000, 0, 0, 193, 764, 0 +ATT, 0.00, -2.25, 0.00, 1.87, 0.00, 333.17, 343.17 +GPS, 3, 308941400, 10, 1.49, 24.2397773, 54.5793422, 1.88, 11.04, 1.11, 209.43 +CTUN, 765, 1.07, 0.97, 0.000000, 0, 0, 208, 765, 0 +ATT, 0.00, -2.32, 0.00, 1.56, 0.00, 330.33, 340.33 +CTUN, 702, 1.29, 1.17, 0.000000, 0, 0, 225, 738, 0 +ATT, 0.00, -2.49, 0.00, 0.71, 4.96, 327.66, 337.66 +DU32, 7, 426237 +CURR, 657, 173025, 1152, 0, 4712, 0.000000 +GPS, 3, 308941600, 10, 1.49, 24.2397750, 54.5793408, 2.19, 11.32, 1.42, 210.61 +CTUN, 653, 1.29, 1.66, 0.000000, 0, 0, 237, 653, 0 +ATT, 2.63, -2.14, 0.00, -0.19, 9.48, 326.16, 336.16 +CTUN, 627, 1.67, 1.89, 0.000000, 0, 0, 227, 627, 0 +ATT, 7.21, -0.66, 0.00, -0.13, 15.77, 329.54, 339.54 +GPS, 3, 308941800, 9, 1.75, 24.2397723, 54.5793390, 2.58, 11.63, 1.73, 211.58 +CTUN, 614, 1.67, 1.73, 0.000000, 0, 0, 205, 625, 0 +ATT, 9.50, 1.25, 0.00, 1.51, 18.63, 337.74, 346.96 +CTUN, 606, 2.03, 1.52, 0.000000, 0, 0, 191, 605, 0 +ATT, 10.19, 3.38, 0.00, 2.41, 20.51, 348.93, 355.94 +GPS, 3, 308942000, 10, 1.49, 24.2397692, 54.5793366, 2.84, 11.95, 2.09, 214.41 +CTUN, 606, 2.03, 1.55, 0.000000, 0, 0, 171, 605, 0 +ATT, 9.16, 5.69, 0.00, 2.67, 20.73, 0.59, 5.35 +CTUN, 601, 2.37, 1.53, 0.000000, 0, 0, 155, 605, 0 +ATT, 6.41, 6.52, 0.00, 2.90, 19.30, 11.27, 14.42 +GPS, 3, 308942200, 9, 1.75, 24.2397658, 54.5793338, 3.01, 12.21, 2.30, 215.00 +CTUN, 624, 2.37, 1.53, 0.000000, 0, 0, 130, 624, 0 +ATT, 3.32, 6.15, -5.07, 3.19, 16.32, 20.74, 22.21 +CTUN, 650, 2.62, 1.46, 0.000000, 0, 0, 118, 641, 0 +ATT, 2.40, 5.29, -8.19, 3.70, 15.11, 27.58, 29.11 +GPS, 3, 308942400, 10, 1.49, 24.2397620, 54.5793315, 3.07, 12.41, 2.39, 211.88 +CTUN, 661, 2.62, 1.59, 0.000000, 0, 0, 104, 675, 0 +ATT, 3.54, 4.54, -8.76, 1.94, 13.67, 31.65, 35.33 +CTUN, 665, 2.78, 1.80, 0.000000, 0, 0, 105, 665, 0 +ATT, 3.66, 4.68, -10.03, -0.08, 15.66, 33.31, 41.89 +DU32, 7, 426237 +CURR, 665, 179353, 1191, 0, 4772, 0.000000 +GPS, 3, 308942600, 10, 1.49, 24.2397583, 54.5793293, 3.10, 12.56, 2.37, 209.44 +CTUN, 663, 2.78, 1.91, 0.000000, 0, 0, 95, 663, 0 +ATT, 0.22, 4.64, -9.23, -1.39, 17.20, 36.36, 46.36 +CTUN, 654, 2.89, 1.90, 0.000000, 0, 0, 90, 657, 0 +ATT, 1.03, 3.86, -7.38, -1.82, 21.28, 42.91, 52.91 +GPS, 3, 308942800, 10, 1.49, 24.2397541, 54.5793275, 3.14, 12.72, 2.49, 205.10 +CTUN, 643, 2.89, 1.84, 0.000000, 0, 0, 83, 654, 0 +ATT, 0.00, 2.92, -5.88, -1.81, 27.02, 52.10, 62.10 +CTUN, 631, 3.00, 1.86, 0.000000, 0, 0, 80, 631, 0 +ATT, 0.00, 2.66, -4.15, -1.75, 28.67, 64.10, 74.02 +GPS, 3, 308943000, 10, 1.49, 24.2397499, 54.5793257, 3.15, 12.85, 2.49, 203.53 +CTUN, 631, 2.95, 1.87, 0.000000, 0, 0, 69, 631, 0 +ATT, 0.00, 2.63, -4.96, -1.75, 23.71, 78.12, 86.09 +CTUN, 660, 2.95, 2.01, 0.000000, 0, 0, 61, 647, 0 +ATT, -5.89, 2.46, -7.73, -1.04, 15.33, 91.60, 94.60 +GPS, 3, 308943200, 10, 1.49, 24.2397458, 54.5793241, 3.13, 12.98, 2.39, 201.07 +CTUN, 669, 2.92, 2.01, 0.000000, 0, 0, 51, 669, 0 +ATT, -11.91, 1.23, -0.80, -1.09, 9.70, 100.19, 100.27 +CTUN, 671, 2.92, 2.23, 0.000000, 0, 0, 47, 671, 0 +ATT, -13.18, -2.27, 0.00, -2.84, 6.83, 102.17, 103.82 +GPS, 3, 308943400, 10, 1.49, 24.2397417, 54.5793229, 3.10, 13.02, 2.43, 197.46 +CTUN, 671, 2.88, 2.13, 0.000000, 0, 0, 40, 671, 0 +ATT, -12.37, -5.13, 0.00, -2.32, 0.00, 100.50, 104.72 +CTUN, 704, 2.88, 1.85, 0.000000, 0, 0, 29, 680, 0 +ATT, -13.76, -7.41, 0.00, -1.11, 0.00, 96.80, 104.72 +GPS, 3, 308943600, 10, 1.49, 24.2397374, 54.5793218, 3.05, 13.05, 2.52, 194.86 +DU32, 7, 426237 +CURR, 788, 186664, 1179, 0, 4772, 0.000000 +CTUN, 795, 2.78, 1.37, 0.000000, 0, 1, 23, 789, 0 +ATT, -18.04, -7.97, 0.00, -0.12, 0.00, 92.28, 102.28 +CTUN, 818, 2.78, 1.34, 0.000000, 0, 2, 30, 815, 0 +ATT, -16.54, -11.01, 0.00, -0.87, 0.00, 87.00, 97.00 +GPS, 3, 308943800, 10, 1.49, 24.2397331, 54.5793210, 2.93, 13.02, 2.45, 191.63 +CTUN, 822, 2.78, 1.19, 0.000000, 0, 4, 51, 826, 0 +ATT, -2.31, -10.75, -9.92, -2.65, 0.00, 80.16, 90.16 +CTUN, 822, 2.79, 0.93, 0.000000, 0, 2, 79, 824, 0 +ATT, 0.00, -7.75, -12.57, -1.99, 0.00, 70.73, 80.73 +GPS, 3, 308944000, 10, 1.49, 24.2397295, 54.5793204, 2.85, 13.02, 2.06, 190.65 +CTUN, 806, 2.79, 1.17, 0.000000, 0, 1, 104, 823, 0 +ATT, 0.00, -3.75, -9.69, -5.27, 0.55, 61.01, 71.01 +CTUN, 791, 2.97, 1.15, 0.000000, 0, 1, 138, 793, 0 +ATT, 0.00, -0.50, -7.73, -7.92, 2.64, 52.74, 62.74 +GPS, 3, 308944200, 10, 1.49, 24.2397265, 54.5793199, 2.89, 13.17, 1.60, 190.52 +CTUN, 789, 2.97, 1.41, 0.000000, 0, 1, 152, 790, 0 +ATT, 0.00, -1.02, -7.26, -4.33, 4.08, 48.32, 58.32 +CTUN, 789, 3.13, 1.48, 0.000000, 0, 0, 165, 789, 0 +ATT, 0.00, -1.09, -5.65, -2.59, 2.31, 47.38, 57.38 +GPS, 3, 308944400, 10, 1.49, 24.2397241, 54.5793198, 3.02, 13.42, 1.20, 188.26 +CTUN, 789, 3.13, 1.78, 0.000000, 0, 0, 178, 789, 0 +ATT, -2.77, 0.34, -2.88, -3.51, 0.00, 46.00, 56.00 +CTUN, 789, 3.40, 1.83, 0.000000, 0, 0, 191, 789, 0 +ATT, -8.56, -0.03, -2.19, -3.05, 0.00, 43.49, 53.49 +GPS, 3, 308944600, 10, 1.49, 24.2397223, 54.5793195, 3.23, 13.70, 0.98, 188.84 +DU32, 7, 426237 +CURR, 752, 194666, 1178, 0, 4772, 0.000000 +CTUN, 752, 3.40, 2.44, 0.000000, 0, 0, 191, 757, 0 +ATT, -9.71, -4.57, -3.00, -2.88, 0.00, 42.24, 52.24 +CTUN, 750, 3.68, 2.55, 0.000000, 0, 0, 183, 750, 0 +ATT, -1.96, -6.47, -11.53, -2.66, 0.00, 43.02, 52.21 +GPS, 3, 308944800, 10, 1.49, 24.2397206, 54.5793194, 3.49, 14.03, 0.88, 186.60 +CTUN, 750, 3.68, 2.71, 0.000000, 0, 0, 175, 750, 0 +ATT, 0.00, -4.80, -14.88, -0.75, 0.00, 43.49, 52.21 +CTUN, 745, 4.01, 2.95, 0.000000, 0, 0, 175, 747, 0 +ATT, 0.00, -3.37, -17.30, -3.58, 0.00, 42.24, 52.21 +GPS, 3, 308945000, 10, 1.49, 24.2397191, 54.5793191, 3.74, 14.37, 0.80, 187.43 +CTUN, 740, 4.01, 3.32, 0.000000, 0, 0, 176, 743, 0 +ATT, 0.00, -0.69, -18.57, -8.64, 0.00, 40.53, 50.53 +CTUN, 735, 4.30, 3.31, 0.000000, 0, 1, 171, 736, 0 +ATT, 0.00, 0.62, -19.50, -10.24, 0.00, 40.17, 50.13 +GPS, 3, 308945200, 10, 1.49, 24.2397180, 54.5793187, 4.01, 14.68, 0.65, 191.75 +CTUN, 732, 4.30, 3.44, 0.000000, 0, 1, 163, 735, 0 +ATT, 0.00, -0.11, -14.76, -9.91, 0.00, 40.84, 50.09 +CTUN, 709, 4.61, 3.48, 0.000000, 0, 1, 158, 710, 0 +ATT, 0.00, -0.46, -12.69, -9.64, 0.00, 42.42, 50.09 +GPS, 3, 308945400, 10, 1.49, 24.2397172, 54.5793183, 4.27, 15.03, 0.43, 196.14 +CTUN, 705, 4.61, 3.66, 0.000000, 0, 1, 143, 706, 0 +ATT, 0.00, 0.27, -10.15, -9.44, 0.00, 44.31, 50.09 +CTUN, 703, 4.90, 3.75, 0.000000, 0, 1, 130, 704, 0 +ATT, 0.00, 0.66, -7.73, -9.10, 0.00, 44.59, 50.09 +GPS, 3, 308945600, 10, 1.49, 24.2397169, 54.5793180, 4.45, 15.30, 0.21, 199.72 +DU32, 7, 426237 +CURR, 701, 201958, 1163, 0, 4813, 0.000000 +CTUN, 701, 4.90, 3.81, 0.000000, 0, 0, 120, 701, 0 +ATT, 0.00, -0.49, -5.19, -7.94, 2.31, 43.45, 50.26 +CTUN, 701, 5.11, 3.82, 0.000000, 0, 0, 119, 701, 0 +ATT, -1.15, -1.64, -4.15, -6.09, 7.27, 43.75, 52.49 +GPS, 3, 308945800, 10, 1.49, 24.2397169, 54.5793181, 4.61, 15.49, 0.06, 199.72 +CTUN, 701, 5.11, 3.90, 0.000000, 0, 0, 120, 701, 0 +ATT, -3.12, -1.68, -4.73, -3.25, 9.48, 48.26, 56.41 +CTUN, 701, 5.29, 3.59, 0.000000, 0, 0, 127, 701, 0 +ATT, -3.35, -2.19, -9.23, -0.92, 9.92, 55.08, 60.79 +GPS, 3, 308946000, 10, 1.49, 24.2397172, 54.5793183, 4.76, 15.71, 0.24, 82.92 +CTUN, 701, 5.29, 3.39, 0.000000, 0, 0, 135, 701, 0 +ATT, 0.00, -2.91, -14.65, -0.47, 9.37, 60.34, 65.11 +CTUN, 701, 5.53, 3.43, 0.000000, 0, 0, 146, 701, 0 +ATT, 0.00, -1.73, -19.61, -2.39, 4.63, 63.06, 68.26 +GPS, 3, 308946200, 10, 1.49, 24.2397179, 54.5793185, 4.88, 15.94, 0.41, 31.94 +CTUN, 701, 5.53, 3.52, 0.000000, 0, 0, 162, 701, 0 +ATT, 0.00, 0.06, -19.96, -5.89, 0.00, 62.26, 68.85 +CTUN, 701, 5.53, 3.81, 0.000000, 0, 0, 170, 701, 0 +ATT, 0.00, 2.35, -13.73, -8.94, 0.00, 59.22, 68.85 +GPS, 3, 308946400, 10, 1.49, 24.2397187, 54.5793186, 5.04, 16.18, 0.45, 15.96 +CTUN, 701, 5.20, 4.01, 0.000000, 0, 1, 171, 702, 0 +ATT, 0.00, 1.77, -6.57, -8.07, 0.00, 58.01, 67.94 +CTUN, 701, 5.20, 3.97, 0.000000, 0, 0, 169, 701, 0 +ATT, 0.00, -0.23, 0.00, -5.44, 0.00, 58.22, 67.94 +GPS, 3, 308946600, 10, 1.49, 24.2397195, 54.5793193, 5.25, 16.51, 0.57, 22.90 +DU32, 7, 426237 +CURR, 701, 208969, 1167, 0, 4752, 0.000000 +CTUN, 701, 3.27, 4.09, 0.000000, 0, 0, 174, 701, 0 +ATT, 0.00, -0.13, 0.00, -1.90, 0.00, 59.18, 67.94 +CTUN, 701, 5.20, 3.97, 0.000000, 0, 0, 179, 701, 0 +ATT, 0.00, -0.35, 0.00, 1.30, 0.00, 58.94, 67.94 +GPS, 3, 308946800, 10, 1.49, 24.2397206, 54.5793202, 5.45, 16.80, 0.71, 32.04 +CTUN, 701, 5.20, 4.23, 0.000000, 0, 0, 182, 701, 0 +ATT, 0.00, 1.02, 9.52, 1.15, 0.00, 58.04, 67.94 +CTUN, 656, 5.94, 4.72, 0.000000, 0, 0, 173, 666, 0 +ATT, 0.00, 1.03, 8.72, 2.73, 0.00, 57.53, 67.53 +GPS, 3, 308947000, 10, 1.49, 24.2397216, 54.5793211, 5.65, 17.11, 0.75, 34.04 +CTUN, 649, 5.20, 4.65, 0.000000, 0, 0, 164, 654, 0 +ATT, 0.00, -0.63, 0.57, 7.53, 0.00, 58.69, 67.52 +CTUN, 600, 5.49, 4.82, 0.000000, 0, 0, 144, 623, 0 +ATT, 0.00, -1.18, 0.00, 8.65, 0.22, 60.16, 67.52 +GPS, 3, 308947200, 10, 1.49, 24.2397223, 54.5793221, 5.84, 17.47, 0.70, 41.66 +CTUN, 589, 5.49, 5.22, 0.000000, 0, 0, 131, 589, 0 +ATT, 0.00, 0.38, 0.00, 5.17, 0.44, 60.52, 67.55 +CTUN, 565, 6.22, 5.58, 0.000000, 0, 0, 107, 565, 0 +ATT, -5.78, 1.33, 0.00, 4.36, 0.22, 60.86, 67.55 +GPS, 3, 308947400, 10, 1.49, 24.2397228, 54.5793228, 6.00, 17.71, 0.40, 44.23 +CTUN, 565, 6.22, 5.59, 0.000000, 0, 0, 85, 565, 0 +ATT, -10.75, -2.12, -1.03, 6.38, 0.99, 63.00, 67.63 +CTUN, 565, 6.22, 5.60, 0.000000, 0, 0, 52, 565, 0 +ATT, -12.26, -4.80, -1.61, 6.62, 1.43, 66.94, 68.13 +GPS, 3, 308947600, 10, 1.49, 24.2397230, 54.5793233, 6.08, 17.92, 0.25, 55.24 +CTUN, 578, 6.22, 6.07, 0.000000, 0, 0, 32, 567, 0 +DU32, 7, 426237 +CURR, 578, 215183, 1166, 0, 4732, 0.000000 +ATT, -15.26, -5.47, 0.00, 5.89, 3.30, 69.46, 69.25 +CTUN, 624, 6.35, 6.26, 0.000000, 0, 0, 14, 611, 0 +ATT, -17.35, -8.18, 0.00, 5.58, 2.64, 69.95, 70.59 +GPS, 3, 308947800, 10, 1.49, 24.2397233, 54.5793230, 6.11, 18.00, 0.13, 55.24 +CTUN, 641, 6.35, 5.64, 0.000000, 0, 0, 8, 641, 0 +ATT, -15.50, -10.88, -2.53, 6.10, 2.97, 70.15, 71.75 +CTUN, 641, 6.38, 5.25, 0.000000, 0, 0, 0, 641, 0 +ATT, -9.94, -12.58, -8.76, 7.05, 3.41, 69.66, 73.09 +GPS, 3, 308948000, 10, 1.49, 24.2397234, 54.5793225, 6.07, 18.01, 0.23, 337.25 +CTUN, 641, 6.37, 5.66, 0.000000, 0, 0, -4, 641, 0 +ATT, -5.43, -11.76, -13.03, 5.49, 2.42, 68.81, 74.45 +CTUN, 606, 6.38, 6.50, 0.000000, 0, 0, 12, 613, 0 +ATT, 0.00, -8.89, -20.07, 0.77, 2.86, 66.29, 75.54 +GPS, 3, 308948200, 10, 1.49, 24.2397239, 54.5793215, 6.04, 18.00, 0.54, 299.77 +CTUN, 603, 6.38, 6.39, 0.000000, 0, 0, 33, 603, 0 +ATT, 0.00, -4.84, -21.46, -2.69, 3.97, 64.50, 74.50 +CTUN, 603, 6.38, 6.36, 0.000000, 0, 0, 47, 603, 0 +ATT, 0.00, -3.16, -21.80, -5.04, 6.28, 65.85, 75.78 +GPS, 3, 308948400, 10, 1.49, 24.2397249, 54.5793199, 6.17, 18.01, 0.96, 301.57 +CTUN, 605, 6.38, 6.32, 0.000000, 0, 0, 55, 605, 0 +PM, 0, 0, 50, 8, 1000, 11104, 11, 0 +ATT, 0.00, -2.21, -19.38, -6.79, 6.50, 69.40, 78.71 +CTUN, 602, 6.38, 6.49, 0.000000, 0, 0, 69, 602, 0 +ATT, 0.00, -1.53, -12.46, -8.17, 4.30, 73.78, 80.99 +GPS, 3, 308948600, 10, 1.49, 24.2397263, 54.5793181, 6.32, 18.11, 1.26, 307.37 +CTUN, 583, 6.38, 6.37, 0.000000, 0, 0, 85, 593, 0 +DU32, 7, 426237 +CURR, 571, 221341, 1176, 0, 4772, 0.000000 +ATT, 0.00, -0.61, -1.15, -6.84, 3.63, 77.36, 82.73 +CTUN, 539, 6.38, 6.49, 0.000000, 0, 0, 95, 539, 0 +ATT, 0.00, -0.82, 0.00, -2.38, 3.86, 81.06, 84.46 +GPS, 3, 308948800, 10, 1.49, 24.2397283, 54.5793165, 6.51, 18.23, 1.39, 318.36 +CTUN, 436, 6.33, 6.64, 0.000000, 0, 0, 92, 511, 0 +ATT, 0.00, -1.30, 0.00, 2.26, 3.63, 85.93, 86.12 +CTUN, 429, 6.33, 7.03, 0.000000, 0, 0, 89, 428, 0 +ATT, -1.15, -1.19, 0.00, 4.02, 4.19, 90.68, 87.72 +GPS, 3, 308949000, 10, 1.49, 24.2397303, 54.5793155, 6.70, 18.37, 1.22, 323.49 +CTUN, 417, 6.33, 7.10, 0.000000, 0, 0, 76, 417, 0 +ATT, -9.37, 0.31, 0.00, 4.86, 4.74, 93.89, 89.69 +CTUN, 409, 6.38, 7.26, 0.000000, 0, 0, 61, 412, 0 +ATT, -13.30, -1.45, 0.00, 5.57, 4.41, 96.75, 91.70 +GPS, 3, 308949200, 10, 1.49, 24.2397325, 54.5793145, 6.88, 18.51, 1.30, 331.60 +CTUN, 399, 6.38, 7.43, 0.000000, 0, 0, 30, 400, 0 +ATT, -16.42, -3.26, 0.00, 4.86, 4.19, 99.89, 93.59 +CTUN, 380, 6.38, 7.49, 0.000000, 0, 0, 10, 382, 0 +ATT, -17.46, -4.90, -1.15, 3.99, 3.97, 102.54, 95.38 +GPS, 3, 308949400, 9, 1.96, 24.2397344, 54.5793134, 6.97, 18.62, 1.22, 332.09 +CTUN, 376, 6.37, 7.61, 0.000000, 0, 0, -23, 378, 0 +ATT, -17.58, -7.26, -3.34, 3.17, 2.75, 104.90, 96.87 +CTUN, 378, 6.37, 7.40, 0.000000, 0, 0, -51, 378, 0 +ATT, -18.74, -9.68, -3.80, 1.52, 1.54, 105.90, 97.64 +GPS, 3, 308949600, 10, 1.49, 24.2397364, 54.5793120, 6.95, 18.61, 1.28, 331.25 +CTUN, 387, 5.35, 7.03, 0.000000, 0, 0, -84, 384, 0 +DU32, 7, 426237 +CURR, 387, 225610, 1187, 0, 4793, 0.000000 +ATT, -19.78, -10.85, -6.34, 0.93, 1.43, 105.06, 98.22 +CTUN, 390, 6.22, 6.88, 0.000000, 0, 0, -106, 390, 0 +ATT, -20.24, -12.72, -6.57, 1.35, 1.21, 102.78, 98.72 +GPS, 3, 308949800, 9, 1.96, 24.2397387, 54.5793106, 6.79, 18.48, 1.36, 331.24 +CTUN, 456, 6.22, 6.55, 0.000000, 0, 0, -131, 456, 0 +ATT, -20.70, -14.28, -6.80, 0.96, 3.86, 100.93, 99.60 +CTUN, 527, 6.36, 6.40, 0.000000, 0, 0, -142, 527, 0 +ATT, -17.00, -14.49, -8.53, 0.02, 6.17, 100.34, 101.90 +GPS, 3, 308950000, 10, 1.49, 24.2397411, 54.5793093, 6.49, 18.26, 1.48, 332.48 +CTUN, 563, 6.36, 5.94, 0.000000, 0, 0, -140, 563, 0 +ATT, -4.62, -12.77, -13.73, 0.40, 8.16, 100.20, 105.20 +CTUN, 570, 6.36, 5.71, 0.000000, 0, 0, -111, 570, 0 +ATT, 0.00, -9.68, -15.46, 1.26, 9.04, 101.05, 109.21 +GPS, 3, 308950200, 10, 1.49, 24.2397443, 54.5793082, 6.20, 17.91, 1.80, 337.72 +CTUN, 570, 6.36, 5.44, 0.000000, 0, 0, -67, 570, 0 +ATT, 0.00, -6.54, -15.46, 0.17, 7.94, 103.34, 112.81 +CTUN, 570, 6.40, 5.23, 0.000000, 0, 0, -13, 570, 0 +ATT, 0.00, -2.51, -14.53, -2.23, 3.75, 105.60, 115.41 +GPS, 3, 308950400, 10, 1.49, 24.2397483, 54.5793073, 6.05, 17.65, 2.28, 342.85 +CTUN, 509, 6.40, 5.39, 0.000000, 0, 0, 35, 536, 0 +ATT, 0.00, 0.73, -15.00, -3.07, 1.98, 107.93, 116.62 +CTUN, 451, 6.40, 5.49, 0.000000, 0, 0, 62, 458, 0 +ATT, 0.00, 1.47, -14.65, -3.53, 0.77, 110.08, 117.28 +GPS, 3, 308950600, 10, 1.49, 24.2397529, 54.5793066, 6.07, 17.57, 2.67, 347.06 +CTUN, 399, 6.38, 5.42, 0.000000, 0, 0, 65, 409, 0 +DU32, 7, 426237 +CURR, 376, 230636, 1175, 0, 4732, 0.000000 +ATT, 0.00, 1.79, -10.61, -5.48, 0.00, 111.55, 117.31 +CTUN, 356, 6.38, 5.52, 0.000000, 0, 0, 63, 356, 0 +ATT, 0.00, 2.20, -8.19, -6.63, 0.00, 112.53, 117.31 +GPS, 3, 308950800, 9, 1.96, 24.2397573, 54.5793061, 6.12, 17.71, 2.56, 350.74 +CTUN, 350, 6.38, 5.53, 0.000000, 0, 0, 47, 355, 0 +ATT, 0.00, 2.02, -7.84, -6.39, 0.00, 114.39, 117.31 +CTUN, 348, 6.38, 5.55, 0.000000, 0, 0, 27, 348, 0 +GPS, 3, 308951000, 9, 1.96, 24.2397614, 54.5793061, 6.12, 17.81, 2.32, 355.08 +ATT, 0.00, 1.43, -6.34, -5.93, 0.00, 115.70, 117.31 +CTUN, 346, 6.38, 5.86, 0.000000, 0, 0, 6, 346, 0 +ATT, -3.23, 0.98, -1.61, -5.31, 0.00, 116.69, 117.31 +CTUN, 346, 6.38, 5.93, 0.000000, 0, 0, -13, 346, 0 +GPS, 3, 308951200, 10, 1.49, 24.2397650, 54.5793062, 6.07, 17.83, 1.96, 357.55 +ATT, -8.21, 0.23, 0.00, -3.84, 0.00, 117.09, 117.31 +CTUN, 343, 6.38, 5.85, 0.000000, 0, 0, -42, 343, 0 +ATT, -14.46, -0.69, 0.00, -1.76, 0.00, 117.57, 117.31 +CTUN, 435, 6.38, 5.63, 0.000000, 0, 0, -84, 426, 0 +GPS, 3, 308951400, 10, 1.49, 24.2397680, 54.5793065, 5.92, 17.76, 1.69, 1.23 +ATT, -16.19, -4.42, 0.00, -1.05, 0.00, 118.46, 117.31 +CTUN, 452, 6.38, 5.62, 0.000000, 0, 0, -113, 450, 0 +ATT, -15.73, -6.42, 0.00, -2.56, 0.00, 117.88, 117.31 +CTUN, 464, 6.38, 5.35, 0.000000, 0, 0, -127, 464, 0 +ATT, -12.26, -5.91, 0.00, -1.31, 0.00, 116.56, 117.31 +GPS, 3, 308951600, 10, 1.49, 24.2397708, 54.5793070, 5.63, 17.58, 1.49, 5.88 +CTUN, 480, 6.38, 5.29, 0.000000, 0, 0, -144, 465, 0 +DU32, 7, 426237 +CURR, 506, 234520, 1173, 0, 4793, 0.000000 +ATT, -9.60, -7.19, 0.00, 1.99, 0.00, 114.91, 117.31 +CTUN, 535, 6.38, 5.00, 0.000000, 0, 0, -160, 530, 0 +ATT, -5.20, -5.87, 0.00, 3.24, 0.00, 113.56, 117.31 +GPS, 3, 308951800, 10, 1.49, 24.2397735, 54.5793076, 5.29, 17.25, 1.44, 9.21 +CTUN, 547, 6.38, 4.98, 0.000000, 0, 0, -140, 547, 0 +ATT, 0.00, -3.75, 0.00, 4.21, 0.00, 111.82, 117.31 +CTUN, 553, 6.38, 4.81, 0.000000, 0, 0, -108, 553, 0 +ATT, 0.00, -0.65, 0.00, 6.23, 0.66, 110.32, 117.35 +GPS, 3, 308952000, 10, 1.49, 24.2397766, 54.5793084, 5.02, 16.88, 1.67, 11.07 +CTUN, 553, 6.27, 4.78, 0.000000, 0, 0, -75, 553, 0 +ATT, 0.00, 1.26, -8.42, 8.62, 2.86, 109.89, 118.12 +CTUN, 552, 6.27, 4.66, 0.000000, 0, 0, -39, 564, 0 +ATT, 0.00, 1.53, -12.11, 6.89, 4.63, 111.51, 119.73 +GPS, 3, 308952200, 10, 1.49, 24.2397797, 54.5793090, 4.89, 16.61, 1.75, 9.72 +CTUN, 495, 5.75, 4.76, 0.000000, 0, 0, -2, 531, 0 +ATT, 0.00, 1.79, -16.26, 1.89, 3.75, 113.17, 121.45 +CTUN, 463, 5.91, 4.75, 0.000000, 0, 0, 33, 478, 0 +GPS, 3, 308952400, 10, 1.49, 24.2397828, 54.5793093, 4.90, 16.54, 1.88, 4.04 +ATT, 0.00, 2.95, -16.73, -1.45, 3.19, 115.71, 122.96 +CTUN, 427, 5.90, 4.63, 0.000000, 0, 0, 50, 438, 0 +ATT, 0.00, 3.21, -15.34, -3.07, 1.54, 120.03, 123.90 +CTUN, 411, 5.90, 4.68, 0.000000, 0, 0, 62, 414, 0 +GPS, 3, 308952600, 10, 1.49, 24.2397858, 54.5793091, 4.99, 16.58, 1.79, 1.21 +ATT, 0.00, 2.73, -12.57, -4.54, 1.10, 124.27, 124.36 +CTUN, 388, 5.90, 4.87, 0.000000, 0, 0, 68, 388, 0 +DU32, 7, 426237 +CURR, 388, 239511, 1194, 0, 4772, 0.000000 +ATT, 0.00, 2.25, -8.07, -6.26, 0.00, 126.85, 124.52 +CTUN, 378, 5.94, 4.63, 0.000000, 0, 0, 66, 378, 0 +GPS, 3, 308952800, 9, 1.96, 24.2397885, 54.5793090, 5.09, 16.67, 1.59, 0.05 +ATT, 0.00, 1.85, -6.11, -6.54, 0.00, 127.71, 124.52 +CTUN, 375, 5.94, 4.91, 0.000000, 0, 0, 40, 376, 0 +ATT, 0.00, 1.82, -3.23, -5.65, 0.00, 127.79, 124.52 +CTUN, 369, 5.94, 4.81, 0.000000, 0, 0, 10, 369, 0 +GPS, 3, 308953000, 10, 1.49, 24.2397904, 54.5793091, 5.11, 16.77, 1.11, 1.03 +ATT, 0.00, 2.62, -0.80, -4.05, 0.00, 128.23, 124.52 +CTUN, 369, 4.30, 5.05, 0.000000, 0, 0, -13, 369, 0 +ATT, 0.00, 3.59, 0.00, -1.94, 0.00, 128.54, 124.52 +CTUN, 369, 4.30, 5.06, 0.000000, 0, 0, -37, 369, 0 +ATT, 0.00, 3.78, 0.00, -0.02, 0.00, 129.78, 124.52 +GPS, 3, 308953200, 10, 1.49, 24.2397920, 54.5793093, 5.03, 16.74, 0.86, 3.03 +CTUN, 428, 4.30, 5.04, 0.000000, 0, 0, -58, 385, 0 +ATT, 0.00, 3.73, 2.52, 0.73, 0.00, 130.70, 124.52 +CTUN, 447, 5.53, 4.91, 0.000000, 0, 0, -75, 441, 0 +ATT, -1.27, 4.20, 2.18, 1.46, 0.00, 131.40, 124.52 +GPS, 3, 308953400, 10, 1.49, 24.2397933, 54.5793095, 4.89, 16.59, 0.66, 4.09 +CTUN, 464, 5.53, 4.78, 0.000000, 0, 0, -74, 460, 0 +ATT, -6.94, 5.17, 0.00, 3.17, 0.00, 131.19, 124.52 +CTUN, 506, 5.68, 4.78, 0.000000, 0, 0, -79, 490, 0 +GPS, 3, 308953600, 10, 1.49, 24.2397943, 54.5793098, 4.74, 16.36, 0.49, 5.69 +ATT, -9.71, 3.23, 0.00, 4.14, 0.00, 130.40, 124.52 +CTUN, 523, 5.58, 4.68, 0.000000, 0, 0, -76, 523, 0 +DU32, 7, 426237 +CURR, 523, 243668, 1180, 0, 4752, 0.000000 +ATT, -12.03, 0.69, 0.00, 2.49, 0.00, 129.27, 124.52 +CTUN, 517, 5.58, 4.59, 0.000000, 0, 0, -70, 522, 0 +ATT, -14.46, 0.14, 0.00, 1.72, 0.00, 126.95, 124.52 +GPS, 3, 308953800, 10, 1.49, 24.2397951, 54.5793096, 4.59, 16.19, 0.43, 358.60 +CTUN, 515, 5.39, 4.34, 0.000000, 0, 0, -62, 518, 0 +ATT, -14.57, -2.38, -1.61, 2.83, 0.00, 125.42, 124.52 +CTUN, 496, 5.39, 4.29, 0.000000, 0, 0, -73, 512, 0 +ATT, -11.79, -5.10, -2.76, 2.53, 0.00, 124.96, 124.52 +GPS, 3, 308954000, 10, 1.49, 24.2397956, 54.5793093, 4.43, 16.00, 0.36, 347.89 +CTUN, 492, 5.29, 4.27, 0.000000, 0, 0, -69, 492, 0 +ATT, -7.98, -5.56, -1.84, 2.06, 0.00, 124.33, 124.52 +CTUN, 490, 5.29, 4.05, 0.000000, 0, 0, -68, 490, 0 +ATT, -3.47, -3.79, 0.00, 2.58, 0.00, 124.17, 124.52 +GPS, 3, 308954200, 10, 1.49, 24.2397963, 54.5793089, 4.26, 15.84, 0.46, 336.26 +CTUN, 490, 5.13, 4.04, 0.000000, 0, 0, -62, 487, 0 +ATT, 0.00, -1.80, 0.00, 4.75, 0.55, 124.17, 124.57 +CTUN, 493, 5.13, 3.92, 0.000000, 0, 0, -58, 492, 0 +GPS, 3, 308954400, 10, 1.49, 24.2397973, 54.5793087, 4.14, 15.66, 0.54, 344.04 +ATT, 0.00, 0.29, 0.00, 5.86, 0.22, 124.38, 124.63 +CTUN, 492, 4.91, 4.01, 0.000000, 0, 0, -51, 492, 0 +ATT, 0.00, 2.38, 2.64, 5.62, 0.22, 124.95, 124.64 +CTUN, 483, 4.91, 3.91, 0.000000, 0, 0, -40, 483, 0 +GPS, 3, 308954600, 10, 1.49, 24.2397985, 54.5793085, 4.02, 15.50, 0.70, 347.84 +ATT, 0.00, 4.32, 0.00, 5.96, 0.00, 124.79, 124.64 +CTUN, 478, 4.74, 3.62, 0.000000, 0, 0, -30, 478, 0 +DU32, 7, 426237 +CURR, 471, 248632, 1160, 0, 4752, 0.000000 +ATT, -1.38, 4.40, 0.00, 6.77, 0.00, 124.79, 124.64 +CTUN, 471, 4.74, 3.66, 0.000000, 0, 0, -17, 471, 0 +GPS, 3, 308954800, 10, 1.49, 24.2397996, 54.5793079, 3.94, 15.37, 0.73, 339.87 +ATT, -7.98, 3.52, 0.00, 5.76, 0.00, 125.75, 124.64 +CTUN, 471, 4.64, 3.94, 0.000000, 0, 0, -22, 471, 0 +ATT, -9.02, 0.37, 0.00, 2.83, 0.00, 126.03, 124.64 +CTUN, 458, 4.64, 3.96, 0.000000, 0, 0, -34, 466, 0 +GPS, 3, 308955000, 10, 1.49, 24.2398006, 54.5793070, 3.87, 15.27, 0.78, 328.05 +ATT, -10.64, -0.67, 0.00, 0.22, 0.00, 126.35, 124.64 +CTUN, 448, 4.57, 3.65, 0.000000, 0, 0, -41, 450, 0 +ATT, -8.56, -1.31, 0.00, 0.96, 0.00, 126.79, 124.64 +CTUN, 447, 4.57, 3.65, 0.000000, 0, 0, -56, 447, 0 +GPS, 3, 308955200, 10, 1.49, 24.2398016, 54.5793058, 3.77, 15.18, 0.84, 320.08 +ATT, -8.32, -2.34, 0.00, 2.89, 0.00, 127.61, 124.64 +CTUN, 477, 4.44, 3.53, 0.000000, 0, 0, -73, 477, 0 +ATT, -9.83, -2.80, 0.00, 3.66, 0.00, 129.31, 124.64 +CTUN, 489, 4.44, 3.54, 0.000000, 0, 0, -85, 489, 0 +GPS, 3, 308955400, 10, 1.49, 24.2398027, 54.5793045, 3.58, 15.00, 0.88, 315.92 +ATT, -9.71, -2.55, 0.00, 2.93, 0.00, 130.08, 124.64 +CTUN, 492, 4.25, 3.27, 0.000000, 0, 0, -91, 492, 0 +ATT, -6.70, -2.97, 0.00, 2.30, 0.22, 129.61, 124.64 +CTUN, 492, 4.25, 3.29, 0.000000, 0, 0, -89, 492, 0 +GPS, 3, 308955600, 10, 1.49, 24.2398039, 54.5793034, 3.38, 14.80, 0.83, 317.21 +ATT, -4.74, -2.61, 0.00, 1.84, 0.11, 128.89, 124.64 +CTUN, 490, 4.07, 3.10, 0.000000, 0, 0, -92, 490, 0 +DU32, 7, 426237 +CURR, 492, 253367, 1185, 0, 4772, 0.000000 +ATT, -4.51, -1.30, 0.00, 2.49, 0.11, 127.47, 124.64 +CTUN, 490, 4.07, 3.06, 0.000000, 0, 0, -97, 490, 0 +GPS, 3, 308955800, 10, 1.49, 24.2398051, 54.5793024, 3.17, 14.65, 0.88, 321.05 +ATT, -1.96, -0.50, 0.00, 3.18, 0.11, 126.44, 124.65 +CTUN, 490, 3.87, 2.82, 0.000000, 0, 0, -106, 492, 0 +ATT, 0.00, 0.30, 0.00, 3.75, 0.00, 125.65, 124.65 +CTUN, 498, 3.87, 2.65, 0.000000, 0, 0, -106, 498, 0 +GPS, 3, 308956000, 10, 1.49, 24.2398064, 54.5793012, 2.93, 14.39, 0.92, 320.32 +ATT, 0.00, 2.41, 0.00, 4.70, 0.00, 124.91, 124.65 +CTUN, 498, 3.63, 2.57, 0.000000, 0, 0, -102, 496, 0 +ATT, 0.00, 3.78, -0.57, 5.68, 0.00, 125.59, 124.65 +CTUN, 511, 3.63, 2.72, 0.000000, 0, 0, -89, 511, 0 +GPS, 3, 308956200, 10, 1.49, 24.2398077, 54.5793001, 2.72, 14.12, 0.92, 319.97 +ATT, 0.00, 4.50, -4.50, 4.98, 0.00, 126.59, 124.65 +CTUN, 511, 3.37, 2.58, 0.000000, 0, 0, -77, 511, 0 +ATT, -0.92, 4.69, -3.23, 3.73, 0.00, 126.89, 124.65 +CTUN, 511, 3.37, 2.42, 0.000000, 0, 0, -58, 511, 0 +GPS, 3, 308956400, 10, 1.49, 24.2398088, 54.5792988, 2.56, 13.90, 0.97, 315.97 +ATT, -3.47, 4.54, -2.19, 2.47, 0.00, 126.89, 124.65 +CTUN, 513, 3.08, 2.29, 0.000000, 0, 0, -48, 511, 0 +ATT, -4.97, 3.82, -2.19, 1.06, 0.00, 126.13, 124.65 +CTUN, 515, 3.08, 2.37, 0.000000, 0, 0, -40, 515, 0 +GPS, 3, 308956600, 10, 1.49, 24.2398099, 54.5792969, 2.45, 13.78, 1.19, 309.50 +ATT, -5.32, 3.12, -1.38, 0.38, 0.00, 125.79, 124.65 +CTUN, 511, 3.08, 2.21, 0.000000, 0, 0, -34, 512, 0 +DU32, 7, 426237 +CURR, 511, 258397, 1180, 0, 4772, 0.000000 +ATT, -6.01, 1.91, 0.00, 0.05, 0.00, 125.70, 124.65 +CTUN, 494, 3.08, 2.32, 0.000000, 0, 0, -31, 511, 0 +GPS, 3, 308956800, 10, 1.49, 24.2398108, 54.5792949, 2.37, 13.69, 1.18, 302.50 +ATT, -13.65, 0.91, 0.00, -0.20, 0.00, 125.12, 124.65 +CTUN, 492, 2.98, 2.20, 0.000000, 0, 0, -37, 492, 0 +ATT, -14.92, -2.31, 0.00, 0.12, 0.00, 124.90, 124.65 +CTUN, 492, 2.98, 2.21, 0.000000, 0, 0, -55, 492, 0 +GPS, 3, 308957000, 10, 1.49, 24.2398115, 54.5792928, 2.27, 13.60, 1.16, 298.74 +ATT, -13.99, -6.29, 0.00, -1.03, 0.00, 125.59, 124.65 +CTUN, 492, 2.89, 2.00, 0.000000, 0, 0, -60, 492, 0 +ATT, -7.40, -6.50, -6.23, -1.43, 0.00, 126.31, 124.65 +CTUN, 492, 2.89, 1.91, 0.000000, 0, 0, -70, 490, 0 +GPS, 3, 308957200, 10, 1.49, 24.2398121, 54.5792909, 2.11, 13.47, 1.02, 295.17 +ATT, -1.15, -4.76, -8.76, 0.56, 0.00, 126.32, 124.65 +CTUN, 498, 2.75, 1.84, 0.000000, 0, 0, -79, 492, 0 +ATT, 0.00, -2.04, -7.03, 0.00, 0.00, 126.07, 124.65 +CTUN, 530, 2.75, 1.81, 0.000000, 0, 0, -84, 524, 0 +GPS, 3, 308957400, 10, 1.49, 24.2398129, 54.5792893, 1.93, 13.29, 0.93, 294.87 +ATT, 0.00, 0.70, -6.92, -1.11, 0.00, 125.40, 124.65 +CTUN, 531, 2.57, 1.58, 0.000000, 0, 0, -76, 531, 0 +ATT, -3.47, 3.32, -7.96, -0.28, 0.00, 125.03, 124.65 +CTUN, 534, 2.57, 1.55, 0.000000, 0, 0, -62, 531, 0 +GPS, 3, 308957600, 10, 1.49, 24.2398135, 54.5792880, 1.76, 13.13, 0.73, 297.00 +ATT, -9.71, 3.54, -6.46, -0.27, 0.00, 125.22, 124.65 +CTUN, 549, 2.38, 1.46, 0.000000, 0, 0, -45, 549, 0 +DU32, 7, 426237 +CURR, 549, 263501, 1169, 0, 4752, 0.000000 +ATT, -11.68, 1.07, -4.96, -2.03, 0.00, 125.91, 124.65 +CTUN, 549, 2.38, 1.31, 0.000000, 0, 0, -29, 549, 0 +GPS, 3, 308957800, 10, 1.49, 24.2398142, 54.5792867, 1.65, 12.98, 0.81, 297.46 +ATT, -11.22, -0.71, -4.84, -3.14, 0.00, 126.75, 124.65 +CTUN, 530, 2.24, 1.46, 0.000000, 0, 0, -16, 539, 0 +ATT, -8.90, -1.71, -4.84, -2.62, 0.00, 126.64, 124.65 +CTUN, 511, 2.24, 1.36, 0.000000, 0, 0, -15, 511, 0 +GPS, 3, 308958000, 10, 1.49, 24.2398145, 54.5792855, 1.58, 12.92, 0.75, 296.41 +ATT, -4.62, -2.64, -2.76, -2.15, 0.00, 126.28, 124.65 +CTUN, 483, 2.18, 1.53, 0.000000, 0, 0, -21, 486, 0 +ATT, -9.37, -1.86, 0.00, -1.86, 0.00, 126.43, 124.65 +CTUN, 486, 2.18, 1.51, 0.000000, 0, 0, -32, 486, 0 +GPS, 3, 308958200, 10, 1.49, 24.2398148, 54.5792846, 1.52, 12.88, 0.51, 295.31 +ATT, -10.41, -1.71, 0.00, 0.02, 0.00, 126.84, 124.65 +CTUN, 499, 2.12, 1.50, 0.000000, 0, 0, -50, 481, 0 +ATT, -10.29, -3.83, 0.00, 0.81, 0.00, 128.17, 124.65 +CTUN, 521, 2.12, 1.28, 0.000000, 0, 0, -54, 521, 0 +GPS, 3, 308958400, 10, 1.49, 24.2398152, 54.5792840, 1.41, 12.77, 0.39, 297.65 +ATT, -11.68, -3.93, 0.00, 0.30, 0.00, 129.19, 124.65 +CTUN, 522, 2.01, 1.24, 0.000000, 0, 0, -60, 522, 0 +PM, 0, 0, 50, 1, 1000, 10504, 9, 0 +ATT, -12.03, -4.03, 0.00, 1.26, 0.00, 128.16, 124.65 +CTUN, 522, 2.01, 1.05, 0.000000, 0, 0, -61, 522, 0 +GPS, 3, 308958600, 10, 1.49, 24.2398156, 54.5792835, 1.28, 12.63, 0.30, 305.68 +ATT, -5.78, -4.42, 0.00, 2.45, 0.00, 126.66, 124.65 +CTUN, 522, 1.86, 1.07, 0.000000, 0, 0, -64, 522, 0 +DU32, 7, 426237 +CURR, 522, 268663, 1156, 0, 4752, 0.000000 +ATT, 0.00, -3.43, -1.03, 2.72, 0.00, 125.13, 124.65 +CTUN, 522, 1.86, 0.86, 0.000000, 0, 0, -52, 522, 0 +GPS, 3, 308958800, 10, 1.49, 24.2398161, 54.5792834, 1.13, 12.48, 0.29, 319.57 +ATT, 0.00, 0.30, -0.57, 3.90, 0.00, 124.04, 124.65 +CTUN, 522, 1.72, 0.89, 0.000000, 0, 0, -54, 522, 0 +ATT, 0.00, 1.82, 0.00, 5.37, 0.00, 124.11, 124.65 +CTUN, 522, 1.72, 0.77, 0.000000, 0, 0, -52, 522, 0 +GPS, 3, 308959000, 10, 1.49, 24.2398169, 54.5792832, 1.00, 12.34, 0.44, 337.97 +ATT, 0.00, 2.51, 0.00, 5.09, 0.00, 124.02, 124.65 +CTUN, 522, 1.60, 0.65, 0.000000, 0, 0, -50, 522, 0 +ATT, 0.00, 3.80, -0.34, 4.87, 0.00, 124.13, 124.65 +CTUN, 523, 1.60, 0.58, 0.000000, 0, 0, -41, 525, 0 +GPS, 3, 308959200, 10, 1.49, 24.2398176, 54.5792830, 0.88, 12.20, 0.45, 340.97 +ATT, 0.00, 4.78, 0.00, 4.70, 0.00, 124.40, 124.65 +CTUN, 523, 1.49, 0.61, 0.000000, 0, 0, -37, 523, 0 +ATT, -5.66, 5.11, 0.00, 4.17, 0.00, 124.09, 124.65 +CTUN, 523, 1.49, 0.49, 0.000000, 0, 0, -34, 523, 0 +GPS, 3, 308959400, 10, 1.49, 24.2398183, 54.5792823, 0.77, 12.11, 0.56, 324.86 +ATT, -7.05, 3.59, -0.80, 3.69, 0.00, 124.38, 124.65 +CTUN, 523, 1.30, 0.54, 0.000000, 0, 0, -38, 523, 0 +ATT, -5.43, 1.09, -4.26, 2.59, 0.00, 124.72, 124.65 +CTUN, 523, 1.30, 0.33, 0.000000, 0, 0, -33, 523, 0 +GPS, 3, 308959600, 10, 1.49, 24.2398189, 54.5792814, 0.67, 12.03, 0.60, 316.19 +ATT, -5.43, 0.96, -4.26, 1.54, 0.00, 124.99, 124.65 +CTUN, 523, 1.29, 0.53, 0.000000, 0, 0, -33, 523, 0 +DU32, 7, 426237 +CURR, 523, 273896, 1157, 0, 4752, 0.000000 +ATT, -3.23, 0.87, -6.46, 1.04, 0.00, 125.26, 124.65 +CTUN, 523, 1.29, 0.48, 0.000000, 0, 0, -36, 523, 0 +GPS, 3, 308959800, 10, 1.49, 24.2398196, 54.5792803, 0.58, 11.96, 0.72, 310.23 +ATT, -1.96, 0.98, -7.96, 0.26, 0.00, 125.17, 124.65 +CTUN, 523, 1.23, 0.39, 0.000000, 0, 0, -38, 523, 0 +ATT, -4.16, 1.76, -7.84, -0.33, 0.00, 125.30, 124.65 +CTUN, 523, 1.23, 0.29, 0.000000, 0, 0, -40, 523, 0 +GPS, 3, 308960000, 10, 1.49, 24.2398202, 54.5792790, 0.48, 11.89, 0.73, 303.57 +ATT, -6.94, 2.06, -5.65, -0.90, 0.00, 125.76, 124.65 +CTUN, 523, 1.14, 0.32, 0.000000, 0, 0, -41, 523, 0 +ATT, -8.79, 1.27, -5.53, -1.50, 0.00, 125.91, 124.65 +CTUN, 535, 1.14, 0.27, 0.000000, 0, 0, -41, 535, 0 +GPS, 3, 308960200, 10, 1.49, 24.2398209, 54.5792779, 0.38, 11.78, 0.67, 303.56 +ATT, -9.48, 0.09, -5.42, -2.59, 0.00, 126.10, 124.65 +CTUN, 548, 1.05, 0.27, 0.000000, 0, 0, -35, 548, 0 +ATT, -9.71, -0.80, -5.42, -3.09, 0.00, 125.78, 124.65 +CTUN, 548, 1.05, 0.07, 0.000000, 0, 0, -28, 548, 0 +GPS, 3, 308960400, 10, 1.49, 24.2398212, 54.5792768, 0.30, 11.70, 0.61, 299.83 +ATT, -9.02, -1.61, -5.42, -2.93, 0.00, 125.14, 124.65 +CTUN, 548, 0.96, 0.09, 0.000000, 0, 0, -27, 548, 0 +ATT, -6.59, -2.42, -5.19, -2.67, 0.00, 124.88, 124.65 +CTUN, 548, 0.96, 0.20, 0.000000, 0, 0, -29, 548, 0 +GPS, 3, 308960600, 10, 1.49, 24.2398215, 54.5792760, 0.22, 11.64, 0.50, 296.37 +ATT, -3.70, -2.32, -5.19, -2.38, 0.00, 124.49, 124.65 +CTUN, 537, 0.90, 0.11, 0.000000, 0, 0, -29, 537, 0 +DU32, 7, 426237 +CURR, 533, 279259, 1175, 0, 4752, 0.000000 +ATT, -2.77, -0.91, -4.96, -1.01, 0.00, 123.81, 124.65 +CTUN, 533, 0.90, 0.05, 0.000000, 0, 0, -29, 533, 0 +GPS, 3, 308960800, 10, 1.49, 24.2398217, 54.5792755, 0.15, 11.58, 0.31, 296.55 +ATT, -1.38, -0.08, -3.92, 0.13, 0.00, 123.62, 124.65 +CTUN, 533, 0.85, 0.04, 0.000000, 0, 0, -36, 533, 0 +ATT, -0.34, 0.65, -2.88, -0.06, 0.00, 124.03, 124.65 +CTUN, 533, 0.85, 0.01, 0.000000, 0, 0, -36, 533, 0 +GPS, 3, 308961000, 10, 1.49, 24.2398218, 54.5792752, 0.07, 11.50, 0.14, 296.55 +ATT, -4.16, 2.63, -2.76, 0.57, 0.00, 124.62, 124.65 +CTUN, 530, 0.74, 0.04, 0.000000, 0, 0, -46, 530, 0 +ATT, -3.12, 2.14, -4.73, 1.67, 0.00, 125.33, 124.65 +CTUN, 530, 0.74, 0.04, 0.000000, 0, 0, -44, 530, 0 +GPS, 3, 308961200, 10, 1.49, 24.2398220, 54.5792751, -0.01, 11.44, 0.16, 296.55 +ATT, -5.32, 1.83, -4.03, 1.21, 0.00, 125.76, 124.65 +CTUN, 531, 0.67, -0.04, 0.000000, 0, 0, -46, 531, 0 +ATT, -8.21, 2.36, -3.46, 0.60, 0.00, 126.07, 124.65 +CTUN, 531, 0.67, -0.09, 0.000000, 0, 0, -42, 531, 0 +GPS, 3, 308961400, 10, 1.49, 24.2398218, 54.5792749, -0.09, 11.35, 0.12, 296.55 +ATT, -8.79, 1.16, -3.34, 0.81, 0.00, 126.05, 124.65 +CTUN, 530, 0.57, -0.17, 0.000000, 0, 0, -49, 530, 0 +ATT, -9.37, -0.34, -3.34, 0.00, 0.00, 126.12, 124.65 +CTUN, 531, 0.57, -0.25, 0.000000, 0, 0, -49, 530, 0 +GPS, 3, 308961600, 10, 1.49, 24.2398219, 54.5792745, -0.19, 11.27, 0.18, 296.55 +ATT, -9.37, -1.19, -3.34, -0.64, 0.00, 126.24, 124.65 +CTUN, 531, 0.49, -0.35, 0.000000, 0, 0, -53, 531, 0 +DU32, 7, 426237 +CURR, 531, 284575, 1185, 0, 4752, 0.000000 +ATT, -7.63, -1.86, -3.69, -0.36, 0.00, 126.19, 124.65 +CTUN, 525, 0.49, -0.35, 0.000000, 0, 0, -56, 528, 0 +GPS, 3, 308961800, 10, 1.49, 24.2398220, 54.5792744, -0.32, 11.16, 0.10, 296.55 +ATT, -3.00, -2.34, -4.61, 0.00, 0.00, 125.98, 124.65 +CTUN, 512, 0.40, -0.56, 0.000000, 0, 0, -62, 517, 0 +ATT, 0.00, -0.71, -5.07, 0.22, 0.00, 126.02, 124.65 +CTUN, 511, 0.40, -0.47, 0.000000, 0, 0, -67, 511, 0 +GPS, 3, 308962000, 10, 1.49, 24.2398220, 54.5792744, -0.43, 11.06, 0.04, 296.55 +ATT, 0.00, 1.62, -6.11, 0.84, 0.00, 126.63, 124.65 +CTUN, 517, 0.27, -0.53, 0.000000, 0, 0, -78, 517, 0 +ATT, 0.00, 2.65, -6.92, 1.23, 0.00, 128.28, 124.65 +CTUN, 511, 0.27, -0.50, 0.000000, 0, 0, -78, 511, 0 +GPS, 3, 308962200, 10, 1.49, 24.2398221, 54.5792744, -0.61, 10.90, 0.05, 296.55 +ATT, 0.00, 3.65, -5.76, 1.02, 0.00, 130.21, 124.65 +CTUN, 494, 0.16, -0.74, 0.000000, 0, 0, -79, 494, 0 +ATT, 0.00, 4.20, -4.61, 1.05, 0.00, 131.39, 124.65 +CTUN, 471, 0.25, -0.67, 0.000000, 0, 0, 1, 474, 0 +GPS, 3, 308962400, 10, 1.49, 24.2398223, 54.5792746, -0.71, 10.68, 0.09, 296.55 +ATT, -0.11, 1.56, -4.03, -1.39, 0.00, 132.59, 124.65 +CTUN, 422, 0.19, -0.76, 0.000000, 0, 0, -4, 422, 0 +ATT, 0.00, 1.84, -3.23, -1.07, 0.00, 134.82, 124.82 +CTUN, 402, 0.19, -0.74, 0.000000, 0, 0, -8, 403, 0 +GPS, 3, 308962600, 10, 1.49, 24.2398223, 54.5792746, -0.72, 10.63, 0.13, 296.55 +ATT, -0.11, -1.97, -2.53, 0.18, 0.00, 137.03, 127.03 +CTUN, 369, 0.19, -0.55, 0.000000, 0, 0, 5, 369, 0 +DU32, 7, 426237 +CURR, 366, 289373, 1188, 0, 4752, 0.000000 +ATT, 0.00, -2.11, -0.80, 0.12, 0.00, 138.98, 128.98 +CTUN, 351, 0.20, -0.65, 0.000000, 0, 0, 6, 356, 0 +GPS, 3, 308962800, 10, 1.49, 24.2398225, 54.5792748, -0.71, 10.61, 0.13, 296.55 +ATT, 0.00, -2.89, 0.00, 0.31, 0.00, 139.90, 129.90 +CTUN, 346, 0.19, -0.71, 0.000000, 0, 0, 3, 346, 0 +ATT, 0.00, -2.98, 0.00, 0.50, 0.00, 141.06, 131.06 +CTUN, 314, 0.20, -0.75, 0.000000, 0, 0, -2, 314, 0 +GPS, 3, 308963000, 10, 1.49, 24.2398225, 54.5792749, -0.71, 10.59, 0.05, 296.55 +ATT, 0.00, -3.04, 0.00, 0.53, 0.00, 141.31, 131.31 +CTUN, 280, 0.19, -0.74, 0.000000, 0, 0, 1, 296, 0 +ATT, 0.00, -3.00, 0.00, 0.47, 0.00, 141.53, 131.53 +CTUN, 268, 0.20, -0.40, 0.000000, 0, 0, 1, 271, 0 +GPS, 3, 308963200, 10, 1.49, 24.2398224, 54.5792749, -0.71, 10.59, 0.01, 296.55 +ATT, 0.00, -3.07, 0.00, 0.49, 0.00, 141.98, 131.98 +CTUN, 267, 0.20, -0.39, 0.000000, 0, 0, 4, 268, 0 +ATT, 0.00, -3.02, 0.00, 0.46, 0.00, 142.20, 132.20 +CTUN, 268, 0.20, -0.20, 0.000000, 0, 0, -3, 268, 0 +GPS, 3, 308963400, 10, 1.49, 24.2398224, 54.5792750, -0.67, 10.58, 0.03, 296.55 +ATT, 0.00, -2.99, 0.00, 0.48, 0.00, 142.48, 132.48 +CTUN, 268, 0.19, -0.28, 0.000000, 0, 0, 1, 268, 0 +ATT, 0.00, -2.90, 0.00, 0.46, 0.00, 142.79, 132.79 +CTUN, 268, 0.19, -0.43, 0.000000, 0, 0, 2, 268, 0 +GPS, 3, 308963600, 10, 1.49, 24.2398224, 54.5792750, -0.62, 10.58, 0.00, 296.55 +ATT, 0.00, -2.90, 0.00, 0.46, 0.00, 142.91, 132.91 +CTUN, 267, 0.19, -0.50, 0.000000, 0, 0, 7, 268, 0 +DU32, 7, 426237 +CURR, 268, 292328, 1173, 0, 4712, 0.000000 +ATT, 0.00, -2.85, 0.00, 0.45, 0.00, 143.09, 133.12 +CTUN, 268, 0.19, -0.48, 0.000000, 0, 0, 1, 268, 0 +GPS, 3, 308963800, 10, 1.49, 24.2398223, 54.5792750, -0.59, 10.58, 0.01, 296.55 +ATT, 0.00, -2.84, 0.00, 0.54, 0.00, 143.33, 133.33 +CTUN, 268, 0.19, -0.49, 0.000000, 0, 0, 0, 268, 0 +ATT, 0.00, -2.76, 0.00, 0.50, 0.00, 143.58, 133.58 +CTUN, 268, 0.21, -0.48, 0.000000, 0, 0, 1, 268, 0 +GPS, 3, 308964000, 10, 1.49, 24.2398223, 54.5792750, -0.57, 10.58, 0.01, 296.55 +ATT, 0.00, -2.75, 0.00, 0.47, 0.00, 143.65, 133.65 +CTUN, 268, 0.20, -0.51, 0.000000, 0, 0, 7, 268, 0 +ATT, 0.00, -2.72, 0.00, 0.45, 0.00, 143.74, 133.76 +CTUN, 268, 0.20, -0.60, 0.000000, 0, 0, 7, 268, 0 +GPS, 3, 308964200, 10, 1.49, 24.2398223, 54.5792750, -0.54, 10.58, 0.01, 296.55 +ATT, 0.00, -2.70, 0.00, 0.42, 0.00, 143.71, 133.76 +CTUN, 212, 0.20, -0.67, 0.000000, 0, 0, 4, 211, 0 +ATT, 0.00, -2.73, 0.00, 0.41, 0.00, 143.82, 133.82 +CTUN, 211, 0.20, -0.33, 0.000000, 0, 0, 6, 211, 0 +GPS, 3, 308964400, 10, 1.49, 24.2398223, 54.5792750, -0.54, 10.57, 0.00, 296.55 +ATT, 0.00, -2.78, 0.00, 0.39, 0.00, 143.80, 133.82 +CTUN, 212, 0.20, -0.42, 0.000000, 0, 0, 9, 212, 0 +ATT, 0.00, -2.72, 0.00, 0.40, 0.00, 143.93, 133.94 +CTUN, 210, 0.20, -0.41, 0.000000, 0, 0, 13, 210, 0 +GPS, 3, 308964600, 10, 1.49, 24.2398223, 54.5792750, -0.50, 10.57, 0.01, 296.55 +ATT, 0.00, -2.64, 0.00, 0.35, 0.00, 143.76, 133.94 +CTUN, 210, 0.17, -0.31, 0.000000, 0, 0, 11, 210, 0 +DU32, 7, 426237 +CURR, 210, 294722, 1188, 0, 4772, 0.000000 +ATT, 0.00, -2.74, 0.00, 0.39, 0.00, 143.82, 133.94 +CTUN, 210, 0.19, -0.30, 0.000000, 0, 0, 13, 210, 0 +GPS, 3, 308964800, 10, 1.49, 24.2398223, 54.5792750, -0.47, 10.57, 0.01, 296.55 +ATT, 0.00, -2.78, 0.00, 0.39, 0.00, 143.76, 133.94 +CTUN, 210, 0.19, -0.24, 0.000000, 0, 0, 14, 210, 0 +ATT, 0.00, -2.77, 0.00, 0.42, 0.00, 143.77, 133.94 +CTUN, 210, 0.19, -0.35, 0.000000, 0, 0, 16, 210, 0 +GPS, 3, 308965000, 10, 1.49, 24.2398223, 54.5792750, -0.42, 10.56, 0.02, 296.55 +ATT, 0.00, -2.79, 0.00, 0.38, 0.00, 143.67, 133.94 +CTUN, 210, 0.19, -0.27, 0.000000, 0, 0, 16, 210, 0 +ATT, 0.00, -2.80, 0.00, 0.49, 0.00, 144.15, 134.15 +CTUN, 210, 0.19, -0.27, 0.000000, 0, 0, 19, 210, 0 +GPS, 3, 308965200, 10, 1.49, 24.2398223, 54.5792750, -0.37, 10.56, 0.01, 296.55 +ATT, 0.00, -2.66, 0.00, 0.51, 0.00, 144.82, 134.82 +CTUN, 210, 0.17, -0.41, 0.000000, 0, 0, 13, 210, 0 +ATT, 0.00, -2.62, 0.00, 0.42, 0.00, 145.27, 135.27 +CTUN, 210, 0.19, -0.45, 0.000000, 0, 0, 10, 210, 0 +GPS, 3, 308965400, 10, 1.49, 24.2398222, 54.5792750, -0.34, 10.57, 0.00, 296.55 +ATT, 0.00, -2.81, 0.00, 0.40, 0.00, 145.39, 135.39 +CTUN, 210, 0.19, -0.14, 0.000000, 0, 0, 13, 210, 0 +ATT, 0.00, -2.80, 0.00, 0.53, 0.00, 145.68, 135.68 +CTUN, 210, 0.24, -0.40, 0.000000, 0, 0, 14, 210, 0 +GPS, 3, 308965600, 10, 1.49, 24.2398222, 54.5792750, -0.32, 10.57, 0.01, 296.55 +ATT, 0.00, -2.64, 0.00, 0.42, 0.00, 145.77, 135.77 +CTUN, 210, 0.24, -0.19, 0.000000, 0, 0, 14, 210, 0 +ATT, 0.00, -2.77, 0.00, 0.46, 0.00, 145.75, 135.78 +DU32, 7, 426237 +CURR, 210, 296820, 1205, 0, 4793, 0.000000 +CTUN, 210, 0.24, -0.37, 0.000000, 0, 0, 15, 210, 0 +GPS, 3, 308965800, 10, 1.49, 24.2398222, 54.5792750, -0.28, 10.57, 0.01, 296.55 +ATT, 0.00, -2.79, 0.00, 0.42, 0.00, 145.76, 135.78 +CTUN, 0, 0.24, -0.20, 0.000000, 0, 0, 20, 0, 0 +ATT, 0.00, -2.59, 0.00, 0.44, 0.00, 145.97, 145.97 +CTUN, 0, 0.24, 0.06, 0.000000, 0, 0, 18, 0, 0 +GPS, 3, 308966000, 10, 1.49, 24.2398222, 54.5792750, -0.25, 10.57, 0.02, 296.55 +ATT, 0.00, -2.86, 0.00, 0.44, 0.00, 146.23, 146.23 +CTUN, 0, 0.24, -0.06, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -3.13, 0.00, 0.52, 0.00, 146.26, 146.26 +CTUN, 0, 0.25, -0.13, 0.000000, 0, 0, 15, 0, 0 +GPS, 3, 308966200, 10, 1.49, 24.2398221, 54.5792750, -0.18, 10.58, 0.02, 296.55 +ATT, 0.00, -2.94, 0.00, 0.53, 0.00, 146.44, 146.44 +CTUN, 0, 0.25, -0.07, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -2.88, 0.00, 0.49, 0.00, 146.87, 146.87 +CTUN, 0, 0.25, -0.12, 0.000000, 0, 0, 15, 0, 0 +GPS, 3, 308966400, 10, 1.49, 24.2398221, 54.5792750, -0.14, 10.59, 0.01, 296.55 +ATT, 0.00, -2.85, 0.00, 0.47, 0.00, 147.51, 147.51 +CTUN, 0, 0.20, 0.02, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -2.62, 0.00, 0.47, 0.00, 148.18, 148.18 +CTUN, 0, 0.24, 0.03, 0.000000, 0, 0, 17, 0, 0 +GPS, 3, 308966600, 10, 1.49, 24.2398222, 54.5792750, -0.10, 10.58, 0.02, 296.55 +ATT, 0.00, -2.50, 0.00, 0.43, 0.00, 148.83, 148.83 +CTUN, 0, 0.20, -0.02, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -2.70, 0.00, 0.48, 0.00, 149.44, 149.44 +DU32, 7, 426173 +CURR, 0, 297030, 1210, 0, 4772, 0.000000 +CTUN, 0, 0.24, 0.01, 0.000000, 0, 0, 16, 0, 0 +GPS, 3, 308966800, 10, 1.49, 24.2398222, 54.5792750, -0.05, 10.59, 0.01, 296.55 +ATT, 0.00, -2.82, 0.00, 0.42, 0.00, 150.17, 150.17 +CTUN, 0, 0.24, 0.01, 0.000000, 0, 0, 16, 0, 0 +ATT, 0.00, -2.44, 0.00, 0.48, 0.00, 150.97, 150.97 +CTUN, 0, 0.29, -0.01, 0.000000, 0, 0, 19, 0, 0 +GPS, 3, 308967000, 10, 1.49, 24.2398221, 54.5792751, -0.01, 10.60, 0.01, 296.55 +ATT, 0.00, -2.67, 0.00, 0.47, 0.00, 151.69, 151.69 +CTUN, 0, 0.27, -0.05, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -2.36, 0.00, 0.40, 0.00, 152.16, 152.16 +CTUN, 0, 0.29, -0.08, 0.000000, 0, 0, 19, 0, 0 +GPS, 3, 308967200, 10, 1.49, 24.2398221, 54.5792751, 0.02, 10.59, 0.03, 296.55 +ATT, 0.00, -2.64, 0.00, 0.47, 0.00, 152.68, 152.68 +CTUN, 0, 0.27, -0.02, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -2.15, 0.00, 0.48, 0.00, 152.97, 152.97 +CTUN, 0, 0.27, -0.04, 0.000000, 0, 0, 17, 0, 0 +GPS, 3, 308967400, 10, 1.49, 24.2398221, 54.5792752, 0.04, 10.60, 0.03, 296.55 +ATT, 0.00, -2.41, 0.00, 0.51, 0.00, 153.10, 153.10 +CTUN, 0, 0.25, 0.01, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -2.46, 0.00, 0.51, 0.00, 153.46, 153.46 +CTUN, 0, 0.25, -0.10, 0.000000, 0, 0, 17, 0, 0 +GPS, 3, 308967600, 10, 1.49, 24.2398221, 54.5792752, 0.07, 10.59, 0.00, 296.55 +ATT, 0.00, -2.19, 0.00, 0.45, 0.00, 153.61, 153.61 +CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -2.19, 0.00, 0.44, -1.11, 153.74, 153.74 +DU32, 7, 426173 +CURR, 0, 297030, 1207, 0, 4772, 0.000000 +CTUN, 0, 0.22, -0.02, 0.000000, 0, 0, 16, 0, 0 +GPS, 3, 308967800, 10, 1.49, 24.2398222, 54.5792752, 0.08, 10.59, 0.01, 296.55 +ATT, 0.00, -2.41, 0.00, 0.46, -17.26, 153.63, 153.63 +CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -2.50, 0.00, 0.43, -34.41, 153.33, 153.33 +CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 15, 0, 0 +GPS, 3, 308968000, 10, 1.49, 24.2398221, 54.5792752, 0.09, 10.59, 0.05, 296.55 +ATT, 0.00, -2.37, 0.00, 0.41, -45.00, 152.88, 152.88 +CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -2.33, 0.00, 0.34, -42.77, 152.10, 152.10 +CTUN, 0, 0.22, -0.03, 0.000000, 0, 0, 13, 0, 0 +GPS, 3, 308968200, 10, 1.49, 24.2398222, 54.5792752, 0.10, 10.58, 0.00, 296.55 +ATT, 0.00, -2.29, 0.00, 0.27, -38.65, 151.24, 151.24 +CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -2.23, 0.00, 0.33, -45.11, 150.89, 150.89 +CTUN, 0, 0.22, -0.08, 0.000000, 0, 0, 12, 0, 0 +GPS, 3, 308968400, 10, 1.49, 24.2398221, 54.5792752, 0.11, 10.58, 0.03, 296.55 +ATT, 0.00, -2.27, 0.00, 0.32, -45.11, 150.32, 150.32 +CTUN, 0, 0.22, -0.17, 0.000000, 0, 0, 12, 0, 0 +PM, 0, 0, 50, 0, 1000, 10500, 9, 0 +ATT, 0.00, -2.31, 0.00, 0.32, -45.11, 149.78, 149.78 +CTUN, 0, 0.27, 0.03, 0.000000, 0, 0, 11, 0, 0 +GPS, 3, 308968600, 10, 1.49, 24.2398222, 54.5792751, 0.10, 10.59, 0.01, 296.55 +ATT, 0.00, -2.27, 0.00, 0.39, -45.00, 149.58, 149.58 +CTUN, 0, 0.26, -0.02, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -2.19, 0.00, 0.31, -45.11, 149.34, 149.34 +DU32, 7, 426173 +CURR, 0, 297030, 1212, 0, 4752, 0.000000 +CTUN, 0, 0.27, -0.07, 0.000000, 0, 0, 8, 0, 0 +GPS, 3, 308968800, 10, 1.49, 24.2398222, 54.5792751, 0.11, 10.59, 0.01, 296.55 +ATT, 0.00, -2.02, 0.00, 0.29, -45.11, 149.29, 149.29 +CTUN, 0, 0.27, -0.06, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -1.97, 0.00, 0.25, -45.00, 149.19, 149.19 +CTUN, 0, 0.27, -0.14, 0.000000, 0, 0, 8, 0, 0 +GPS, 3, 308969000, 10, 1.49, 24.2398222, 54.5792751, 0.11, 10.58, 0.01, 296.55 +ATT, 0.00, -2.21, 0.00, 0.29, -45.11, 149.13, 149.13 +CTUN, 0, 0.27, -0.05, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -2.24, 0.00, 0.31, -45.00, 149.02, 149.02 +CTUN, 0, 0.27, -0.03, 0.000000, 0, 0, 6, 0, 0 +GPS, 3, 308969200, 10, 1.49, 24.2398221, 54.5792751, 0.10, 10.59, 0.05, 296.55 +ATT, 0.00, -2.01, 0.00, 0.22, -45.00, 148.96, 148.96 +CTUN, 0, 0.27, -0.07, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, -1.98, 0.00, 0.18, -45.11, 149.00, 149.00 +CTUN, 0, 0.27, -0.18, 0.000000, 0, 0, 6, 0, 0 +GPS, 3, 308969400, 10, 1.49, 24.2398221, 54.5792751, 0.09, 10.61, 0.02, 296.55 +ATT, 0.00, -2.25, 0.00, 0.24, -45.11, 148.94, 148.94 +CTUN, 0, 0.27, -0.02, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, -1.89, 0.00, 0.18, -45.00, 148.92, 148.92 +CTUN, 0, 0.27, -0.07, 0.000000, 0, 0, 4, 0, 0 +GPS, 3, 308969600, 10, 1.49, 24.2398221, 54.5792751, 0.08, 10.60, 0.01, 296.55 +ATT, 0.00, -2.09, 0.00, 0.18, -45.11, 148.95, 148.95 +CTUN, 0, 0.27, -0.06, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, -1.97, 0.00, 0.25, -45.00, 148.88, 148.88 +DU32, 7, 426173 +CURR, 0, 297030, 1214, 0, 4772, 0.000000 +CTUN, 0, 0.29, 0.04, 0.000000, 0, 0, 2, 0, 0 +GPS, 3, 308969800, 10, 1.49, 24.2398220, 54.5792751, 0.07, 10.58, 0.07, 296.55 +ATT, 0.00, -1.81, 0.00, 0.16, -45.00, 148.87, 148.87 +CTUN, 0, 0.27, -0.01, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, -1.90, 0.00, 0.21, -32.30, 148.87, 148.87 +CTUN, 0, 0.29, 0.01, 0.000000, 0, 0, 2, 0, 0 +GPS, 3, 308970000, 10, 1.49, 24.2398220, 54.5792752, 0.07, 10.58, 0.01, 296.55 +ATT, 0.00, -1.82, 0.00, 0.12, -0.77, 148.81, 148.81 +CTUN, 0, 0.29, -0.04, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, -1.92, 0.00, 0.21, 0.00, 148.88, 148.88 +CTUN, 0, 0.29, -0.14, 0.000000, 0, 0, 1, 0, 0 +GPS, 3, 308970200, 10, 1.49, 24.2398220, 54.5792752, 0.06, 10.56, 0.01, 296.55 +ATT, 0.00, -1.92, 0.00, 0.15, 0.00, 148.82, 148.82 +CTUN, 0, 0.25, 0.03, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, -1.87, 0.00, 0.19, 0.00, 148.83, 148.83 +CTUN, 0, 0.25, -0.07, 0.000000, 0, 0, 1, 0, 0 +GPS, 3, 308970400, 10, 1.49, 24.2398220, 54.5792752, 0.05, 10.56, 0.03, 296.55 +ATT, 0.00, -1.96, 0.00, 0.17, 0.00, 148.81, 148.81 +CTUN, 0, 0.24, 0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, -1.82, 0.00, 0.13, 0.00, 148.76, 148.76 +CTUN, 0, 0.24, -0.06, 0.000000, 0, 0, 0, 0, 0 +GPS, 3, 308970600, 10, 1.49, 24.2398220, 54.5792752, 0.04, 10.55, 0.02, 296.55 +ATT, 0.00, -1.89, 0.00, 0.20, 0.00, 148.80, 148.80 +CTUN, 0, 0.24, 0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, -1.91, 0.00, 0.12, 0.00, 148.73, 148.73 +DU32, 7, 426173 +CURR, 0, 297030, 1219, 0, 4772, 0.000000 +CTUN, 0, 0.24, -0.01, 0.000000, 0, 0, -1, 0, 0 +GPS, 3, 308970800, 10, 1.49, 24.2398220, 54.5792752, 0.04, 10.55, 0.00, 296.55 +ATT, 0.00, -1.79, 0.00, 0.12, 0.00, 148.71, 148.71 +CTUN, 0, 0.22, 0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, -1.86, 0.00, 0.17, 0.00, 148.74, 148.74 +CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, 0, 0, 0 +GPS, 3, 308971000, 10, 1.49, 24.2398220, 54.5792752, 0.03, 10.55, 0.01, 296.55 +ATT, 0.00, -1.92, 0.00, 0.13, 0.00, 148.71, 148.71 +CTUN, 0, 0.22, 0.06, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, -1.83, 0.00, 0.11, 0.00, 148.67, 148.67 +CTUN, 0, 0.22, 0.00, 0.000000, 0, 0, -1, 0, 0 +GPS, 3, 308971200, 10, 1.49, 24.2398220, 54.5792752, 0.03, 10.54, 0.00, 296.55 +ATT, 0.00, -1.80, 0.00, 0.13, 0.00, 148.67, 148.67 +CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, -1.84, 0.00, 0.14, 0.00, 148.68, 148.68 +CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, -2, 0, 0 +GPS, 3, 308971400, 10, 1.49, 24.2398220, 54.5792752, 0.02, 10.55, 0.02, 296.55 +ATT, 0.00, -1.84, 0.00, 0.11, 0.00, 148.63, 148.63 +CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, -1.76, 0.00, 0.10, 0.00, 148.62, 148.62 +CTUN, 0, 0.22, 0.04, 0.000000, 0, 0, -3, 0, 0 +GPS, 3, 308971600, 10, 1.49, 24.2398220, 54.5792752, 0.00, 10.54, 0.02, 296.55 +ATT, 0.00, -1.70, 0.00, 0.11, 0.00, 148.60, 148.60 +CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, -1.83, 0.00, 0.09, 0.00, 148.59, 148.59 +DU32, 7, 426173 +CURR, 0, 297030, 1215, 0, 4752, 0.000000 +CTUN, 0, 0.22, -0.06, 0.000000, 0, 0, -4, 0, 0 +GPS, 3, 308971800, 10, 1.49, 24.2398221, 54.5792753, 0.00, 10.52, 0.06, 296.55 +ATT, 0.00, -1.79, 0.00, 0.13, 0.00, 148.60, 148.60 +CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, -1.82, 0.00, 0.18, 0.00, 148.58, 148.58 +CTUN, 0, 0.22, 0.04, 0.000000, 0, 0, -5, 0, 0 +GPS, 3, 308972000, 10, 1.49, 24.2398220, 54.5792753, -0.02, 10.53, 0.02, 296.55 +ATT, 0.00, -1.87, 0.00, 0.11, 0.00, 148.55, 148.55 +CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, -5, 0, 0 +ATT, 0.00, -1.83, 0.00, 0.11, 0.00, 148.54, 148.54 +CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -6, 0, 0 +GPS, 3, 308972200, 10, 1.49, 24.2398220, 54.5792753, -0.02, 10.53, 0.03, 296.55 +ATT, 0.00, -1.74, 0.00, 0.06, 0.00, 148.50, 148.50 +CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -6, 0, 0 +ATT, 0.00, -1.68, 0.00, 0.12, 0.00, 148.52, 148.52 +CTUN, 0, 0.22, -0.20, 0.000000, 0, 0, -6, 0, 0 +GPS, 3, 308972400, 10, 1.49, 24.2398220, 54.5792753, -0.05, 10.54, 0.00, 296.55 +ATT, 0.00, -1.67, 0.00, 0.30, 0.00, 148.44, 148.44 +CTUN, 0, 0.22, 0.03, 0.000000, 0, 0, -7, 0, 0 +ATT, 0.00, -1.74, 0.00, 0.05, 0.00, 148.48, 148.48 +CTUN, 0, 0.22, -0.03, 0.000000, 0, 0, -8, 0, 0 +GPS, 3, 308972600, 10, 1.49, 24.2398220, 54.5792753, -0.07, 10.54, 0.02, 296.55 +ATT, 0.00, -1.51, 0.00, 0.00, 0.00, 148.51, 148.51 +CTUN, 0, 0.22, -0.08, 0.000000, 0, 0, -8, 0, 0 +ATT, 0.00, -1.43, 0.00, 0.01, 0.00, 148.49, 148.49 +DU32, 7, 426173 +CURR, 0, 297030, 1212, 0, 4752, 0.000000 +GPS, 3, 308972800, 10, 1.49, 24.2398220, 54.5792753, -0.08, 10.53, 0.02, 296.55 +CTUN, 0, 0.22, -0.07, 0.000000, 0, 0, -9, 0, 0 +ATT, 0.00, -1.50, 0.00, 0.00, 0.00, 148.47, 148.47 +CTUN, 0, 0.22, -0.09, 0.000000, 0, 0, -9, 0, 0 +ATT, 0.00, -1.45, 0.00, -0.02, 0.00, 148.44, 148.44 +GPS, 3, 308973000, 10, 1.49, 24.2398220, 54.5792753, -0.10, 10.54, 0.03, 296.55 +CTUN, 0, 0.22, -0.08, 0.000000, 0, 0, -9, 0, 0 +ATT, 0.00, -1.52, 0.00, 0.03, 0.00, 148.43, 148.43 +CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, -9, 0, 0 +ATT, 0.00, -1.34, 0.00, -0.07, 0.00, 148.36, 148.36 +GPS, 3, 308973200, 10, 1.49, 24.2398221, 54.5792753, -0.11, 10.51, 0.04, 296.55 +CTUN, 0, 0.22, -0.16, 0.000000, 0, 0, -9, 0, 0 +ATT, 0.00, -1.24, 0.00, 0.27, 0.00, 148.40, 148.40 +CTUN, 0, 0.22, 0.00, 0.000000, 0, 0, -10, 0, 0 +ATT, 0.00, -1.53, 0.00, 0.21, 0.00, 148.19, 148.19 +GPS, 3, 308973400, 10, 1.49, 24.2398221, 54.5792753, -0.13, 10.53, 0.02, 296.55 +CTUN, 0, 0.22, -0.16, 0.000000, 0, 0, -10, 0, 0 +ATT, 0.00, -1.33, 0.00, -0.08, 0.00, 148.27, 148.27 +CTUN, 0, 0.21, -0.09, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, -1.31, 0.00, 0.19, 0.00, 148.30, 148.30 +GPS, 3, 308973600, 10, 1.49, 24.2398221, 54.5792754, -0.15, 10.53, 0.02, 296.55 +CTUN, 0, 0.21, -0.12, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, -1.28, 0.00, 0.25, 0.00, 148.25, 148.25 +CTUN, 0, 0.15, -0.17, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, -1.36, 0.00, 0.29, 0.00, 148.22, 148.22 +DU32, 7, 426173 +CURR, 0, 297030, 1214, 0, 4752, 0.000000 +GPS, 3, 308973800, 10, 1.49, 24.2398221, 54.5792753, -0.17, 10.53, 0.03, 296.55 +CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, -1.55, 0.00, 0.18, 0.00, 148.13, 148.13 +CTUN, 0, 0.15, -0.14, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, -1.24, 0.00, -0.04, 0.00, 148.18, 148.18 +GPS, 3, 308974000, 10, 1.49, 24.2398221, 54.5792753, -0.19, 10.52, 0.01, 296.55 +CTUN, 0, 0.15, -0.18, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, -1.26, 0.00, 0.17, 0.00, 148.19, 148.19 +CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, -1.46, 0.00, 0.39, 0.00, 148.10, 148.10 +CTUN, 0, 0.15, -0.10, 0.000000, 0, 0, -13, 0, 0 +GPS, 3, 308974200, 10, 1.49, 24.2398222, 54.5792753, -0.22, 10.52, 0.03, 296.55 +ATT, 0.00, -1.40, 0.00, 0.02, 0.00, 148.10, 148.10 +CTUN, 0, 0.15, -0.07, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -1.30, 0.00, 0.04, 0.00, 148.15, 148.15 +GPS, 3, 308974400, 10, 1.49, 24.2398222, 54.5792754, -0.23, 10.53, 0.02, 296.55 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, -1.27, 0.00, 0.42, 0.00, 148.05, 148.05 +CTUN, 0, 0.15, -0.04, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -1.33, 0.00, 0.22, 0.00, 148.01, 148.01 +GPS, 3, 308974600, 10, 1.49, 24.2398222, 54.5792754, -0.24, 10.54, 0.02, 296.55 +CTUN, 0, 0.15, -0.01, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -1.24, 0.00, 0.15, 0.00, 148.03, 148.03 +CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -1.17, 0.00, 0.35, 0.00, 148.01, 148.01 +DU32, 7, 426173 +CURR, 0, 297030, 1216, 0, 4752, 0.000000 +GPS, 3, 308974800, 10, 1.49, 24.2398221, 54.5792754, -0.24, 10.55, 0.04, 296.55 +CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, -1.27, 0.00, 0.14, 0.00, 147.97, 147.97 +CTUN, 0, 0.15, -0.14, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -1.14, 0.00, 0.00, 0.00, 148.03, 148.03 +GPS, 3, 308975000, 10, 1.49, 24.2398222, 54.5792754, -0.26, 10.56, 0.04, 296.55 +CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -1.07, 0.00, 0.38, 0.00, 147.95, 147.95 +CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, -1.16, 0.00, 0.42, 0.00, 147.92, 147.92 +GPS, 3, 308975200, 10, 1.49, 24.2398221, 54.5792754, -0.27, 10.58, 0.05, 296.55 +CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, -1.24, 0.00, 0.06, 0.00, 147.90, 147.90 +CTUN, 0, 0.15, -0.19, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, -1.07, 0.00, 0.00, 0.00, 147.95, 147.95 +GPS, 3, 308975400, 10, 1.49, 24.2398224, 54.5792753, -0.29, 10.52, 0.02, 296.55 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, -1.08, 0.00, 0.19, 0.00, 147.94, 147.94 +CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, -1.07, 0.00, 0.43, 0.00, 147.85, 147.85 +GPS, 3, 308975600, 10, 1.49, 24.2398223, 54.5792753, -0.30, 10.54, 0.06, 296.55 +CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, -1.18, 0.00, 0.27, 0.00, 147.82, 147.82 +CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, -1.08, 0.00, 0.05, 0.00, 147.83, 147.83 +DU32, 7, 426173 +CURR, 0, 297030, 1217, 0, 4752, 0.000000 +GPS, 3, 308975800, 10, 1.49, 24.2398226, 54.5792754, -0.31, 10.50, 0.07, 296.55 +CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, -1.01, 0.00, -0.02, 0.00, 147.85, 147.85 +CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, -1.00, 0.00, 0.09, 0.00, 147.90, 147.90 +GPS, 3, 308976000, 10, 1.49, 24.2398224, 54.5792754, -0.32, 10.53, 0.10, 296.55 +CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, -0.86, 0.00, 0.41, 0.00, 147.82, 147.82 +CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, -0.89, 0.00, 0.40, 0.00, 147.78, 147.78 +GPS, 3, 308976200, 10, 1.49, 24.2398225, 54.5792755, -0.33, 10.52, 0.04, 296.55 +CTUN, 0, 0.15, -0.15, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.97, 0.00, 0.21, 0.00, 147.73, 147.73 +CTUN, 0, 0.15, -0.06, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.99, 0.00, 0.00, 0.00, 147.76, 147.76 +GPS, 3, 308976400, 10, 1.49, 24.2398226, 54.5792756, -0.34, 10.51, 0.05, 296.55 +CTUN, 0, 0.15, -0.05, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.99, 0.00, -0.03, 0.00, 147.74, 147.74 +CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.19, 0.00, 0.00, 0.00, 147.76, 147.76 +GPS, 3, 308976600, 10, 1.49, 24.2398225, 54.5792755, -0.34, 10.49, 0.05, 296.55 +CTUN, 0, 0.15, -0.20, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.26, 0.00, -0.02, 0.00, 147.74, 147.74 +CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.23, 0.00, -0.02, 0.00, 147.72, 147.72 +DU32, 7, 426173 +CURR, 0, 297030, 1213, 0, 4772, 0.000000 +GPS, 3, 308976800, 10, 1.49, 24.2398229, 54.5792756, -0.35, 10.44, 0.14, 296.55 +CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.23, 0.00, -0.01, 0.00, 147.71, 147.71 +CTUN, 0, 0.15, -0.20, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.25, 0.00, 0.01, 0.00, 147.69, 147.69 +GPS, 3, 308977000, 10, 1.49, 24.2398230, 54.5792756, -0.36, 10.42, 0.03, 296.55 +CTUN, 0, 0.15, -0.11, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.27, 0.00, 0.02, 0.00, 147.67, 147.67 +CTUN, 0, 0.15, 0.02, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.16, 0.00, -0.01, 0.00, 147.64, 147.64 +GPS, 3, 308977200, 10, 1.49, 24.2398230, 54.5792757, -0.36, 10.42, 0.02, 296.55 +CTUN, 0, 0.15, -0.05, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.12, 0.00, -0.05, 0.00, 147.61, 147.61 +CTUN, 0, 0.15, -0.10, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.09, 0.00, -0.06, 0.00, 147.59, 147.59 +GPS, 3, 308977400, 10, 1.49, 24.2398231, 54.5792757, -0.36, 10.39, 0.03, 296.55 +CTUN, 0, 0.15, -0.05, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.03, 0.00, -0.05, 0.00, 147.57, 147.57 +CTUN, 0, 0.15, -0.01, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.02, 0.00, -0.03, 0.00, 147.57, 147.57 +GPS, 3, 308977600, 10, 1.49, 24.2398230, 54.5792757, -0.36, 10.39, 0.05, 296.55 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.96, 0.00, 0.04, 0.00, 147.59, 147.59 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.97, 0.00, 0.01, 0.00, 147.55, 147.55 +DU32, 7, 426173 +CURR, 0, 297030, 1213, 0, 4772, 0.000000 +GPS, 3, 308977800, 10, 1.49, 24.2398234, 54.5792759, -0.36, 10.33, 0.13, 296.55 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.97, 0.00, 0.09, 0.00, 147.55, 147.55 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.07, 0.00, 0.17, 0.00, 147.49, 147.49 +GPS, 3, 308978000, 10, 1.49, 24.2398233, 54.5792759, -0.36, 10.31, 0.07, 296.55 +CTUN, 0, 0.15, 0.00, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.07, 0.00, 0.18, 0.00, 147.47, 147.47 +CTUN, 0, 0.15, -0.13, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.07, 0.00, 0.03, 0.00, 147.42, 147.42 +GPS, 3, 308978200, 10, 1.49, 24.2398234, 54.5792759, -0.36, 10.32, 0.04, 296.55 +CTUN, 0, 0.15, -0.09, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.03, 0.00, -0.04, 0.00, 147.43, 147.43 +CTUN, 0, 0.15, -0.16, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.12, 0.00, -0.04, 0.00, 147.42, 147.42 +GPS, 3, 308978400, 10, 1.49, 24.2398234, 54.5792759, -0.36, 10.32, 0.03, 296.55 +CTUN, 0, 0.15, -0.08, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.17, 0.00, -0.01, 0.00, 147.41, 147.41 +PM, 0, 0, 50, 0, 1000, 10500, 9, 0 +CTUN, 0, 0.15, -0.15, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -1.06, 0.00, -0.18, 0.00, 147.40, 147.40 +GPS, 3, 308978600, 10, 1.49, 24.2398236, 54.5792760, -0.37, 10.29, 0.07, 296.55 +CTUN, 0, 0.15, -0.19, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.61, 0.00, -0.23, 0.00, 147.34, 147.34 +CTUN, 0, 0.15, -0.12, 0.000000, 0, 0, 23, 0, 0 +ATT, 0.00, -1.00, 0.00, 0.01, 0.00, 145.29, 145.29 +DU32, 7, 426173 +CURR, 0, 297030, 1214, 0, 4793, 0.000000 +GPS, 3, 308978800, 10, 1.49, 24.2398236, 54.5792761, -0.30, 10.28, 0.04, 296.55 +CTUN, 0, 0.16, 0.01, 0.000000, 0, 0, 47, 0, 0 +ATT, 0.00, -1.95, 0.00, -0.04, 0.00, 142.63, 142.63 +CTUN, 0, 0.15, 0.01, 0.000000, 0, 0, 70, 0, 0 +ATT, 0.00, -1.15, 0.00, -1.26, 0.00, 139.35, 139.35 +GPS, 3, 308979000, 10, 1.49, 24.2398239, 54.5792761, -0.15, 10.33, 0.12, 296.55 +CTUN, 0, 0.16, 0.08, 0.000000, 0, 0, 72, 0, 0 +ATT, 0.00, -0.03, 0.00, -2.25, 0.00, 135.23, 135.23 +CTUN, 0, 0.16, 0.29, 0.000000, 0, 0, 56, 0, 0 +ATT, 0.00, 0.48, 0.00, -2.76, 0.00, 130.68, 130.68 +GPS, 3, 308979200, 10, 1.49, 24.2398241, 54.5792763, 0.00, 10.46, 0.12, 296.55 +CTUN, 0, 0.26, 0.54, 0.000000, 0, 0, 42, 0, 0 +ATT, 0.00, 0.75, 0.00, -3.45, 0.00, 126.26, 126.26 +CTUN, 0, 0.26, 0.75, 0.000000, 0, 0, 36, 0, 0 +ATT, 0.00, -1.53, 0.00, -4.36, 0.00, 122.30, 122.30 +GPS, 3, 308979400, 10, 1.49, 24.2398241, 54.5792766, 0.14, 10.58, 0.13, 296.55 +CTUN, 0, 0.39, 0.79, 0.000000, 0, 0, 22, 0, 0 +ATT, 0.00, -1.44, 0.00, -6.41, 0.00, 118.11, 118.11 +CTUN, 0, 0.39, 0.76, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, -0.27, 0.00, -7.35, 0.00, 114.46, 114.46 +GPS, 3, 308979600, 10, 1.49, 24.2398237, 54.5792777, 0.23, 10.65, 0.51, 16.51 +CTUN, 0, 0.49, 0.78, 0.000000, 0, 0, -7, 0, 0 +ATT, 0.00, 2.36, 0.00, -7.68, 0.00, 111.88, 111.88 +CTUN, 0, 0.49, 0.87, 0.000000, 0, 0, -18, 0, 0 +ATT, 0.00, 4.44, 0.00, -7.58, 0.00, 109.95, 109.95 +DU32, 7, 426173 +CURR, 0, 297030, 1210, 0, 4752, 0.000000 +GPS, 3, 308979800, 10, 1.49, 24.2398230, 54.5792792, 0.26, 10.67, 0.88, 98.67 +CTUN, 0, 0.50, 0.79, 0.000000, 0, 0, -26, 0, 0 +ATT, 0.00, 4.45, 0.00, -5.84, 0.00, 108.51, 108.51 +CTUN, 0, 0.49, 0.56, 0.000000, 0, 0, -9, 0, 0 +ATT, 0.00, 4.50, 0.00, -2.32, 0.00, 107.44, 107.44 +GPS, 3, 308980000, 10, 1.49, 24.2398219, 54.5792814, 0.29, 10.64, 1.33, 113.88 +CTUN, 0, 0.49, 0.80, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 4.32, 0.00, 0.89, 0.00, 106.66, 106.66 +CTUN, 0, 0.46, 0.59, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, 4.23, 0.00, 3.31, 0.00, 105.22, 105.22 +GPS, 3, 308980200, 10, 1.49, 24.2398206, 54.5792835, 0.34, 10.64, 1.34, 118.38 +CTUN, 0, 0.49, 0.78, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 3.56, 0.00, 5.08, 0.00, 103.94, 103.94 +CTUN, 0, 0.49, 1.04, 0.000000, 0, 0, -10, 0, 0 +ATT, 0.00, 3.21, 0.00, 6.28, 0.00, 103.04, 103.04 +GPS, 3, 308980400, 9, 1.75, 24.2398195, 54.5792856, 0.39, 10.66, 1.25, 122.12 +CTUN, 0, 0.54, 0.84, 0.000000, 0, 0, -6, 0, 0 +ATT, 0.00, 2.61, 0.00, 5.87, 0.00, 102.47, 102.47 +CTUN, 0, 0.54, 0.89, 0.000000, 0, 0, 7, 0, 0 +ATT, 0.00, 1.49, 0.00, 4.41, 0.00, 102.44, 102.44 +GPS, 3, 308980600, 9, 1.75, 24.2398187, 54.5792873, 0.46, 10.63, 1.09, 122.11 +CTUN, 0, 0.55, 0.89, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 1.22, 0.00, 3.91, 0.00, 103.11, 103.11 +CTUN, 0, 0.55, 0.70, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 2.55, 0.00, 4.65, 0.00, 103.50, 103.50 +DU32, 7, 426173 +CURR, 0, 297030, 1211, 0, 4772, 0.000000 +GPS, 3, 308980800, 9, 1.75, 24.2398176, 54.5792888, 0.49, 10.70, 0.93, 124.60 +CTUN, 0, 0.57, 0.68, 0.000000, 0, 0, -23, 0, 0 +ATT, 0.00, 3.63, 0.00, 5.71, 0.00, 103.80, 103.80 +CTUN, 0, 0.55, 0.75, 0.000000, 0, 0, -35, 0, 0 +ATT, 0.00, 3.84, 0.00, 6.11, 0.00, 104.06, 104.06 +GPS, 3, 308981000, 9, 1.75, 24.2398169, 54.5792898, 0.45, 10.63, 0.81, 127.13 +CTUN, 0, 0.55, 0.82, 0.000000, 0, 0, -33, 0, 0 +ATT, 0.00, 3.44, 0.00, 5.55, 0.00, 104.03, 104.03 +CTUN, 0, 0.54, 0.61, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, 2.55, 0.00, 4.47, 0.00, 103.61, 103.61 +GPS, 3, 308981200, 9, 1.75, 24.2398160, 54.5792908, 0.45, 10.54, 0.89, 131.80 +CTUN, 0, 0.54, 0.62, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 3.66, 0.00, 2.52, 0.00, 102.71, 102.71 +CTUN, 0, 0.49, 0.87, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 4.89, 0.00, 0.52, 0.00, 101.18, 101.18 +GPS, 3, 308981400, 9, 1.75, 24.2398148, 54.5792915, 0.47, 10.54, 0.75, 139.90 +CTUN, 0, 0.53, 0.91, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 4.60, 0.00, 0.07, 0.00, 99.46, 99.46 +CTUN, 0, 0.53, 1.03, 0.000000, 0, 0, -18, 0, 0 +ATT, 0.00, 3.49, 0.00, 0.85, 0.00, 98.69, 98.69 +GPS, 3, 308981600, 9, 1.75, 24.2398138, 54.5792925, 0.49, 10.55, 0.73, 142.17 +CTUN, 0, 0.55, 1.02, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 2.72, 0.00, 1.34, 0.00, 98.97, 98.97 +CTUN, 0, 0.55, 0.87, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 2.31, 0.00, 1.28, 0.00, 99.86, 99.86 +DU32, 7, 426173 +CURR, 0, 297030, 1211, 0, 4752, 0.000000 +GPS, 3, 308981800, 9, 1.75, 24.2398126, 54.5792935, 0.54, 10.53, 0.87, 142.38 +CTUN, 0, 0.55, 0.89, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 1.52, 0.00, 0.48, 0.00, 101.15, 101.15 +CTUN, 0, 0.55, 0.89, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 1.17, 0.00, 0.93, 0.00, 102.61, 102.61 +GPS, 3, 308982000, 9, 1.75, 24.2398114, 54.5792945, 0.58, 10.53, 0.86, 143.83 +CTUN, 0, 0.57, 0.85, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, 2.11, 0.00, 2.22, 0.00, 104.12, 104.12 +CTUN, 0, 0.55, 0.72, 0.000000, 0, 0, -32, 0, 0 +ATT, 0.00, 2.40, 0.00, 3.20, 0.00, 105.78, 105.78 +GPS, 3, 308982200, 9, 1.75, 24.2398102, 54.5792955, 0.55, 10.52, 0.88, 144.06 +CTUN, 0, 0.55, 0.63, 0.000000, 0, 0, -40, 0, 0 +ATT, 0.00, 2.21, 0.00, 3.51, 0.00, 107.22, 107.22 +CTUN, 0, 0.53, 0.67, 0.000000, 0, 0, -29, 0, 0 +ATT, 0.00, 1.90, 0.00, 3.76, 0.00, 107.76, 107.76 +GPS, 3, 308982400, 10, 1.49, 24.2398087, 54.5792966, 0.50, 10.47, 1.09, 143.33 +CTUN, 0, 0.53, 0.69, 0.000000, 0, 0, -24, 0, 0 +ATT, 0.00, 2.21, 0.00, 3.16, 0.00, 107.37, 107.37 +CTUN, 0, 0.44, 0.79, 0.000000, 0, 0, -21, 0, 0 +ATT, 0.00, 2.08, 0.00, 2.20, 0.00, 105.88, 105.88 +GPS, 3, 308982600, 10, 1.49, 24.2398074, 54.5792974, 0.48, 10.44, 0.92, 145.95 +CTUN, 0, 0.46, 0.74, 0.000000, 0, 0, -32, 0, 0 +ATT, 0.00, 1.67, 0.00, 1.51, 0.00, 103.73, 103.73 +CTUN, 0, 0.45, 0.88, 0.000000, 0, 0, -47, 0, 0 +ATT, 0.00, 0.64, 0.00, 1.12, 0.00, 102.04, 102.04 +DU32, 7, 426173 +CURR, 0, 297030, 1220, 0, 4752, 0.000000 +GPS, 3, 308982800, 10, 1.49, 24.2398061, 54.5792982, 0.43, 10.41, 0.84, 149.62 +CTUN, 0, 0.45, 0.64, 0.000000, 0, 0, -41, 0, 0 +ATT, 0.00, 1.36, 0.00, 0.38, 0.00, 100.90, 100.90 +CTUN, 0, 0.44, 0.69, 0.000000, 0, 0, -37, 0, 0 +ATT, 0.00, 2.07, 0.00, -1.15, 0.00, 100.38, 100.38 +GPS, 3, 308983000, 10, 1.49, 24.2398053, 54.5792990, 0.38, 10.30, 0.72, 145.42 +CTUN, 0, 0.44, 0.63, 0.000000, 0, 0, -55, 0, 0 +ATT, 0.00, 2.23, 0.00, -2.21, 0.00, 101.09, 101.09 +CTUN, 0, 0.39, 0.49, 0.000000, 0, 0, -69, 0, 0 +ATT, 0.00, 1.95, 0.00, -2.39, 0.00, 102.55, 102.55 +GPS, 3, 308983200, 10, 1.49, 24.2398043, 54.5792999, 0.27, 10.25, 0.69, 144.51 +CTUN, 0, 0.39, 0.34, 0.000000, 0, 0, -83, 0, 0 +ATT, 0.00, 2.33, 0.00, -1.19, 0.00, 103.20, 103.20 +CTUN, 0, 0.29, 0.28, 0.000000, 0, 0, -86, 0, 0 +ATT, 0.00, 1.40, 0.00, 1.02, 0.00, 103.32, 103.32 +GPS, 3, 308983400, 10, 1.49, 24.2398034, 54.5793010, 0.12, 10.10, 0.89, 137.08 +CTUN, 0, 0.29, 0.08, 0.000000, 0, 0, -71, 0, 0 +ATT, 0.00, 0.40, 0.00, 2.72, 0.00, 102.94, 102.94 +CTUN, 0, 0.17, 0.00, 0.000000, 0, 0, -57, 0, 0 +ATT, 0.00, 1.17, 0.00, 2.02, 0.00, 102.25, 102.25 +GPS, 3, 308983600, 10, 1.49, 24.2398027, 54.5793015, 0.00, 9.92, 0.61, 139.64 +CTUN, 0, 0.17, -0.07, 0.000000, 0, 0, -47, 0, 0 +ATT, 0.00, 0.78, 0.00, -0.67, 0.00, 101.02, 101.02 +CTUN, 0, 0.17, -0.09, 0.000000, 0, 0, -37, 0, 0 +ATT, 0.00, 0.73, 0.00, -1.93, 0.00, 99.80, 99.80 +DU32, 7, 426173 +CURR, 0, 297030, 1210, 0, 4772, 0.000000 +GPS, 3, 308983800, 10, 1.49, 24.2398025, 54.5793017, -0.08, 9.82, 0.22, 139.64 +CTUN, 0, 0.17, -0.20, 0.000000, 0, 0, -31, 0, 0 +ATT, 0.00, 0.74, 0.00, -2.06, 0.00, 98.52, 98.52 +CTUN, 0, 0.17, -0.13, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.90, 0.00, -0.44, 0.00, 98.26, 98.26 +GPS, 3, 308984000, 10, 1.49, 24.2398023, 54.5793016, -0.12, 9.78, 0.18, 139.64 +CTUN, 0, 0.20, -0.10, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.73, 0.00, -0.37, 0.00, 98.23, 98.23 +CTUN, 0, 0.20, -0.15, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.71, 0.00, -0.31, 0.00, 98.24, 98.24 +GPS, 3, 308984200, 10, 1.49, 24.2398023, 54.5793016, -0.14, 9.78, 0.12, 139.64 +CTUN, 0, 0.22, -0.22, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.68, 0.00, -0.26, 0.00, 98.24, 98.24 +CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.64, 0.00, -0.27, 0.00, 98.24, 98.24 +GPS, 3, 308984400, 9, 1.75, 24.2398026, 54.5793015, -0.17, 9.74, 0.11, 139.64 +CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.61, 0.00, -0.27, 0.00, 98.24, 98.24 +CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.59, 0.00, -0.28, 0.00, 98.25, 98.25 +GPS, 3, 308984600, 10, 1.49, 24.2398027, 54.5793016, -0.20, 9.75, 0.04, 139.64 +CTUN, 0, 0.22, -0.11, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.57, 0.00, -0.30, 0.00, 98.25, 98.25 +CTUN, 0, 0.22, -0.11, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.56, 0.00, -0.34, 0.00, 98.25, 98.25 +DU32, 7, 426173 +CURR, 0, 297030, 1215, 0, 4772, 0.000000 +GPS, 3, 308984800, 10, 1.49, 24.2398026, 54.5793017, -0.21, 9.77, 0.03, 139.64 +CTUN, 0, 0.22, 0.03, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.56, 0.00, -0.37, 0.00, 98.26, 98.26 +CTUN, 0, 0.22, -0.06, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.57, 0.00, -0.37, 0.00, 98.26, 98.26 +GPS, 3, 308985000, 10, 1.49, 24.2398029, 54.5793018, -0.21, 9.75, 0.08, 139.64 +CTUN, 0, 0.22, -0.01, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.57, 0.00, -0.38, 0.00, 98.27, 98.27 +CTUN, 0, 0.22, -0.18, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.53, 0.00, -0.38, 0.00, 98.27, 98.27 +GPS, 3, 308985200, 9, 1.75, 24.2398029, 54.5793020, -0.22, 9.78, 0.09, 139.64 +CTUN, 0, 0.22, -0.28, 0.000000, 0, 0, -11, 0, 0 +ATT, 0.00, 0.51, 0.00, -0.39, 0.00, 98.28, 98.28 +CTUN, 0, 0.22, -0.34, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.52, 0.00, -0.42, 0.00, 98.28, 98.28 +GPS, 3, 308985400, 10, 1.49, 24.2398029, 54.5793019, -0.25, 9.78, 0.06, 139.64 +CTUN, 0, 0.22, -0.29, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.52, 0.00, -0.43, 0.00, 98.29, 98.29 +CTUN, 0, 0.22, -0.29, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.53, 0.00, -0.39, 0.00, 98.30, 98.30 +GPS, 3, 308985600, 10, 1.49, 24.2398028, 54.5793018, -0.28, 9.81, 0.04, 139.64 +CTUN, 0, 0.22, -0.23, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.53, 0.00, -0.37, 0.00, 98.30, 98.30 +CTUN, 0, 0.22, -0.37, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.51, 0.00, -0.38, 0.00, 98.31, 98.31 +DU32, 7, 426173 +CURR, 0, 297030, 1221, 0, 4752, 0.000000 +GPS, 3, 308985800, 10, 1.49, 24.2398028, 54.5793019, -0.31, 9.84, 0.08, 139.64 +CTUN, 0, 0.22, -0.41, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.50, 0.00, -0.40, 0.00, 98.31, 98.31 +CTUN, 0, 0.22, -0.39, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.48, 0.00, -0.44, 0.00, 98.32, 98.32 +GPS, 3, 308986000, 10, 1.49, 24.2398030, 54.5793019, -0.34, 9.82, 0.07, 139.64 +CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.46, 0.00, -0.46, 0.00, 98.32, 98.32 +CTUN, 0, 0.22, -0.22, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.45, 0.00, -0.42, 0.00, 98.33, 98.33 +GPS, 3, 308986200, 10, 1.49, 24.2398031, 54.5793020, -0.36, 9.85, 0.01, 139.64 +CTUN, 0, 0.22, -0.26, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.44, 0.00, -0.40, 0.00, 98.33, 98.33 +CTUN, 0, 0.22, -0.23, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.44, 0.00, -0.43, 0.00, 98.33, 98.33 +GPS, 3, 308986400, 10, 1.49, 24.2398030, 54.5793020, -0.37, 9.85, 0.02, 139.64 +CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.44, 0.00, -0.44, 0.00, 98.34, 98.34 +CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.44, 0.00, -0.45, 0.00, 98.35, 98.35 +GPS, 3, 308986600, 10, 1.49, 24.2398029, 54.5793021, -0.40, 9.88, 0.02, 139.64 +CTUN, 0, 0.22, -0.41, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.44, 0.00, -0.46, 0.00, 98.35, 98.35 +CTUN, 0, 0.22, -0.32, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.43, 0.00, -0.47, 0.00, 98.36, 98.36 +DU32, 7, 426173 +CURR, 0, 297030, 1219, 0, 4772, 0.000000 +GPS, 3, 308986800, 10, 1.49, 24.2398029, 54.5793022, -0.42, 9.92, 0.00, 139.64 +CTUN, 0, 0.22, -0.35, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.42, 0.00, -0.48, 0.00, 98.36, 98.36 +CTUN, 0, 0.22, -0.39, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.41, 0.00, -0.48, 0.00, 98.37, 98.37 +GPS, 3, 308987000, 10, 1.49, 24.2398028, 54.5793020, -0.44, 9.92, 0.03, 139.64 +CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.40, 0.00, -0.48, 0.00, 98.37, 98.37 +CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.38, 0.00, -0.49, 0.00, 98.38, 98.38 +GPS, 3, 308987200, 10, 1.49, 24.2398027, 54.5793020, -0.45, 9.93, 0.01, 139.64 +CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.37, 0.00, -0.50, 0.00, 98.39, 98.39 +CTUN, 0, 0.22, -0.25, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.37, 0.00, -0.50, 0.00, 98.39, 98.39 +GPS, 3, 308987400, 10, 1.49, 24.2398026, 54.5793021, -0.46, 9.95, 0.01, 139.64 +CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.36, 0.00, -0.51, 0.00, 98.40, 98.40 +CTUN, 0, 0.22, -0.45, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.36, 0.00, -0.50, 0.00, 98.41, 98.41 +GPS, 3, 308987600, 10, 1.49, 24.2398026, 54.5793020, -0.48, 9.96, 0.02, 139.64 +CTUN, 0, 0.24, -0.59, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.35, 0.00, -0.50, 0.00, 98.41, 98.41 +CTUN, 0, 0.22, -0.50, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.34, 0.00, -0.50, 0.00, 98.42, 98.42 +DU32, 7, 426173 +CURR, 0, 297030, 1213, 0, 4793, 0.000000 +GPS, 3, 308987800, 10, 1.49, 24.2398026, 54.5793021, -0.52, 9.97, 0.02, 139.64 +CTUN, 0, 0.22, -0.42, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.34, 0.00, -0.51, 0.11, 98.42, 98.42 +CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.33, 0.00, -0.52, 0.00, 98.43, 98.43 +GPS, 3, 308988000, 9, 1.96, 24.2398025, 54.5793020, -0.53, 10.00, 0.01, 139.64 +CTUN, 0, 0.22, -0.40, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.32, 0.00, -0.53, 0.00, 98.43, 98.43 +CTUN, 0, 0.22, -0.43, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.31, 0.00, -0.53, 0.00, 98.44, 98.44 +GPS, 3, 308988200, 9, 1.96, 24.2398024, 54.5793020, -0.55, 10.02, 0.02, 139.64 +CTUN, 0, 0.22, -0.44, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.30, 0.00, -0.53, 0.00, 98.45, 98.45 +CTUN, 0, 0.22, -0.38, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.29, 0.00, -0.54, 0.00, 98.46, 98.46 +GPS, 3, 308988400, 10, 1.49, 24.2398023, 54.5793020, -0.56, 10.04, 0.00, 139.64 +CTUN, 0, 0.22, -0.43, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.28, 0.00, -0.54, 0.00, 98.46, 98.46 +PM, 0, 0, 50, 0, 1000, 10500, 9, 0 +CTUN, 0, 0.22, -0.46, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.28, 0.00, -0.55, 0.00, 98.46, 98.46 +GPS, 3, 308988600, 10, 1.49, 24.2398022, 54.5793020, -0.58, 10.05, 0.00, 139.64 +CTUN, 0, 0.22, -0.54, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.27, 0.00, -0.55, 0.00, 98.47, 98.47 +CTUN, 0, 0.22, -0.44, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.26, 0.00, -0.55, 0.00, 98.47, 98.47 +DU32, 7, 426173 +CURR, 0, 297030, 1216, 0, 4772, 0.000000 +GPS, 3, 308988800, 10, 1.49, 24.2398022, 54.5793019, -0.59, 10.05, 0.02, 139.64 +CTUN, 0, 0.24, -0.43, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.26, 0.00, -0.56, 0.00, 98.48, 98.48 +CTUN, 0, 0.22, -0.42, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.26, 0.00, -0.56, 0.00, 98.48, 98.48 +GPS, 3, 308989000, 10, 1.49, 24.2398021, 54.5793020, -0.61, 10.07, 0.01, 139.64 +CTUN, 0, 0.22, -0.46, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.25, 0.00, -0.57, 0.00, 98.49, 98.49 +CTUN, 0, 0.22, -0.43, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.24, 0.00, -0.57, 0.00, 98.50, 98.50 +GPS, 3, 308989200, 10, 1.49, 24.2398021, 54.5793020, -0.62, 10.07, 0.02, 139.64 +CTUN, 0, 0.22, -0.34, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.23, 0.00, -0.58, 0.00, 98.50, 98.50 +CTUN, 0, 0.22, -0.44, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.23, 0.00, -0.58, 0.00, 98.51, 98.51 +GPS, 3, 308989400, 10, 1.49, 24.2398021, 54.5793019, -0.62, 10.07, 0.01, 139.64 +CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.23, 0.00, -0.59, 0.00, 98.51, 98.51 +CTUN, 0, 0.22, -0.34, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.21, 0.00, -0.59, 0.00, 98.52, 98.52 +GPS, 3, 308989600, 10, 1.49, 24.2398020, 54.5793020, -0.62, 10.10, 0.01, 139.64 +CTUN, 0, 0.22, -0.45, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.21, 0.00, -0.59, 0.00, 98.53, 98.53 +CTUN, 0, 0.22, -0.35, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.21, 0.00, -0.60, 0.00, 98.53, 98.53 +DU32, 7, 426173 +CURR, 0, 297030, 1216, 0, 4752, 0.000000 +GPS, 3, 308989800, 10, 1.49, 24.2398020, 54.5793021, -0.62, 10.12, 0.01, 139.64 +CTUN, 0, 0.22, -0.47, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.20, 0.00, -0.60, 0.00, 98.54, 98.54 +CTUN, 0, 0.22, -0.35, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.18, 0.00, -0.61, 0.00, 98.55, 98.55 +GPS, 3, 308990000, 10, 1.49, 24.2398019, 54.5793021, -0.62, 10.14, 0.02, 139.64 +CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.16, 0.00, -0.61, 0.00, 98.56, 98.56 +CTUN, 0, 0.22, -0.33, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.15, 0.00, -0.61, 0.00, 98.57, 98.57 +GPS, 3, 308990200, 10, 1.49, 24.2398019, 54.5793022, -0.61, 10.16, 0.01, 139.64 +CTUN, 0, 0.22, -0.36, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.13, 0.00, -0.61, 0.00, 98.58, 98.58 +CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.12, 0.00, -0.62, 0.00, 98.59, 98.59 +GPS, 3, 308990400, 10, 1.49, 24.2398018, 54.5793022, -0.61, 10.18, 0.00, 139.64 +CTUN, 0, 0.22, -0.25, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.11, 0.00, -0.62, 0.00, 98.60, 98.60 +CTUN, 0, 0.22, -0.27, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.10, 0.00, -0.62, 0.00, 98.61, 98.61 +GPS, 3, 308990600, 10, 1.49, 24.2398017, 54.5793022, -0.59, 10.19, 0.01, 139.64 +CTUN, 0, 0.22, -0.28, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.09, 0.00, -0.62, 0.00, 98.61, 98.61 +CTUN, 0, 0.22, -0.24, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.09, 0.00, -0.63, 0.00, 98.62, 98.62 +DU32, 7, 426173 +CURR, 0, 297030, 1217, 0, 4772, 0.000000 +EV, 11 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +PM, 0, 0, 51, 4, 1000, 115952, 11, 0 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +PM, 0, 0, 50, 5, 1000, 11076, 10, 0 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +PM, 0, 0, 50, 3, 1000, 11148, 10, 0 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +PM, 0, 0, 52, 13, 1000, 58732, 9, 0 +DU32, 7, 393405 +DU32, 7, 393405 +DU32, 7, 393405 +D32, 9, 10034 +CMD, 9, 0, 16, 0, 0, 0.00, 24.2397986, 54.5793039 +EV, 10 +GPS, 3, 309032600, 10, 1.49, 24.2397986, 54.5793039, -0.46, 12.10, 0.01, 139.64 +DU32, 7, 393405 +CURR, 0, 297030, 1212, 0, 4772, 0.000000 +GPS, 3, 309034600, 10, 1.49, 24.2397986, 54.5793039, -0.46, 12.13, 0.01, 139.64 +CTUN, 0, 0.22, 0.02, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, -0.61, 0.00, -0.61, 0.00, 100.34, 100.34 +CTUN, 0, 0.22, 0.10, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, -0.60, 0.00, -0.59, 0.00, 100.34, 100.34 +GPS, 3, 309034800, 10, 1.49, 24.2397986, 54.5793038, -0.40, 12.13, 0.01, 139.64 +CTUN, 0, 0.22, 0.00, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, -0.60, 0.00, -0.58, 0.00, 100.33, 100.33 +CTUN, 0, 0.22, -0.04, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, -0.61, 0.00, -0.59, 0.00, 100.33, 100.33 +GPS, 3, 309035000, 10, 1.49, 24.2397986, 54.5793038, -0.35, 12.13, 0.01, 139.64 +CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, -0.61, 0.00, -0.59, 0.00, 100.33, 100.33 +CTUN, 0, 0.22, 0.09, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, -0.60, 0.00, -0.59, 0.11, 100.33, 100.33 +GPS, 3, 309035200, 10, 1.49, 24.2397986, 54.5793038, -0.30, 12.14, 0.01, 139.64 +CTUN, 0, 0.22, -0.10, 0.000000, 0, 0, 4, 0, 0 +EV, 15 +ATT, 0.00, -0.60, 0.00, -0.59, 0.00, 100.32, 100.32 +CTUN, 278, 0.22, -0.10, 0.000000, 0, 0, 4, 256, 0 +ATT, 0.00, -0.60, 0.00, -0.60, 0.00, 100.32, 100.32 +GPS, 3, 309035400, 10, 1.49, 24.2397986, 54.5793038, -0.27, 12.14, 0.00, 139.64 +CTUN, 285, 0.22, -0.04, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.60, 0.00, -0.61, 0.00, 100.32, 100.32 +CTUN, 286, 0.22, -0.08, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.61, 0.00, -0.61, 0.00, 100.32, 100.32 +GPS, 3, 309035600, 10, 1.49, 24.2397985, 54.5793039, -0.23, 12.15, 0.02, 139.64 +CTUN, 285, 0.22, -0.02, 0.000000, 0, 0, 4, 285, 0 +DU32, 7, 393469 +CURR, 285, 298109, 1213, 0, 4772, 0.000000 +ATT, 0.00, -0.61, 0.00, -0.61, 0.00, 100.32, 100.32 +CTUN, 285, 0.22, -0.13, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.32, 100.32 +GPS, 3, 309035800, 10, 1.49, 24.2397985, 54.5793039, -0.21, 12.15, 0.01, 139.64 +CTUN, 286, 0.22, 0.06, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.32, 100.32 +CTUN, 285, 0.22, 0.00, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.32, 100.32 +GPS, 3, 309036000, 10, 1.49, 24.2397985, 54.5793039, -0.17, 12.16, 0.01, 139.64 +CTUN, 285, 0.22, -0.03, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.61, 0.00, 100.32, 100.32 +CTUN, 286, 0.22, 0.03, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.62, 0.00, 100.33, 100.32 +GPS, 3, 309036200, 10, 1.49, 24.2397985, 54.5793039, -0.13, 12.16, 0.00, 139.64 +CTUN, 285, 0.22, 0.11, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.62, 0.00, 100.33, 100.32 +CTUN, 285, 0.22, 0.21, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.62, 0.00, 100.33, 100.32 +GPS, 3, 309036400, 10, 1.49, 24.2397985, 54.5793039, -0.09, 12.16, 0.01, 139.64 +CTUN, 286, 0.22, 0.03, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.63, 0.00, 100.32, 100.32 +CTUN, 285, 0.22, 0.13, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.63, 0.00, 100.32, 100.32 +GPS, 3, 309036600, 10, 1.49, 24.2397985, 54.5793039, -0.05, 12.17, 0.01, 139.64 +CTUN, 285, 0.22, 0.15, 0.000000, 0, 0, 8, 285, 0 +DU32, 7, 393469 +CURR, 286, 300963, 1214, 0, 4772, 0.000000 +ATT, 0.00, -0.63, 0.00, -0.63, 0.00, 100.32, 100.32 +CTUN, 286, 0.22, 0.02, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.63, 0.00, 100.33, 100.32 +GPS, 3, 309036800, 10, 1.49, 24.2397985, 54.5793039, -0.02, 12.17, 0.00, 139.64 +CTUN, 285, 0.22, 0.06, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.63, 0.00, 100.33, 100.32 +CTUN, 285, 0.22, 0.09, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.63, 0.00, 100.33, 100.32 +GPS, 3, 309037000, 10, 1.49, 24.2397985, 54.5793039, 0.00, 12.18, 0.01, 139.64 +CTUN, 286, 0.22, 0.17, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.64, 0.00, 100.33, 100.32 +CTUN, 286, 0.22, 0.12, 0.000000, 0, 0, 9, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.64, 0.00, 100.33, 100.32 +GPS, 3, 309037200, 10, 1.49, 24.2397984, 54.5793040, 0.04, 12.18, 0.01, 139.64 +CTUN, 285, 0.22, -0.18, 0.000000, 0, 0, 9, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.64, 0.00, 100.33, 100.32 +CTUN, 286, 0.22, -0.23, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.62, 0.00, -0.65, 0.00, 100.33, 100.32 +GPS, 3, 309037400, 10, 1.49, 24.2397984, 54.5793040, 0.03, 12.19, 0.00, 139.64 +CTUN, 285, 0.22, -0.21, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.65, 0.00, 100.33, 100.32 +CTUN, 286, 0.22, -0.15, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.65, 0.00, 100.33, 100.32 +GPS, 3, 309037600, 10, 1.49, 24.2397984, 54.5793040, 0.02, 12.20, 0.00, 139.64 +CTUN, 286, 0.22, -0.18, 0.000000, 0, 0, 8, 286, 0 +DU32, 7, 393469 +CURR, 285, 303819, 1219, 0, 4752, 0.000000 +ATT, 0.00, -0.63, 0.00, -0.65, 0.00, 100.33, 100.32 +CTUN, 285, 0.22, -0.08, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.33, 100.32 +GPS, 3, 309037800, 10, 1.49, 24.2397984, 54.5793040, 0.01, 12.20, 0.02, 139.64 +CTUN, 286, 0.22, -0.05, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.33, 100.32 +CTUN, 285, 0.22, -0.12, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.34, 100.32 +GPS, 3, 309038000, 10, 1.49, 24.2397984, 54.5793040, 0.02, 12.21, 0.01, 139.64 +CTUN, 285, 0.22, 0.02, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.67, 0.00, 100.34, 100.32 +CTUN, 286, 0.22, 0.11, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.34, 100.32 +GPS, 3, 309038200, 10, 1.49, 24.2397984, 54.5793041, 0.04, 12.21, 0.01, 139.64 +CTUN, 286, 0.22, -0.06, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.66, 0.00, 100.34, 100.32 +CTUN, 285, 0.22, -0.02, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.67, 0.00, 100.35, 100.32 +GPS, 3, 309038400, 10, 1.49, 24.2397984, 54.5793041, 0.04, 12.22, 0.01, 139.64 +CTUN, 285, 0.22, 0.02, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.68, 0.00, -0.67, 0.00, 100.31, 100.32 +CTUN, 285, 0.24, -0.02, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.68, 0.00, 100.33, 100.32 +GPS, 3, 309038600, 10, 1.49, 24.2397984, 54.5793041, 0.05, 12.22, 0.01, 139.64 +CTUN, 286, 0.22, 0.16, 0.000000, 0, 0, 7, 286, 0 +DU32, 7, 393469 +CURR, 286, 306673, 1213, 0, 4752, 0.000000 +ATT, 0.00, -0.65, 0.00, -0.68, 0.00, 100.33, 100.32 +CTUN, 286, 0.24, 0.19, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.34, 100.32 +GPS, 3, 309038800, 10, 1.49, 24.2397983, 54.5793041, 0.08, 12.23, 0.02, 139.64 +CTUN, 286, 0.22, 0.24, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.64, 0.00, -0.69, 0.00, 100.35, 100.32 +CTUN, 285, 0.22, 0.06, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.64, 0.00, -0.68, 0.00, 100.35, 100.32 +GPS, 3, 309039000, 10, 1.49, 24.2397983, 54.5793041, 0.10, 12.23, 0.03, 139.64 +CTUN, 285, 0.22, 0.00, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.64, 0.00, -0.67, 0.00, 100.35, 100.32 +CTUN, 285, 0.22, 0.00, 0.000000, 0, 0, 8, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.35, 100.32 +GPS, 3, 309039200, 10, 1.49, 24.2397984, 54.5793041, 0.11, 12.25, 0.04, 139.64 +CTUN, 286, 0.22, 0.00, 0.000000, 0, 0, 8, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.36, 100.32 +CTUN, 285, 0.22, 0.02, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.36, 100.32 +GPS, 3, 309039400, 10, 1.49, 24.2397983, 54.5793041, 0.11, 12.26, 0.01, 139.64 +CTUN, 285, 0.22, 0.09, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.66, 0.00, -0.69, 0.00, 100.37, 100.32 +CTUN, 286, 0.22, 0.03, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.37, 100.32 +GPS, 3, 309039600, 10, 1.49, 24.2397983, 54.5793041, 0.12, 12.26, 0.04, 139.64 +CTUN, 286, 0.22, -0.06, 0.000000, 0, 0, 7, 286, 0 +DU32, 7, 393469 +CURR, 286, 309529, 1216, 0, 4772, 0.000000 +ATT, 0.00, -0.64, 0.00, -0.70, 0.00, 100.38, 100.32 +CTUN, 286, 0.22, -0.08, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.70, 0.00, 100.38, 100.32 +GPS, 3, 309039800, 10, 1.49, 24.2397982, 54.5793042, 0.11, 12.26, 0.05, 139.64 +CTUN, 285, 0.22, -0.04, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.70, 0.00, 100.38, 100.32 +CTUN, 285, 0.22, 0.01, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.72, 0.00, 100.39, 100.32 +GPS, 3, 309040000, 10, 1.49, 24.2397983, 54.5793041, 0.11, 12.27, 0.01, 139.64 +CTUN, 286, 0.22, -0.08, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.72, 0.00, 100.39, 100.32 +CTUN, 286, 0.22, -0.01, 0.000000, 0, 0, 6, 286, 0 +ATT, 0.00, -0.64, 0.00, -0.70, 0.00, 100.39, 100.32 +GPS, 3, 309040200, 10, 1.49, 24.2397983, 54.5793041, 0.10, 12.29, 0.02, 139.64 +CTUN, 286, 0.22, -0.03, 0.000000, 0, 0, 6, 286, 0 +ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.40, 100.32 +CTUN, 285, 0.22, -0.01, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.40, 100.32 +GPS, 3, 309040400, 10, 1.49, 24.2397984, 54.5793040, 0.10, 12.30, 0.03, 139.64 +CTUN, 286, 0.22, -0.09, 0.000000, 0, 0, 5, 285, 0 +ATT, 0.00, -0.64, 0.00, -0.69, 0.00, 100.41, 100.32 +CTUN, 286, 0.22, -0.10, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.66, 0.00, -0.69, 0.00, 100.41, 100.32 +GPS, 3, 309040600, 10, 1.49, 24.2397984, 54.5793041, 0.09, 12.30, 0.01, 139.64 +CTUN, 286, 0.22, 0.00, 0.000000, 0, 0, 5, 286, 0 +DU32, 7, 393469 +CURR, 286, 312385, 1219, 0, 4772, 0.000000 +ATT, 0.00, -0.65, 0.00, -0.69, 0.00, 100.41, 100.32 +CTUN, 285, 0.22, 0.05, 0.000000, 0, 0, 5, 285, 0 +ATT, 0.00, -0.65, 0.00, -0.70, 0.00, 100.41, 100.32 +GPS, 3, 309040800, 10, 1.49, 24.2397984, 54.5793041, 0.09, 12.30, 0.01, 139.64 +CTUN, 285, 0.22, -0.07, 0.000000, 0, 0, 5, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.71, 0.00, 100.42, 100.32 +CTUN, 286, 0.22, -0.03, 0.000000, 0, 0, 5, 285, 0 +ATT, 0.00, -0.64, 0.00, -0.70, 0.00, 100.42, 100.32 +GPS, 3, 309041000, 10, 1.49, 24.2397984, 54.5793041, 0.08, 12.29, 0.01, 139.64 +CTUN, 286, 0.22, -0.10, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.70, 0.00, 100.42, 100.32 +CTUN, 286, 0.22, -0.03, 0.000000, 0, 0, 4, 286, 0 +ATT, 0.00, -0.60, 0.00, -0.71, 0.00, 100.43, 100.32 +PM, 0, 0, 51, 4, 1001, 2106108, 11, 0 +GPS, 3, 309041200, 10, 1.49, 24.2397984, 54.5793041, 0.07, 12.30, 0.02, 139.64 +CTUN, 286, 0.22, 0.06, 0.000000, 0, 0, 4, 286, 0 +ATT, 0.00, -0.64, 0.00, -0.71, 0.00, 100.43, 100.32 +CTUN, 285, 0.22, -0.01, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.61, 0.00, -0.71, 0.00, 100.43, 100.32 +GPS, 3, 309041400, 10, 1.49, 24.2397984, 54.5793041, 0.08, 12.30, 0.01, 139.64 +CTUN, 285, 0.22, -0.03, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.61, 0.00, -0.70, 0.00, 100.41, 100.32 +CTUN, 286, 0.22, -0.20, 0.000000, 0, 0, 4, 286, 0 +ATT, 0.00, -0.63, 0.00, -0.69, 0.00, 100.39, 100.32 +GPS, 3, 309041600, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.29, 0.02, 139.64 +CTUN, 286, 0.22, -0.12, 0.000000, 0, 0, 4, 286, 0 +DU32, 7, 393469 +CURR, 286, 315239, 1209, 0, 4732, 0.000000 +ATT, 0.00, -0.58, 0.00, -0.73, 0.00, 100.39, 100.32 +CTUN, 286, 0.22, -0.06, 0.000000, 0, 0, 3, 286, 0 +ATT, 0.00, -0.46, 0.00, -0.83, 0.00, 100.20, 100.32 +GPS, 3, 309041800, 10, 1.49, 24.2397984, 54.5793041, 0.05, 12.29, 0.01, 139.64 +CTUN, 285, 0.22, -0.26, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.63, 0.00, -0.77, 0.00, 99.46, 100.32 +CTUN, 285, 0.24, -0.28, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.88, 0.00, -0.50, 0.00, 98.85, 100.32 +GPS, 3, 309042000, 10, 1.49, 24.2397984, 54.5793042, 0.02, 12.29, 0.01, 139.64 +CTUN, 285, 0.24, -0.17, 0.000000, 0, 0, 0, 285, 0 +ATT, 0.00, -0.45, 0.00, -0.59, 0.00, 97.84, 100.32 +CTUN, 286, 0.26, -0.22, 0.000000, 0, 0, 4, 286, 0 +ATT, 0.00, -0.72, 0.00, -0.44, 0.00, 97.00, 100.32 +GPS, 3, 309042200, 10, 1.49, 24.2397984, 54.5793041, 0.00, 12.29, 0.02, 139.64 +CTUN, 286, 0.26, -0.12, 0.000000, 0, 0, 3, 286, 0 +ATT, 0.00, -0.37, 0.00, -0.57, 0.00, 96.09, 100.32 +CTUN, 286, 0.30, -0.13, 0.000000, 0, 0, 4, 286, 0 +ATT, 0.00, -0.30, 0.00, -0.41, 0.00, 95.14, 100.32 +GPS, 3, 309042400, 10, 1.49, 24.2397983, 54.5793041, 0.00, 12.28, 0.02, 139.64 +CTUN, 285, 0.30, -0.30, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.44, 0.00, -0.35, 0.00, 94.10, 100.32 +CTUN, 285, 0.30, -0.17, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.57, 0.00, -0.41, 0.00, 93.16, 100.32 +GPS, 3, 309042600, 10, 1.49, 24.2397983, 54.5793041, -0.02, 12.28, 0.01, 139.64 +CTUN, 286, 0.26, -0.30, 0.000000, 0, 0, 3, 286, 0 +DU32, 7, 393469 +CURR, 286, 318093, 1202, 0, 4772, 0.000000 +ATT, 0.00, -0.56, 0.00, -0.46, 0.00, 92.29, 100.32 +CTUN, 286, 0.26, -0.29, 0.000000, 0, 0, 1, 286, 0 +ATT, 0.00, -0.44, 0.00, -0.44, 0.00, 91.80, 100.32 +GPS, 3, 309042800, 10, 1.49, 24.2397983, 54.5793041, -0.04, 12.28, 0.01, 139.64 +CTUN, 286, 0.26, -0.15, 0.000000, 0, 0, 4, 286, 0 +ATT, 0.00, -0.34, 0.00, -0.45, 0.00, 91.75, 100.32 +CTUN, 286, 0.55, -0.14, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.30, 0.00, -0.48, 0.00, 91.55, 100.32 +GPS, 3, 309043000, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.01, 139.64 +CTUN, 285, 0.36, -0.12, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.28, 0.00, -0.51, 0.00, 91.46, 100.32 +CTUN, 285, 0.38, -0.19, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.43, 0.00, -0.51, 0.00, 91.47, 100.32 +GPS, 3, 309043200, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.02, 139.64 +CTUN, 286, 0.38, -0.16, 0.000000, 0, 0, 5, 285, 0 +ATT, 0.00, -0.29, 0.00, -0.51, 0.00, 91.50, 100.32 +CTUN, 286, 0.38, -0.14, 0.000000, 0, 0, 6, 286, 0 +ATT, 0.00, -0.45, 0.00, -0.50, 0.00, 91.57, 100.32 +GPS, 3, 309043400, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.01, 139.64 +CTUN, 286, 0.38, -0.13, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.39, 0.00, -0.44, 0.00, 91.70, 100.32 +CTUN, 286, 0.38, -0.24, 0.000000, 0, 0, 5, 286, 0 +ATT, 0.00, -0.37, 0.00, -0.44, 0.00, 91.89, 100.32 +GPS, 3, 309043600, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.02, 139.64 +CTUN, 285, 0.38, -0.15, 0.000000, 0, 0, 6, 285, 0 +DU32, 7, 393469 +CURR, 285, 320949, 1174, 0, 4772, 0.000000 +ATT, 0.00, -0.48, 0.00, -0.44, 0.00, 92.11, 100.32 +CTUN, 285, 0.53, -0.07, 0.000000, 0, 0, 6, 285, 0 +ATT, 0.00, -0.49, 0.00, -0.37, 0.00, 92.36, 100.32 +GPS, 3, 309043800, 10, 1.49, 24.2397983, 54.5793041, -0.05, 12.29, 0.01, 139.64 +CTUN, 285, 0.39, -0.10, 0.000000, 0, 0, 7, 285, 0 +ATT, 0.00, -0.50, 0.00, -0.25, 0.00, 93.00, 100.32 +CTUN, 286, 0.53, -0.07, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.52, 0.00, -0.20, 0.00, 93.82, 100.32 +GPS, 3, 309044000, 10, 1.49, 24.2397983, 54.5793041, -0.04, 12.30, 0.00, 139.64 +CTUN, 286, 0.53, -0.07, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.52, 0.00, -0.11, 0.00, 94.96, 100.32 +CTUN, 286, 0.53, -0.28, 0.000000, 0, 0, 7, 286, 0 +ATT, 0.00, -0.49, 0.00, -0.21, 0.00, 96.44, 100.32 +GPS, 3, 309044200, 10, 1.49, 24.2397983, 54.5793041, -0.03, 12.30, 0.02, 139.64 +CTUN, 286, 0.34, -0.04, 0.000000, 0, 0, 10, 286, 0 +ATT, 0.00, -0.67, 0.00, -0.36, 0.00, 98.04, 100.32 +CTUN, 285, 0.34, 0.01, 0.000000, 0, 0, 9, 285, 0 +ATT, 0.00, -0.84, 0.00, -0.34, 0.00, 99.56, 100.32 +GPS, 3, 309044400, 10, 1.49, 24.2397983, 54.5793041, -0.02, 12.30, 0.01, 139.64 +CTUN, 285, 0.34, -0.06, 0.000000, 0, 0, 10, 285, 0 +ATT, 0.00, -0.66, 0.00, -0.17, 0.00, 101.29, 100.32 +CTUN, 285, 0.34, 0.09, 0.000000, 0, 0, 11, 285, 0 +ATT, 0.00, -0.72, 0.00, -0.33, 0.00, 102.89, 100.32 +GPS, 3, 309044600, 10, 1.49, 24.2397983, 54.5793041, 0.00, 12.31, 0.01, 139.64 +CTUN, 285, 0.26, -0.02, 0.000000, 0, 0, 13, 286, 0 +ATT, 0.00, -0.55, 0.00, -0.29, 0.00, 104.20, 100.32 +DU32, 7, 393469 +CURR, 286, 323804, 1192, 0, 4752, 0.000000 +CTUN, 286, 0.26, 0.00, 0.000000, 0, 0, 12, 286, 0 +ATT, 0.00, -0.66, 0.00, -0.39, 0.00, 105.22, 100.32 +GPS, 3, 309044800, 10, 1.49, 24.2397983, 54.5793041, 0.02, 12.31, 0.03, 139.64 +CTUN, 285, 0.22, -0.02, 0.000000, 0, 0, 11, 286, 0 +ATT, 0.00, -0.60, 0.00, -0.45, 0.00, 106.19, 100.32 +CTUN, 285, 0.26, -0.01, 0.000000, 0, 0, 15, 285, 0 +ATT, 0.00, -0.48, 0.00, -0.47, 0.00, 106.71, 100.32 +GPS, 3, 309045000, 10, 1.49, 24.2397983, 54.5793041, 0.04, 12.31, 0.01, 139.64 +CTUN, 285, 0.26, -0.02, 0.000000, 0, 0, 14, 285, 0 +ATT, 0.00, -0.48, 0.00, -0.45, 0.00, 107.28, 100.32 +CTUN, 286, 0.40, -0.18, 0.000000, 0, 0, 15, 285, 0 +ATT, 0.00, -0.54, 0.00, -0.45, 0.00, 107.80, 100.32 +GPS, 3, 309045200, 10, 1.49, 24.2397983, 54.5793042, 0.05, 12.31, 0.02, 139.64 +CTUN, 285, 0.40, -0.12, 0.000000, 0, 0, 14, 286, 0 +ATT, 0.00, -0.59, 0.00, -0.37, 0.00, 108.32, 100.32 +CTUN, 286, 0.40, -0.01, 0.000000, 0, 0, 11, 286, 0 +ATT, 0.00, -0.67, 0.00, -0.32, 0.00, 108.76, 100.32 +GPS, 3, 309045400, 10, 1.49, 24.2397984, 54.5793042, 0.06, 12.31, 0.02, 139.64 +CTUN, 285, 0.25, 0.02, 0.000000, 0, 0, 11, 285, 0 +ATT, 0.00, -0.62, 0.00, -0.28, 0.00, 109.21, 100.32 +CTUN, 285, 0.25, -0.09, 0.000000, 0, 0, 11, 285, 0 +ATT, 0.00, -0.51, 0.00, -0.29, 0.00, 109.87, 100.32 +GPS, 3, 309045600, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.31, 0.02, 139.64 +CTUN, 286, 0.20, -0.24, 0.000000, 0, 0, 16, 286, 0 +ATT, 0.00, -0.55, 0.00, -0.32, 0.00, 110.26, 100.32 +DU32, 7, 393469 +CURR, 286, 326658, 1156, 0, 4793, 0.000000 +CTUN, 286, 0.20, -0.27, 0.000000, 0, 0, 16, 286, 0 +ATT, 0.00, -0.79, 0.00, -0.33, 0.00, 110.66, 100.66 +GPS, 3, 309045800, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.31, 0.02, 139.64 +CTUN, 286, 0.15, -0.14, 0.000000, 0, 0, 10, 286, 0 +ATT, 0.00, -0.81, 0.00, -0.25, 0.00, 111.60, 101.60 +CTUN, 285, 0.16, 0.01, 0.000000, 0, 0, 15, 285, 0 +ATT, 0.00, -0.47, 0.00, -0.18, 0.00, 112.94, 102.94 +GPS, 3, 309046000, 10, 1.49, 24.2397984, 54.5793042, 0.07, 12.31, 0.01, 139.64 +CTUN, 285, 0.16, 0.00, 0.000000, 0, 0, 20, 285, 0 +ATT, 0.00, -0.54, 0.00, -0.11, 0.00, 113.50, 103.50 +CTUN, 286, 0.29, -0.16, 0.000000, 0, 0, 20, 286, 0 +ATT, 0.00, -0.60, 0.00, 0.06, 0.00, 114.38, 104.38 +GPS, 3, 309046200, 10, 1.49, 24.2397984, 54.5793042, 0.09, 12.32, 0.01, 139.64 +CTUN, 286, 0.29, 0.00, 0.000000, 0, 0, 4, 285, 0 +ATT, 0.00, -0.49, 0.00, 0.09, 0.00, 115.92, 105.92 +CTUN, 285, 0.30, 0.08, 0.000000, 0, 0, -34, 286, 0 +ATT, 0.00, -0.53, 0.00, 0.06, 0.00, 117.79, 107.79 +MODE, AUTO, 470 +GPS, 3, 309046400, 10, 1.49, 24.2397984, 54.5793043, 0.03, 12.32, 0.01, 139.64 +CTUN, 285, 0.30, -0.07, 0.000000, 0, 0, -73, 286, 0 +CMD, 9, 1, 22, 1, 0, 7.62, 0.0000000, 0.0000000 +ATT, -0.43, -0.54, 0.12, 0.13, 0.00, 119.88, 109.88 +CTUN, 285, 0.30, 0.30, -0.025654, 0, 0, -109, 524, 0 +NTUN, 0.00, 0.00, 81.094238, 19.787561, 81.094238, 19.787561, 86.690399, 9.314609, -5.000000, 10.000000, -0.04, -0.65 +ATT, -0.04, 0.48, -0.65, -0.38, 0.00, 119.42, 110.88 +GPS, 3, 309046600, 10, 1.49, 24.2397984, 54.5793043, -0.16, 12.32, 0.04, 139.64 +CTUN, 286, 0.24, -0.98, -0.025654, 0, 0, -133, 620, 0 +NTUN, 0.04, 1.78, 76.497276, 20.741100, 76.497276, 20.741100, 87.782677, 1.019583, -56.514473, 28.440979, 2.28, -2.89 +DU32, 7, 393457 +CURR, 285, 330071, 1177, 0, 4752, 0.000000 +ATT, 2.28, 0.99, -2.89, 0.39, 0.00, 111.79, 110.88 +CTUN, 285, 0.30, -1.36, 0.025351, 0, 0, -169, 662, 0 +NTUN, 0.08, 1.71, 71.720436, 22.395283, 71.720436, 22.395283, 87.094124, -5.120653, -63.768402, 45.541824, 2.68, -3.69 +ATT, 2.68, 2.69, -3.69, 2.06, 0.00, 105.62, 110.88 +GPS, 3, 309046800, 10, 1.49, 24.2397983, 54.5793043, -0.57, 12.33, 0.07, 139.64 +CTUN, 285, 0.30, -1.50, 0.089945, 0, 0, -184, 702, 0 +NTUN, 0.13, 1.66, 68.257965, 24.653629, 68.257965, 24.653629, 82.325531, -10.859194, -49.974453, 61.811581, 2.01, -4.17 +ATT, 2.01, 3.07, -4.17, 1.13, 0.00, 99.77, 109.77 +CTUN, 285, 0.30, -1.38, 0.149017, 0, 0, -169, 684, 0 +NTUN, 0.16, 1.59, 64.907799, 27.517967, 64.907799, 27.517967, 91.781113, -16.360638, -62.169964, 77.359779, 2.93, -4.98 +GPS, 3, 309047000, 10, 1.49, 24.2397984, 54.5793041, -1.01, 12.34, 0.14, 139.64 +ATT, 2.93, 4.03, -4.98, 0.70, 0.00, 93.83, 103.83 +CTUN, 285, 0.26, -1.25, 0.224606, 0, 0, -165, 734, 0 +NTUN, 0.20, 1.53, 60.097557, 30.371601, 60.097557, 30.371601, 114.825450, -16.639885, -108.102420, 83.536339, 6.07, -5.13 +CTUN, 286, 0.26, -1.11, 0.313335, 0, 0, -128, 714, 0 +ATT, 6.07, 4.23, -5.13, 1.75, 0.00, 85.53, 95.53 +NTUN, 0.25, 1.51, 53.183434, 33.436726, 53.183434, 33.436726, 123.999930, -23.988001, -147.456670, 98.347763, 9.02, -4.91 +GPS, 3, 309047200, 10, 1.49, 24.2397985, 54.5793037, -1.30, 12.49, 0.21, 186.61 +CTUN, 285, 0.24, -1.23, 0.430059, 0, 0, -104, 717, 0 +NTUN, 0.32, 1.51, 45.900955, 37.252762, 45.900955, 37.252762, 125.704120, -34.892059, -164.824780, 125.160360, 11.03, -4.55 +ATT, 11.03, 5.54, -4.55, 3.96, 0.00, 74.10, 84.10 +CTUN, 286, 0.26, -1.32, 0.571672, 0, 1, -84, 734, 0 +NTUN, 0.39, 1.49, 38.896820, 42.060459, 38.896820, 42.060459, 120.331630, -48.998432, -168.041350, 158.076970, 12.46, -4.43 +ATT, 12.46, 6.34, -4.43, 5.43, 0.00, 65.05, 75.05 +GPS, 3, 309047400, 10, 1.49, 24.2397981, 54.5793033, -1.46, 12.77, 0.25, 208.02 +CTUN, 286, 0.26, -1.35, 0.738692, 0, 1, -58, 733, 0 +NTUN, 0.46, 1.46, 33.406029, 48.125500, 33.406029, 48.125500, 108.785800, -64.635132, -150.364270, 197.049900, 13.36, -4.73 +ATT, 13.36, 7.36, -4.73, 5.58, 0.00, 53.40, 63.40 +CTUN, 285, 0.53, -0.66, 0.939282, 0, 1, -29, 739, 0 +NTUN, 0.52, 1.42, 29.587189, 55.360962, 29.587189, 55.360962, 98.446404, -76.764160, -130.188400, 235.354610, 14.54, -4.90 +ATT, 14.54, 8.29, -4.90, 4.97, 0.00, 44.67, 54.67 +GPS, 3, 309047600, 10, 1.49, 24.2397975, 54.5793027, -1.49, 13.08, 0.48, 223.20 +CTUN, 285, 0.53, -0.32, 1.155007, 0, 1, -15, 736, 0 +NTUN, 0.58, 1.36, 27.689941, 63.225525, 27.689941, 63.225525, 86.188568, -84.438812, -103.972470, 264.645630, 15.33, -5.19 +DU32, 7, 393457 +CURR, 285, 336519, 1144, 0, 4752, 0.000000 +ATT, 15.33, 9.66, -5.19, 5.39, 0.00, 36.81, 46.81 +CTUN, 285, 0.90, 0.00, 1.384182, 0, 2, -7, 751, 0 +NTUN, 0.64, 1.30, 27.449661, 71.545242, 27.449661, 71.545242, 69.944626, -91.818504, -73.379013, 292.373440, 16.03, -6.00 +ATT, 16.03, 10.41, -6.00, 5.81, 0.00, 31.84, 41.84 +GPS, 3, 309047800, 10, 1.49, 24.2397961, 54.5793024, -1.35, 13.52, 0.72, 201.34 +CTUN, 285, 0.90, 0.48, 1.629918, 0, 3, 7, 763, 0 +NTUN, 0.69, 1.23, 30.077858, 79.550003, 30.077858, 79.550003, 51.432121, -98.459473, -24.718033, 314.047610, 16.20, -7.63 +ATT, 16.20, 11.36, -7.63, 4.13, 0.00, 25.66, 35.66 +CTUN, 286, 1.35, 1.10, 1.879918, 0, 3, 22, 767, 0 +NTUN, 0.74, 1.16, 35.114761, 87.650192, 35.114761, 87.650192, 36.534496, -104.780070, 19.369034, 338.001890, 16.98, -9.07 +GPS, 3, 309048000, 10, 1.49, 24.2397942, 54.5793020, -1.09, 14.07, 0.95, 192.75 +ATT, 16.98, 13.34, -9.07, 2.00, 0.00, 21.01, 31.01 +CTUN, 285, 1.35, 1.49, 2.129918, 0, 4, 23, 768, 0 +NTUN, 0.79, 1.08, 41.620590, 95.589722, 41.620590, 95.589722, 26.115559, -102.799740, 49.414146, 351.609190, 17.64, -9.79 +CTUN, 285, 1.61, 1.91, 2.382418, 0, 4, 29, 756, 0 +ATT, 17.64, 14.98, -9.79, 0.91, 0.00, 17.92, 27.92 +NTUN, 0.84, 1.00, 49.996918, 102.025510, 49.996918, 102.025510, 13.791585, -96.829689, 91.763275, 347.357850, 17.17, -11.13 +GPS, 3, 309048200, 10, 1.49, 24.2397921, 54.5793016, -0.71, 14.56, 1.21, 191.16 +CTUN, 286, 1.61, 2.05, 2.632418, 0, 4, 39, 764, 0 +NTUN, 0.90, 0.92, 59.942490, 107.232350, 59.942490, 107.232350, 2.932265, -91.686577, 131.455720, 345.068420, 16.81, -12.65 +ATT, 16.81, 14.86, -12.65, 0.10, 0.00, 15.58, 25.58 +CTUN, 285, 2.24, 2.43, 2.882418, 0, 5, 41, 790, 0 +NTUN, 0.96, 0.84, 71.164673, 111.675640, 71.164673, 111.675640, -3.660860, -91.860573, 164.110720, 351.993040, 17.05, -14.04 +ATT, 17.05, 15.08, -14.04, -1.65, 0.00, 14.01, 24.01 +GPS, 3, 309048400, 10, 1.49, 24.2397895, 54.5793018, -0.30, 15.09, 1.38, 181.95 +CTUN, 285, 2.24, 2.95, 3.134918, 0, 5, 44, 769, 0 +NTUN, 1.03, 0.76, 83.282387, 114.827000, 83.282387, 114.827000, -9.442659, -85.577728, 196.177140, 346.513520, 16.74, -15.22 +ATT, 16.74, 16.47, -15.22, -3.63, 0.00, 12.04, 22.04 +CTUN, 286, 2.62, 3.24, 3.384918, 0, 6, 58, 761, 0 +NTUN, 1.11, 0.69, 95.901382, 116.636470, 95.899284, 116.633920, -11.150739, -78.515327, 222.168980, 338.069210, 16.39, -16.07 +ATT, 16.39, 16.57, -16.07, -5.29, 0.00, 10.91, 20.91 +GPS, 3, 309048600, 10, 1.49, 24.2397869, 54.5793025, 0.19, 15.60, 1.47, 173.68 +CTUN, 285, 2.52, 3.53, 3.634918, 0, 8, 56, 794, 0 +NTUN, 1.19, 0.62, 108.592900, 116.586930, 108.406680, 116.387000, -12.061378, -69.933739, 238.835650, 318.555270, 15.24, -16.66 +ATT, 15.24, 17.02, -16.66, -7.41, 0.00, 10.48, 20.48 +DU32, 7, 393457 +CURR, 286, 343452, 1183, 0, 4772, 0.000000 +CTUN, 286, 2.55, 3.70, 3.887418, 0, 8, 49, 791, 0 +NTUN, 1.27, 0.56, 121.250660, 114.949410, 120.615560, 114.347330, -9.245070, -58.437130, 251.088780, 294.603270, 13.95, -16.95 +ATT, 13.95, 16.75, -16.95, -7.85, 0.00, 9.43, 19.43 +GPS, 3, 309048800, 9, 1.96, 24.2397845, 54.5793038, 0.68, 16.16, 1.50, 161.11 +CTUN, 285, 2.52, 4.15, 4.137418, 0, 7, 60, 784, 0 +NTUN, 1.35, 0.51, 133.293610, 111.337370, 132.049300, 110.298010, -6.110949, -49.670006, 259.337400, 269.506840, 12.82, -16.92 +ATT, 12.82, 15.01, -16.92, -9.42, 0.00, 9.00, 18.94 +CTUN, 286, 2.52, 4.47, 4.387418, 0, 8, 49, 806, 0 +NTUN, 1.42, 0.45, 144.720260, 106.683640, 142.719560, 105.208780, -1.748475, -50.415558, 263.646120, 263.611540, 12.36, -17.13 +GPS, 3, 309049000, 10, 1.49, 24.2397823, 54.5793060, 1.19, 16.70, 1.64, 146.37 +ATT, 12.36, 14.81, -17.13, -10.80, 0.00, 9.23, 18.94 +CTUN, 285, 1.87, 4.73, 4.639918, 0, 7, 52, 779, 0 +NTUN, 1.51, 0.40, 154.978990, 100.468230, 152.219960, 98.679634, 8.273634, -43.072510, 260.003970, 241.708560, 11.16, -16.75 +CTUN, 285, 2.52, 4.97, 4.889918, 0, 8, 62, 785, 0 +ATT, 11.16, 14.25, -16.75, -11.73, 0.00, 8.97, 18.94 +NTUN, 1.57, 0.35, 163.969390, 92.971588, 160.513900, 91.012306, 20.060749, -40.640942, 251.939450, 227.326720, 10.47, -16.17 +GPS, 3, 309049200, 9, 1.96, 24.2397805, 54.5793090, 1.73, 17.24, 1.84, 134.92 +CTUN, 285, 2.52, 5.37, 5.139918, 0, 9, 60, 813, 0 +NTUN, 1.64, 0.30, 171.508470, 83.943222, 167.518260, 81.990257, 29.737247, -39.001118, 242.043640, 208.779510, 9.22, -15.65 +ATT, 9.22, 12.68, -15.65, -12.74, 0.00, 10.15, 18.94 +CTUN, 286, 3.31, 5.76, 5.389918, 0, 7, 57, 788, 0 +NTUN, 1.68, 0.25, 177.794130, 73.822968, 173.405010, 72.000534, 40.376240, -36.411816, 233.867490, 192.102770, 8.18, -15.16 +ATT, 8.18, 11.38, -15.16, -12.61, 0.00, 10.88, 18.94 +GPS, 3, 309049400, 10, 1.49, 24.2397794, 54.5793125, 2.28, 17.80, 1.89, 121.71 +CTUN, 286, 3.31, 6.42, 5.639918, 0, 6, 62, 779, 0 +NTUN, 1.72, 0.21, 182.034240, 62.707367, 177.536940, 61.158138, 53.130020, -38.380424, 212.910170, 180.649550, 7.70, -13.96 +ATT, 7.70, 9.88, -13.96, -13.06, 0.00, 11.46, 18.94 +CTUN, 285, 3.79, 6.63, 5.892418, 0, 5, 72, 756, 0 +NTUN, 1.73, 0.17, 184.435670, 50.683601, 180.090710, 49.489594, 68.531563, -39.680088, 190.537720, 165.314540, 6.88, -12.69 +ATT, 6.88, 8.85, -12.69, -13.31, 0.00, 12.61, 18.94 +GPS, 3, 309049600, 10, 1.49, 24.2397790, 54.5793166, 2.89, 18.33, 2.06, 109.24 +CTUN, 286, 3.63, 6.99, 6.142417, 0, 6, 61, 813, 0 +NTUN, 1.74, 0.13, 184.956880, 37.782150, 181.012880, 36.976490, 81.721130, -48.648415, 167.221650, 157.868960, 6.34, -11.57 +ATT, 6.34, 7.53, -11.57, -12.55, 0.00, 14.81, 18.94 +CTUN, 286, 3.79, 7.25, 6.392417, 0, 4, 64, 783, 0 +NTUN, 1.74, 0.08, 183.641430, 24.731028, 180.278490, 24.278141, 91.713058, -51.257145, 143.728810, 150.273770, 5.96, -10.39 +DU32, 7, 393457 +CURR, 285, 351310, 1179, 0, 4752, 0.000000 +ATT, 5.96, 6.23, -10.39, -10.83, 0.00, 16.52, 18.94 +GPS, 3, 309049800, 10, 1.49, 24.2397793, 54.5793209, 3.50, 18.85, 2.21, 96.64 +CTUN, 285, 3.79, 7.63, 6.644917, 0, 3, 68, 775, 0 +NTUN, 1.73, 0.04, 180.705690, 10.470793, 178.034320, 10.316003, 99.046005, -52.487785, 122.558290, 127.378620, 4.85, -8.99 +ATT, 4.85, 4.82, -8.99, -9.81, 0.00, 18.47, 18.94 +CTUN, 285, 4.27, 7.83, 6.894917, 0, 2, 56, 778, 0 +NTUN, 1.71, 0.00, 176.326100, -3.759577, 174.344590, -3.717327, 109.876630, -67.122498, 97.468048, 132.056140, 5.28, -7.88 +ATT, 5.28, 4.00, -7.88, -9.38, 0.00, 20.47, 18.94 +GPS, 3, 309050000, 10, 1.49, 24.2397803, 54.5793254, 4.10, 19.44, 2.35, 86.15 +CTUN, 286, 3.79, 8.10, 7.147417, 0, 2, 56, 785, 0 +NTUN, 1.69, 3.55, 170.179900, -17.875822, 168.879170, -17.739191, 120.898000, -75.459068, 65.345764, 127.781360, 5.47, -6.25 +ATT, 5.47, 2.92, -6.25, -7.72, 0.00, 22.18, 18.94 +CTUN, 285, 4.27, 8.13, 7.397417, 0, 1, 66, 756, 0 +NTUN, 1.67, 3.50, 163.092900, -32.429482, 162.308820, -32.273575, 128.235030, -80.497658, 42.296570, 115.656160, 5.25, -4.84 +GPS, 3, 309050200, 10, 1.49, 24.2397820, 54.5793297, 4.69, 20.00, 2.40, 77.49 +ATT, 5.25, 3.23, -4.84, -5.64, 0.00, 21.90, 18.94 +CTUN, 285, 4.27, 8.56, 7.620000, 0, 0, 76, 752, 0 +NTUN, 1.64, 3.45, 156.880620, -46.324120, 156.339290, -46.164280, 130.711730, -90.719246, 41.304718, 120.092960, 5.57, -4.84 +CTUN, 286, 4.81, 8.11, 7.620000, 0, 0, 70, 743, 0 +ATT, 5.57, 4.45, -4.84, -4.62, 0.00, 21.26, 18.94 +NTUN, 1.62, 3.40, 149.998570, -60.341682, 149.606580, -60.183998, 131.077000, -97.067993, 28.339493, 114.190920, 5.59, -3.93 +GPS, 3, 309050400, 10, 1.49, 24.2397841, 54.5793340, 5.25, 20.58, 2.47, 70.13 +CTUN, 286, 4.81, 8.30, 7.620000, 0, 0, 63, 761, 0 +NTUN, 1.60, 3.34, 142.377200, -74.685249, 142.056990, -74.517281, 129.687030, -99.832222, 13.504089, 99.667175, 5.16, -2.74 +ATT, 5.16, 4.25, -2.74, -3.76, 0.00, 20.03, 18.94 +CTUN, 285, 5.52, 8.48, 7.620000, 0, 0, 76, 727, 0 +NTUN, 1.60, 3.28, 134.428440, -89.179955, 134.097080, -88.960129, 131.283400, -108.349800, -0.599152, 93.571518, 5.15, -1.74 +ATT, 5.15, 2.89, -1.74, -3.35, 0.00, 18.96, 18.94 +GPS, 3, 309050600, 10, 1.49, 24.2397866, 54.5793381, 5.75, 21.18, 2.51, 63.74 +CTUN, 286, 5.52, 9.28, 7.620000, 0, 0, 76, 750, 0 +NTUN, 1.62, 3.22, 125.551550, -103.545660, 125.166140, -103.227800, 130.496900, -117.798150, -17.309387, 91.323303, 5.35, -0.78 +ATT, 5.35, 4.43, -0.78, -2.51, 0.00, 19.53, 18.94 +CMD, 9, 2, 16, 1, 0, 7.62, 24.2398304, 54.5793472 +CTUN, 285, 5.52, 9.23, 7.620000, 0, 0, 60, 749, 0 +NTUN, 0.00, 0.35, 118.077210, -115.403990, 117.581910, -114.919900, 126.198590, -122.502140, -6.091370, 111.236630, 6.18, -1.95 +ATT, 6.18, 3.90, -1.95, -1.27, 0.00, 20.72, 23.14 +GPS, 3, 309050800, 10, 1.49, 24.2397892, 54.5793419, 6.28, 21.78, 2.44, 58.66 +CTUN, 285, 3.36, 9.36, 7.620000, 0, 0, 65, 716, 0 +NTUN, 5.11, 0.34, 111.996950, -124.590060, 111.382190, -123.906170, 123.931060, -133.739040, 2.616611, 141.027070, 7.58, -3.11 +DU32, 7, 393457 +CURR, 286, 358864, 1156, 0, 4772, 0.000000 +ATT, 7.58, 3.35, -3.11, 0.59, 0.00, 21.47, 30.34 +CTUN, 285, 4.73, 9.60, 7.620000, 0, 0, 70, 713, 0 +NTUN, 4.95, 0.34, 107.554310, -130.587540, 106.861050, -129.745800, 120.969550, -142.458040, 15.788666, 174.603620, 8.99, -4.75 +ATT, 8.99, 5.03, -4.75, 0.78, 0.00, 24.40, 35.51 +GPS, 3, 309051000, 10, 1.49, 24.2397920, 54.5793453, 6.78, 22.37, 2.32, 54.13 +CTUN, 286, 3.54, 9.85, 7.620000, 0, 0, 65, 720, 0 +NTUN, 4.80, 0.33, 103.475020, -135.680760, 102.715610, -134.684970, 114.861750, -145.972700, 21.545532, 183.608370, 8.93, -5.94 +ATT, 8.93, 7.06, -5.94, 0.67, 0.00, 30.23, 35.51 +CTUN, 285, 3.54, 9.62, 7.620000, 0, 0, 63, 692, 0 +NTUN, 4.64, 0.32, 99.447067, -141.089360, 98.589882, -139.873230, 105.202670, -141.619280, 27.151241, 171.631060, 7.69, -6.53 +GPS, 3, 309051200, 10, 1.49, 24.2397946, 54.5793484, 7.25, 22.96, 2.16, 50.83 +PM, 0, 0, 51, 30, 1000, 11596, 7, 0 +ATT, 7.69, 7.06, -6.53, 0.61, 0.00, 33.53, 35.51 +CTUN, 285, 2.37, 9.73, 7.620000, 0, 0, 58, 696, 0 +NTUN, 4.48, 0.32, 95.609100, -147.473510, 94.577042, -145.881590, 95.208153, -138.006180, 33.871597, 154.916380, 6.37, -6.66 +CTUN, 286, 2.37, 9.85, 7.620000, 0, 0, 34, 712, 0 +ATT, 6.37, 7.29, -6.66, -0.13, 0.00, 34.51, 35.51 +NTUN, 4.33, 0.31, 92.080536, -154.426800, 90.807335, -152.291530, 91.359589, -137.773420, 36.302933, 142.900570, 5.65, -6.45 +GPS, 3, 309051400, 10, 1.49, 24.2397970, 54.5793513, 7.62, 23.53, 2.00, 49.53 +CTUN, 286, 2.05, 10.36, 7.620000, 0, 0, 31, 698, 0 +NTUN, 4.18, 0.30, 88.783951, -161.621980, 87.225197, -158.784420, 85.650322, -130.321490, 40.178619, 126.071110, 4.79, -6.03 +ATT, 4.79, 6.08, -6.03, -0.75, 0.00, 33.69, 35.51 +CTUN, 285, 2.08, 10.66, 7.620000, 0, 0, 30, 698, 0 +NTUN, 4.02, 0.28, 85.384933, -169.494140, 83.487610, -165.727840, 84.039803, -131.738390, 37.624130, 115.565800, 4.45, -5.50 +ATT, 4.45, 5.02, -5.50, -0.25, 0.00, 32.99, 35.51 +GPS, 3, 309051600, 10, 1.49, 24.2397992, 54.5793542, 7.99, 24.09, 1.93, 50.63 +CTUN, 285, 2.08, 10.93, 7.620000, 0, 0, 13, 720, 0 +NTUN, 3.87, 0.27, 81.363876, -176.942380, 79.186539, -172.207320, 87.176407, -136.760180, 24.415138, 116.846760, 4.90, -4.93 +ATT, 4.90, 4.60, -4.93, -0.96, 0.00, 33.51, 35.51 +CTUN, 286, 2.14, 10.77, 7.620000, 0, 0, 1, 689, 0 +NTUN, 3.72, 0.26, 76.977051, -184.242400, 74.556793, -178.449580, 86.566475, -134.617750, 15.702545, 108.577360, 4.77, -4.25 +ATT, 4.77, 4.24, -4.25, -0.24, 0.00, 33.33, 35.51 +GPS, 3, 309051800, 10, 1.49, 24.2398011, 54.5793571, 8.34, 24.59, 1.83, 52.77 +CTUN, 285, 2.14, 10.85, 7.620000, 0, 0, 12, 679, 0 +NTUN, 3.56, 0.24, 72.722839, -191.810590, 70.046951, -184.752790, 83.196503, -133.308460, 14.901581, 96.967926, 4.27, -3.80 +DU32, 7, 393457 +CURR, 285, 365167, 1143, 0, 4752, 0.000000 +ATT, 4.27, 3.52, -3.80, 0.83, 0.00, 32.96, 35.51 +CTUN, 285, 2.78, 11.08, 7.620000, 0, 0, 4, 701, 0 +NTUN, 3.42, 0.23, 68.414055, -199.507510, 65.498856, -191.006260, 81.508934, -138.431960, 10.969353, 95.084518, 4.29, -3.56 +ATT, 4.29, 3.21, -3.56, 0.80, 0.00, 33.02, 35.51 +GPS, 3, 309052000, 10, 1.49, 24.2398029, 54.5793599, 8.65, 25.09, 1.73, 54.13 +CTUN, 286, 2.71, 11.38, 7.620000, 0, 0, -4, 692, 0 +NTUN, 3.27, 0.21, 64.098595, -207.008450, 60.986355, -196.957380, 77.385841, -137.106080, 9.874992, 87.488739, 3.96, -3.26 +ATT, 3.96, 3.42, -3.26, 1.16, 0.00, 32.66, 35.51 +CTUN, 286, 2.78, 11.31, 7.620000, 0, 0, -5, 669, 0 +NTUN, 3.14, 0.19, 59.885651, -214.622890, 56.597240, -202.837630, 76.654449, -140.135420, 6.108856, 82.197510, 3.84, -2.89 +GPS, 3, 309052200, 10, 1.49, 24.2398046, 54.5793624, 8.95, 25.59, 1.59, 54.47 +ATT, 3.84, 3.18, -2.89, 1.69, 0.00, 32.99, 35.51 +CTUN, 285, 2.71, 11.99, 7.620000, 0, 0, -6, 681, 0 +NTUN, 3.01, 0.17, 55.982849, -222.152270, 52.540356, -208.491710, 70.946762, -138.086120, 10.431152, 72.459167, 3.21, -2.80 +ATT, 3.21, 2.64, -2.80, 1.92, 0.00, 32.65, 35.51 +CTUN, 285, 2.71, 12.02, 7.620000, 0, 0, -19, 701, 0 +NTUN, 2.89, 0.15, 52.624634, -229.783870, 49.020973, -214.048600, 64.603691, -135.155760, 19.154629, 61.981342, 2.45, -2.88 +GPS, 3, 309052400, 10, 1.49, 24.2398061, 54.5793647, 9.24, 26.06, 1.43, 54.99 +ATT, 2.45, 2.26, -2.88, 2.63, 0.00, 31.54, 35.51 +CTUN, 286, 2.66, 12.29, 7.620000, 0, 0, -20, 672, 0 +NTUN, 2.78, 0.13, 49.464218, -237.521120, 45.718250, -219.533430, 61.778397, -139.410310, 18.972771, 56.151672, 2.21, -2.65 +CTUN, 286, 2.66, 12.64, 7.620000, 0, 0, -28, 683, 0 +ATT, 2.21, 1.60, -2.65, 2.86, 0.00, 32.18, 35.51 +NTUN, 2.67, 0.10, 46.370911, -245.006520, 42.530926, -224.717470, 56.825630, -141.534590, 21.126755, 52.159637, 1.91, -2.67 +GPS, 3, 309052600, 10, 1.49, 24.2398073, 54.5793668, 9.55, 26.54, 1.24, 56.60 +CTUN, 286, 2.26, 12.49, 7.620000, 0, 0, -30, 685, 0 +NTUN, 2.59, 0.08, 43.495590, -252.015320, 39.603512, -229.464460, 55.287273, -147.105680, 22.015705, 54.000061, 1.94, -2.79 +ATT, 1.94, 1.66, -2.79, 2.40, 0.00, 32.96, 35.51 +CTUN, 285, 2.66, 12.54, 7.620000, 0, 0, -34, 677, 0 +NTUN, 2.51, 0.05, 40.533081, -258.967410, 36.637856, -234.080660, 52.808136, -154.102140, 20.343437, 53.838043, 2.01, -2.68 +ATT, 2.01, 1.66, -2.68, 3.73, 0.00, 32.24, 35.51 +GPS, 3, 309052800, 10, 1.49, 24.2398084, 54.5793684, 9.86, 27.03, 1.06, 54.41 +CTUN, 286, 2.66, 12.63, 7.620000, 0, 0, -34, 670, 0 +NTUN, 2.44, 0.03, 37.745117, -265.253690, 33.892376, -238.178570, 43.375248, -158.213530, 28.817036, 55.426579, 1.85, -3.13 +DU32, 7, 393457 +CURR, 285, 371308, 1139, 0, 4712, 0.000000 +ATT, 1.85, 0.76, -3.13, 3.89, 0.00, 31.97, 35.51 +CTUN, 286, 2.66, 13.20, 7.620000, 0, 0, -44, 691, 0 +NTUN, 2.38, 0.01, 35.552399, -271.281740, 31.717749, -242.021530, 36.449539, -158.014860, 39.253727, 48.570435, 1.20, -3.44 +ATT, 1.20, 1.71, -3.44, 2.52, 0.00, 31.66, 35.51 +GPS, 3, 309053000, 10, 1.49, 24.2398093, 54.5793696, 10.12, 27.52, 0.77, 52.84 +CTUN, 286, 2.66, 13.39, 7.620000, 0, 0, -57, 683, 0 +NTUN, 2.34, 3.58, 33.372986, -276.989560, 29.591713, -245.605710, 35.341824, -166.483810, 38.739643, 52.158173, 1.44, -3.50 +ATT, 1.44, 1.37, -3.50, 3.39, 0.00, 30.40, 35.51 +CTUN, 285, 2.66, 13.56, 7.620000, 0, 0, -62, 694, 0 +NTUN, 2.30, 3.56, 31.230484, -282.149960, 27.539520, -248.804170, 31.475275, -170.937770, 41.681259, 54.332123, 1.50, -3.70 +ATT, 1.50, 0.53, -3.70, 3.68, 0.00, 30.41, 35.51 +GPS, 3, 309053200, 10, 1.49, 24.2398100, 54.5793704, 10.39, 27.97, 0.57, 51.96 +CTUN, 285, 2.43, 13.68, 7.620000, 0, 0, -64, 703, 0 +NTUN, 2.27, 3.55, 29.348816, -286.875670, 25.749353, -251.692020, 23.832811, -176.349590, 48.098331, 55.121521, 1.34, -4.04 +ATT, 1.34, 1.72, -4.04, 2.37, 0.00, 30.45, 35.51 +CTUN, 286, 2.54, 13.92, 7.620000, 0, 0, -78, 714, 0 +NTUN, 2.24, 3.53, 27.589935, -291.222660, 24.093622, -254.317700, 19.442347, -181.306290, 52.442688, 56.743134, 1.32, -4.30 +GPS, 3, 309053400, 10, 1.49, 24.2398103, 54.5793708, 10.64, 28.42, 0.27, 50.34 +ATT, 1.32, 1.27, -4.30, 1.51, 0.00, 29.41, 35.51 +CTUN, 286, 2.43, 14.99, 7.620000, 0, 0, -81, 706, 0 +NTUN, 2.23, 3.52, 26.289154, -294.891570, 22.867151, -256.506160, 17.337414, -183.764140, 57.856724, 58.332069, 1.31, -4.60 +CTUN, 286, 2.43, 15.37, 7.620000, 0, 0, -96, 728, 0 +ATT, 1.31, 1.38, -4.60, 1.56, 0.00, 29.58, 35.51 +NTUN, 2.22, 3.51, 25.201599, -298.123900, 21.844954, -258.416260, 14.001935, -184.039470, 61.778023, 54.899048, 1.00, -4.71 +GPS, 3, 309053600, 10, 1.49, 24.2398106, 54.5793707, 10.96, 28.81, 0.09, 50.34 +CTUN, 286, 1.80, 15.37, 7.620000, 0, 0, -107, 768, 0 +NTUN, 2.21, 3.49, 24.276550, -301.004210, 20.977922, -260.104610, 12.868859, -190.502780, 65.329689, 59.116455, 1.12, -5.00 +ATT, 1.12, 1.03, -5.00, 1.32, 0.00, 29.37, 35.51 +CTUN, 285, 2.43, 15.25, 7.620000, 0, 0, -98, 720, 0 +NTUN, 2.20, 3.49, 23.248505, -302.966250, 20.047884, -261.256900, 9.118357, -196.911390, 66.791702, 66.591263, 1.62, -5.24 +ATT, 1.62, 0.52, -5.24, 1.62, 0.00, 27.48, 35.51 +GPS, 3, 309053800, 10, 1.49, 24.2398107, 54.5793702, 11.27, 29.24, 0.28, 339.99 +CTUN, 285, 2.43, 15.76, 7.620000, 0, 0, -98, 727, 0 +NTUN, 2.20, 3.48, 22.476013, -303.479680, 19.372015, -261.568330, 7.287034, -200.387310, 72.173042, 74.854225, 2.01, -5.71 +DU32, 7, 393457 +CURR, 286, 377689, 1174, 0, 4772, 0.000000 +ATT, 2.01, 0.77, -5.71, 0.14, 0.00, 26.52, 35.51 +CTUN, 286, 4.05, 16.22, 7.620000, 0, 0, -107, 730, 0 +NTUN, 2.19, 3.49, 21.631378, -302.910830, 18.656994, -261.259610, 11.586437, -205.900300, 66.849792, 84.087158, 2.64, -5.67 +ATT, 2.64, 1.88, -5.67, -0.79, 0.00, 26.51, 35.51 +GPS, 3, 309054000, 10, 1.49, 24.2398107, 54.5793693, 11.61, 29.64, 0.49, 287.78 +CTUN, 286, 3.53, 16.34, 7.620000, 0, 0, -104, 743, 0 +NTUN, 2.18, 3.49, 20.759460, -301.518070, 17.933746, -260.476350, 13.129594, -207.173140, 63.839134, 87.755089, 2.92, -5.60 +ATT, 2.92, 1.90, -5.60, 0.24, 0.00, 26.88, 35.51 +CTUN, 286, 3.53, 16.42, 7.620000, 0, 0, -97, 732, 0 +NTUN, 2.17, 3.49, 19.996368, -299.394840, 17.316172, -259.265720, 10.551203, -212.283420, 67.885399, 96.986458, 3.23, -6.08 +ATT, 3.23, 1.83, -6.08, 0.72, 0.00, 27.59, 35.51 +GPS, 3, 309054200, 10, 1.49, 24.2398109, 54.5793678, 11.96, 30.09, 0.75, 281.50 +CTUN, 286, 3.02, 16.69, 7.620000, 0, 0, -109, 743, 0 +NTUN, 2.15, 3.50, 19.380493, -296.125180, 16.844664, -257.378850, 7.282642, -212.158310, 72.237289, 103.059310, 3.33, -6.52 +ATT, 3.33, 2.74, -6.52, -0.17, 0.00, 27.57, 35.51 +CTUN, 286, 3.53, 16.80, 7.620000, 0, 0, -110, 727, 0 +NTUN, 2.14, 3.51, 18.980225, -292.257260, 16.568546, -255.122270, 5.566997, -212.008590, 77.292969, 105.123300, 3.37, -6.80 +GPS, 3, 309054400, 10, 1.49, 24.2398110, 54.5793659, 12.27, 30.52, 0.97, 277.03 +ATT, 3.37, 3.62, -6.80, -1.07, 0.00, 26.61, 35.51 +CTUN, 285, 3.53, 17.36, 7.620000, 0, 0, -101, 737, 0 +NTUN, 2.13, 3.52, 18.691498, -287.556460, 16.402964, -252.348830, 8.734666, -213.659070, 74.327446, 115.014520, 4.07, -6.84 +CTUN, 285, 3.75, 17.57, 7.620000, 0, 0, -118, 758, 0 +ATT, 4.07, 3.70, -6.84, -1.74, 0.00, 26.76, 35.51 +NTUN, 2.12, 3.53, 18.338257, -282.400390, 16.186998, -249.272020, 8.029769, -211.866460, 74.840347, 116.768130, 4.11, -6.94 +GPS, 3, 309054600, 10, 1.49, 24.2398112, 54.5793638, 12.63, 30.98, 1.06, 276.01 +CTUN, 286, 3.75, 17.34, 7.620000, 0, 0, -118, 729, 0 +NTUN, 2.11, 3.55, 17.605804, -276.282780, 15.649113, -245.576970, 9.509535, -213.880130, 70.674400, 126.584690, 4.67, -7.01 +ATT, 4.67, 3.64, -7.01, -1.14, 0.00, 27.21, 35.51 +CTUN, 286, 5.38, 17.86, 7.620000, 0, 0, -115, 742, 0 +NTUN, 2.10, 3.57, 16.749176, -269.348210, 15.006269, -241.320020, 9.682804, -218.364720, 68.571556, 140.569430, 5.39, -7.32 +ATT, 5.39, 3.34, -7.32, -1.20, 0.00, 27.85, 35.51 +GPS, 3, 309054800, 10, 1.49, 24.2398114, 54.5793614, 12.98, 31.43, 1.20, 276.02 +CTUN, 286, 5.38, 18.12, 7.620000, 0, 0, -117, 734, 0 +NTUN, 2.09, 3.59, 15.729584, -261.101620, 14.226836, -236.156940, 12.387700, -222.340330, 63.282848, 157.119660, 6.16, -7.67 +DU32, 7, 393457 +CURR, 285, 384332, 1130, 0, 4752, 0.000000 +ATT, 6.16, 4.23, -7.67, -1.84, 0.00, 29.95, 35.51 +CTUN, 286, 5.52, 18.22, 7.620000, 0, 0, -114, 721, 0 +NTUN, 2.08, 0.01, 14.564667, -252.272580, 13.307709, -230.500990, 13.826535, -223.153120, 60.808723, 168.559450, 6.58, -8.06 +ATT, 6.58, 4.48, -8.06, -1.48, 0.00, 31.29, 35.51 +GPS, 3, 309055000, 10, 1.49, 24.2398116, 54.5793588, 13.35, 31.88, 1.36, 275.71 +CTUN, 286, 5.38, 18.07, 7.620000, 0, 0, -118, 720, 0 +NTUN, 2.07, 0.04, 13.444611, -242.597840, 12.421443, -224.135530, 10.638435, -224.001620, 62.137344, 182.654630, 7.06, -8.68 +ATT, 7.06, 5.08, -8.68, -1.28, 0.00, 32.11, 35.51 +CTUN, 285, 5.38, 18.30, 7.620000, 0, 0, -109, 698, 0 +NTUN, 2.07, 0.06, 12.457886, -232.465640, 11.643294, -217.265270, 6.692154, -220.026090, 66.295555, 189.022310, 7.26, -9.06 +ATT, 7.26, 5.23, -9.06, -1.45, 0.00, 31.71, 35.51 +GPS, 3, 309055200, 10, 1.49, 24.2398119, 54.5793559, 13.73, 32.35, 1.45, 276.07 +CTUN, 285, 5.20, 18.54, 7.620000, 0, 0, -103, 689, 0 +NTUN, 2.08, 0.09, 11.718170, -221.904540, 11.082142, -209.860200, 7.914550, -221.911560, 67.388474, 206.050750, 8.13, -9.56 +ATT, 8.13, 6.57, -9.56, -3.33, 0.00, 32.17, 35.51 +CTUN, 285, 5.20, 18.97, 7.620000, 0, 0, -119, 711, 0 +NTUN, 2.09, 0.12, 10.786407, -210.829530, 10.324662, -201.804320, 9.698957, -219.539170, 62.425201, 218.558780, 8.79, -9.77 +GPS, 3, 309055400, 10, 1.49, 24.2398121, 54.5793528, 14.05, 32.82, 1.54, 274.83 +ATT, 8.79, 7.53, -9.77, -3.37, 0.00, 31.75, 35.51 +CTUN, 285, 3.08, 19.29, 7.620000, 0, 1, -130, 715, 0 +NTUN, 2.11, 0.15, 9.754669, -199.735660, 9.445167, -193.398300, 8.383429, -210.777730, 63.292122, 221.227940, 8.98, -9.82 +CTUN, 285, 3.47, 19.18, 7.620000, 0, 0, -124, 694, 0 +ATT, 8.98, 7.46, -9.82, -1.81, 0.00, 31.08, 35.51 +NTUN, 2.13, 0.18, 8.872437, -188.833070, 8.681162, -184.762150, 5.561554, -207.254230, 66.359955, 230.361540, 9.42, -10.16 +GPS, 3, 309055600, 10, 1.49, 24.2398123, 54.5793497, 14.39, 33.25, 1.57, 274.38 +CTUN, 286, 3.47, 19.10, 7.620000, 0, 0, -132, 707, 0 +NTUN, 2.16, 0.21, 8.101959, -177.468690, 8.003202, -175.305470, 5.962768, -208.387160, 66.220406, 251.566800, 10.47, -10.76 +ATT, 10.47, 8.42, -10.76, -2.50, 0.00, 31.05, 35.51 +CTUN, 286, 3.47, 19.67, 7.620000, 0, 1, -147, 704, 0 +NTUN, 2.20, 0.24, 7.497406, -166.243100, 7.460855, -165.432650, 4.624718, -198.128660, 67.630226, 255.750670, 10.69, -10.87 +ATT, 10.69, 9.45, -10.87, -3.56, 0.00, 30.52, 35.51 +GPS, 3, 309055800, 10, 1.49, 24.2398123, 54.5793468, 14.69, 33.70, 1.48, 273.09 +CTUN, 286, 2.09, 19.92, 7.620000, 0, 1, -144, 692, 0 +NTUN, 2.25, 0.27, 7.099579, -155.417540, 7.095012, -155.317570, 5.585473, -191.759980, 68.341568, 265.150820, 11.13, -11.17 +ATT, 11.13, 9.67, -11.17, -4.14, 0.00, 30.61, 35.51 +DU32, 7, 393457 +CURR, 285, 390717, 1156, 0, 4752, 0.000000 +CTUN, 285, 2.09, 19.90, 7.620000, 0, 1, -144, 706, 0 +NTUN, 2.29, 0.29, 6.858521, -144.573820, 6.858521, -144.573820, 4.294928, -184.300640, 70.635086, 276.437440, 11.47, -11.74 +ATT, 11.47, 9.85, -11.74, -3.88, 0.00, 31.45, 35.51 +GPS, 3, 309056000, 10, 1.49, 24.2398124, 54.5793439, 15.00, 34.10, 1.45, 271.61 +CTUN, 285, 2.07, 19.99, 7.620000, 0, 2, -167, 733, 0 +NTUN, 2.34, 0.31, 7.217346, -133.716370, 7.217346, -133.716370, 0.300463, -174.760060, 80.552727, 280.499510, 11.23, -12.47 +ATT, 11.23, 10.72, -12.47, -3.74, 0.00, 32.05, 35.51 +CTUN, 285, 2.09, 20.20, 7.620000, 0, 1, -165, 684, 0 +NTUN, 2.41, 0.34, 8.130524, -123.025280, 8.130524, -123.025280, -1.742319, -167.083830, 90.131775, 284.910860, 11.26, -12.96 +ATT, 11.26, 10.91, -12.96, -3.96, 0.00, 31.15, 35.51 +GPS, 3, 309056200, 10, 1.49, 24.2398125, 54.5793412, 15.30, 34.47, 1.38, 271.32 +CTUN, 285, 2.09, 20.70, 7.620000, 0, 1, -161, 710, 0 +NTUN, 2.41, 0.34, 9.996674, -112.028790, 9.996674, -112.028790, -4.695375, -150.007420, 104.850000, 284.075650, 10.81, -13.60 +ATT, 10.81, 11.24, -13.60, -6.22, 0.00, 31.33, 35.51 +CTUN, 285, 3.47, 21.09, 7.620000, 0, 3, -175, 748, 0 +NTUN, 2.47, 0.36, 12.936432, -101.556900, 12.936432, -101.556900, -8.041158, -134.583250, 122.821160, 272.665620, 9.66, -14.15 +GPS, 3, 309056400, 10, 1.49, 24.2398123, 54.5793390, 15.57, 34.88, 1.15, 269.40 +ATT, 9.66, 11.28, -14.15, -6.72, 0.00, 31.64, 35.51 +CTUN, 285, 3.39, 20.89, 7.620000, 0, 2, -180, 725, 0 +NTUN, 2.52, 0.37, 16.266876, -91.462692, 16.266876, -91.462692, -4.136828, -126.055270, 127.640850, 274.961700, 9.66, -14.43 +ATT, 9.66, 10.30, -14.43, -5.39, 0.00, 31.51, 35.51 +CTUN, 285, 3.47, 21.06, 7.620000, 0, 1, -170, 704, 0 +NTUN, 2.57, 0.38, 20.035263, -81.251907, 20.035263, -81.251907, -3.731271, -115.181720, 135.944980, 274.105740, 9.36, -14.80 +GPS, 3, 309056600, 10, 1.49, 24.2398123, 54.5793369, 15.87, 35.23, 1.03, 268.13 +ATT, 9.36, 10.01, -14.80, -6.44, 0.00, 32.03, 35.51 +CTUN, 286, 3.39, 21.50, 7.620000, 0, 2, -168, 736, 0 +NTUN, 2.61, 0.39, 24.254395, -71.096939, 24.254395, -71.096939, -3.908225, -104.318140, 147.617490, 277.575440, 8.93, -15.57 +ATT, 8.93, 10.49, -15.57, -8.16, 0.00, 32.51, 35.51 +CTUN, 286, 3.39, 21.63, 7.620000, 0, 2, -175, 720, 0 +NTUN, 2.64, 0.40, 28.840485, -60.465714, 28.840485, -60.465714, 4.230619, -95.851440, 147.860900, 285.312260, 9.27, -15.80 +GPS, 3, 309056800, 10, 1.49, 24.2398122, 54.5793352, 16.18, 35.62, 0.85, 267.69 +ATT, 9.27, 9.80, -15.80, -7.77, 0.00, 31.54, 35.51 +CTUN, 285, 3.39, 21.74, 7.620000, 0, 2, -171, 721, 0 +NTUN, 2.67, 0.40, 33.298798, -49.660263, 33.298798, -49.660263, 8.148936, -87.901588, 149.141710, 290.984650, 9.75, -15.89 +DU32, 7, 393457 +CURR, 285, 397928, 1130, 0, 4712, 0.000000 +CTUN, 286, 3.39, 22.04, 7.620000, 0, 3, -173, 742, 0 +ATT, 9.75, 9.47, -15.89, -8.86, 0.00, 32.48, 35.51 +NTUN, 2.69, 0.41, 38.170624, -38.674988, 38.170624, -38.674988, 10.086967, -72.040222, 157.235900, 289.765110, 9.13, -16.38 +GPS, 3, 309057000, 10, 1.49, 24.2398122, 54.5793339, 16.50, 35.98, 0.66, 268.29 +CTUN, 286, 3.39, 21.99, 7.620000, 0, 3, -183, 756, 0 +NTUN, 2.70, 0.42, 43.239929, -27.657623, 43.239929, -27.657623, 19.550074, -63.516689, 156.205110, 295.286500, 9.22, -16.61 +ATT, 9.22, 10.12, -16.61, -9.12, 0.00, 33.30, 35.51 +CTUN, 286, 3.73, 22.46, 7.620000, 0, 2, -166, 716, 0 +NTUN, 2.70, 0.42, 48.557648, -16.095779, 48.557648, -16.095779, 26.370752, -51.132133, 157.650680, 300.473690, 9.67, -16.68 +ATT, 9.67, 9.30, -16.68, -9.19, 0.00, 32.32, 35.51 +GPS, 3, 309057200, 10, 1.49, 24.2398124, 54.5793328, 16.85, 36.35, 0.56, 274.69 +CTUN, 286, 3.73, 22.85, 7.620000, 0, 3, -166, 728, 0 +NTUN, 2.69, 0.43, 54.153687, -4.620117, 54.153687, -4.620117, 30.789837, -36.915760, 162.960390, 299.756620, 9.38, -16.93 +ATT, 9.38, 9.46, -16.93, -11.14, 0.00, 32.81, 35.51 +CTUN, 285, 3.73, 22.81, 7.620000, 0, 4, -164, 745, 0 +NTUN, 2.66, 0.43, 59.858124, 6.876129, 59.858124, 6.876129, 37.745670, -22.970087, 164.044370, 297.962460, 8.92, -17.10 +ATT, 8.92, 9.62, -17.10, -10.96, 0.00, 33.93, 35.51 +GPS, 3, 309057400, 10, 1.49, 24.2398129, 54.5793322, 17.19, 36.71, 0.45, 291.05 +CTUN, 286, 2.84, 22.83, 7.620000, 0, 3, -165, 731, 0 +NTUN, 2.62, 0.44, 65.872375, 18.765533, 65.872375, 18.765533, 44.370476, -7.856487, 166.547040, 298.716860, 8.64, -17.35 +ATT, 8.64, 8.79, -17.35, -10.54, 0.00, 34.58, 35.51 +CTUN, 286, 3.73, 23.17, 7.620000, 0, 2, -160, 725, 0 +NTUN, 2.57, 0.44, 72.318542, 30.590271, 72.318542, 30.590271, 53.478165, 5.216713, 168.823430, 299.076600, 8.54, -17.48 +GPS, 3, 309057600, 10, 1.49, 24.2398136, 54.5793317, 17.54, 37.09, 0.43, 314.28 +ATT, 8.54, 8.31, -17.48, -11.33, 0.00, 35.02, 35.51 +CTUN, 286, 3.73, 23.33, 7.620000, 0, 4, -173, 763, 0 +NTUN, 2.51, 0.44, 77.596893, 42.027222, 77.596893, 42.027222, 62.161522, 9.051478, 156.316680, 305.524750, 9.06, -17.21 +ATT, 9.06, 8.82, -17.21, -11.46, 0.00, 35.12, 35.51 +CTUN, 286, 3.73, 23.45, 7.620000, 0, 3, -165, 736, 0 +NTUN, 2.44, 0.45, 82.242859, 53.002472, 82.242859, 53.002472, 67.590981, 23.638344, 148.999660, 297.665830, 9.03, -16.60 +GPS, 3, 309057800, 10, 1.49, 24.2398146, 54.5793317, 17.88, 37.45, 0.58, 340.68 +ATT, 9.03, 8.33, -16.60, -11.10, 0.00, 34.34, 35.51 +CTUN, 286, 3.73, 23.49, 7.620000, 0, 3, -157, 726, 0 +NTUN, 2.36, 0.45, 85.999908, 62.740967, 85.999908, 62.740967, 76.126434, 37.820072, 135.570500, 282.384950, 8.89, -15.46 +DU32, 7, 393457 +CURR, 286, 404541, 1135, 0, 4732, 0.000000 +CTUN, 285, 3.73, 23.89, 7.620000, 0, 4, -169, 752, 0 +ATT, 8.89, 8.82, -15.46, -11.96, 0.00, 34.91, 35.51 +NTUN, 2.26, 0.45, 89.146088, 71.409668, 89.146088, 71.409668, 83.388702, 50.284351, 126.461790, 269.687010, 8.41, -14.75 +GPS, 3, 309058000, 10, 1.49, 24.2398160, 54.5793320, 18.23, 37.81, 0.76, 358.87 +CTUN, 285, 3.73, 23.88, 7.620000, 0, 3, -164, 737, 0 +NTUN, 2.16, 0.46, 91.648743, 79.350464, 91.648743, 79.350464, 90.045456, 64.622253, 115.778760, 255.621730, 8.04, -13.88 +ATT, 8.04, 9.35, -13.88, -11.18, 0.00, 35.38, 35.51 +CTUN, 285, 3.73, 24.14, 7.620000, 0, 3, -164, 745, 0 +NTUN, 2.04, 0.46, 93.212494, 86.200043, 93.212494, 86.200043, 95.459412, 70.074265, 103.795470, 249.187670, 8.12, -13.15 +ATT, 8.12, 7.67, -13.15, -10.67, 0.00, 35.48, 35.51 +GPS, 3, 309058200, 10, 1.49, 24.2398177, 54.5793326, 18.61, 38.18, 0.98, 10.85 +CTUN, 286, 3.73, 24.19, 7.620000, 0, 2, -162, 733, 0 +NTUN, 1.91, 0.47, 93.864197, 93.210052, 93.864197, 93.210052, 106.531650, 75.954666, 83.452507, 250.406040, 8.87, -12.26 +ATT, 8.87, 7.66, -12.26, -9.49, 0.00, 35.34, 35.51 +CTUN, 285, 3.73, 24.29, 7.620000, 0, 1, -152, 715, 0 +NTUN, 1.77, 0.47, 93.612518, 99.832977, 93.612518, 99.832977, 113.347910, 83.737297, 66.508133, 246.573520, 9.31, -11.35 +ATT, 9.31, 7.50, -11.35, -8.43, 0.00, 35.52, 35.51 +GPS, 3, 309058400, 10, 1.49, 24.2398196, 54.5793335, 18.93, 38.53, 1.19, 17.83 +CTUN, 285, 3.70, 24.65, 7.620000, 0, 2, -160, 747, 0 +NTUN, 1.63, 0.48, 92.708893, 106.533170, 92.708893, 106.533170, 117.176610, 87.704521, 53.963745, 251.001950, 9.82, -11.02 +ATT, 9.82, 8.11, -11.02, -8.06, 0.00, 36.22, 35.51 +CTUN, 285, 3.73, 24.70, 7.620000, 0, 1, -148, 712, 0 +NTUN, 1.49, 0.50, 90.292328, 111.429200, 90.292328, 111.429200, 122.632230, 92.738571, 29.308186, 233.000260, 9.78, -9.34 +GPS, 3, 309058600, 10, 1.49, 24.2398218, 54.5793346, 19.29, 38.89, 1.32, 21.78 +ATT, 9.78, 8.32, -9.34, -6.68, 0.00, 36.10, 35.51 +CTUN, 285, 3.73, 24.58, 7.620000, 0, 1, -146, 719, 0 +NTUN, 1.34, 0.52, 77.396515, 102.509280, 77.396515, 102.509280, 122.146510, 98.274826, -91.260742, 80.899780, 6.88, 1.49 +CMD, 9, 6, 16, 1, 0, 7.62, 24.2398128, 54.5793536 +ATT, 8.23, 8.46, -6.26, -6.21, 0.00, 36.49, 34.91 +CTUN, 286, 5.08, 24.85, 7.620000, 0, 1, -148, 719, 0 +NTUN, 0.00, 1.27, 61.229309, 94.656097, 61.229309, 94.656097, 127.905170, 97.855171, -147.672060, 85.468201, 9.02, 3.96 +GPS, 3, 309058800, 10, 1.49, 24.2398242, 54.5793357, 19.64, 39.26, 1.45, 22.85 +ATT, 9.02, 7.54, 3.96, -3.51, 0.00, 36.62, 28.31 +CTUN, 286, 3.73, 24.92, 7.620000, 0, 0, -144, 709, 0 +NTUN, 2.07, 1.32, 41.996246, 88.061279, 41.996246, 88.061279, 130.342090, 100.416480, -205.330630, 88.051819, 11.12, 6.54 +CTUN, 285, 3.73, 25.29, 7.620000, 0, 0, -130, 688, 0 +ATT, 11.12, 6.63, 6.54, 1.62, 0.00, 35.28, 21.71 +NTUN, 2.11, 1.36, 22.541473, 82.054199, 22.541473, 82.054199, 120.880460, 92.070541, -220.621510, 96.523956, 11.84, 7.26 +DU32, 7, 393457 +CURR, 285, 411047, 1155, 0, 4772, 0.000000 +GPS, 3, 309059000, 10, 1.49, 24.2398266, 54.5793370, 19.99, 39.63, 1.45, 24.27 +CTUN, 285, 2.75, 25.53, 7.620000, 0, 0, -132, 688, 0 +NTUN, 2.16, 1.40, 4.185822, 77.253143, 4.185822, 77.253143, 108.934910, 83.712914, -224.410630, 111.504490, 12.30, 7.51 +ATT, 12.30, 7.48, 7.51, 4.92, 0.00, 32.15, 14.51 +CTUN, 286, 3.22, 26.34, 7.620000, 0, 0, -129, 674, 0 +NTUN, 2.21, 1.43, -12.878906, 73.122620, -12.878906, 73.122620, 90.860191, 80.984550, -210.301250, 117.504670, 11.68, 7.40 +ATT, 11.68, 7.80, 7.40, 7.29, 0.00, 28.50, 8.51 +GPS, 3, 309059200, 10, 1.49, 24.2398288, 54.5793382, 20.41, 40.03, 1.36, 25.37 +CTUN, 285, 3.22, 26.69, 7.620000, 0, 0, -108, 640, 0 +NTUN, 2.26, 1.46, -27.612366, 69.673645, -27.612366, 69.673645, 71.749290, 70.089066, -192.822830, 130.161870, 11.39, 6.93 +ATT, 11.39, 8.15, 6.93, 8.28, 0.00, 24.78, 2.51 +CTUN, 285, 5.04, 27.52, 7.620000, 0, 0, -110, 653, 0 +NTUN, 2.30, 1.48, -40.823486, 67.586853, -40.823486, 67.586853, 57.444344, 58.876450, -178.803180, 153.338700, 11.90, 6.33 +ATT, 11.90, 8.74, 6.33, 8.31, 0.00, 21.51, 0.00 +GPS, 3, 309059400, 10, 1.49, 24.2398305, 54.5793392, 20.94, 40.46, 1.09, 25.80 +CTUN, 285, 3.88, 27.64, 7.620000, 0, 1, -125, 669, 0 +NTUN, 2.33, 1.49, -52.237885, 66.165161, -52.237885, 66.165161, 36.351078, 59.121655, -156.143980, 158.783080, 11.38, 5.71 +ATT, 11.38, 9.30, 5.71, 9.05, 0.00, 17.46, 0.00 +CTUN, 285, 3.88, 27.71, 7.620000, 0, 1, -121, 661, 0 +NTUN, 2.35, 1.51, -61.562897, 64.853455, -61.562897, 64.853455, 15.689597, 54.747616, -128.250120, 163.882930, 10.91, 4.69 +ATT, 10.91, 9.11, 4.69, 9.73, 0.00, 14.58, 0.00 +GPS, 3, 309059600, 10, 1.49, 24.2398317, 54.5793397, 21.48, 40.90, 0.71, 24.95 +CTUN, 286, 3.56, 27.77, 7.620000, 0, 1, -123, 659, 0 +NTUN, 2.35, 1.51, -68.967468, 64.182343, -68.967468, 64.182343, -3.800247, 50.819443, -100.045720, 173.288880, 10.92, 3.32 +ATT, 10.92, 9.41, 3.32, 8.76, 0.00, 12.56, 0.00 +CTUN, 285, 3.56, 28.17, 7.620000, 0, 1, -149, 696, 0 +NTUN, 2.33, 1.52, -74.793549, 63.983307, -74.793549, 63.983307, -20.404596, 51.267303, -74.563889, 178.067610, 10.83, 2.08 +GPS, 3, 309059800, 10, 1.49, 24.2398323, 54.5793399, 21.96, 41.31, 0.36, 22.80 +ATT, 10.83, 9.63, 2.08, 7.81, 0.00, 11.50, 0.00 +CTUN, 286, 1.95, 28.60, 7.620000, 0, 1, -151, 667, 0 +NTUN, 2.31, 1.52, -78.698517, 64.246399, -78.698517, 64.246399, -40.267986, 43.815380, -43.846615, 191.684620, 11.23, 0.38 +ATT, 11.23, 9.14, 0.38, 7.56, 0.00, 10.78, 0.00 +CTUN, 286, 3.56, 28.89, 7.620000, 0, 1, -146, 671, 0 +NTUN, 2.27, 1.52, -80.825897, 64.804169, -80.825897, 64.804169, -61.132538, 47.506470, -7.273804, 192.577700, 10.91, -1.67 +DU32, 7, 393457 +CURR, 285, 417774, 1156, 0, 4752, 0.000000 +GPS, 3, 309060000, 10, 1.49, 24.2398325, 54.5793398, 22.49, 41.71, 0.08, 22.80 +ATT, 10.91, 9.56, -1.67, 5.83, 0.00, 10.34, 0.00 +CTUN, 285, 3.56, 28.97, 7.620000, 0, 1, -163, 716, 0 +NTUN, 2.21, 1.52, -81.490631, 65.530548, -81.490631, 65.530548, -73.744667, 46.502697, 19.352661, 197.263790, 10.95, -3.18 +ATT, 10.95, 10.14, -3.18, 4.17, 0.00, 10.14, 0.00 +CTUN, 286, 3.56, 28.96, 7.620000, 0, 1, -165, 692, 0 +NTUN, 2.15, 1.51, -81.204041, 66.815979, -81.204041, 66.815979, -85.106285, 41.125175, 38.837532, 209.727040, 11.49, -4.32 +GPS, 3, 309060200, 10, 1.49, 24.2398322, 54.5793396, 22.89, 42.10, 0.21, 329.75 +ATT, 11.49, 9.88, -4.32, 3.55, 0.00, 9.50, 0.00 +CTUN, 285, 2.15, 29.32, 7.620000, 0, 1, -162, 685, 0 +NTUN, 2.09, 1.50, -79.964966, 68.636322, -79.964966, 68.636322, -100.181310, 42.995987, 66.390747, 216.203430, 11.65, -5.85 +CTUN, 285, 3.56, 29.60, 7.620000, 0, 1, -162, 708, 0 +ATT, 11.65, 10.10, -5.85, 1.64, 0.00, 8.35, 0.00 +NTUN, 2.09, 1.50, -77.827682, 70.369568, -77.827682, 70.369568, -111.679560, 45.350922, 88.953758, 215.992610, 11.57, -6.92 +GPS, 3, 309060400, 10, 1.49, 24.2398315, 54.5793392, 23.32, 42.44, 0.48, 230.20 +CTUN, 286, 3.21, 29.73, 7.620000, 0, 1, -174, 713, 0 +NTUN, 2.00, 1.49, -75.262207, 72.576111, -75.262207, 72.576111, -116.633220, 41.095802, 103.913890, 229.288310, 12.37, -7.58 +ATT, 12.37, 10.55, -7.58, -0.20, 0.00, 6.71, 0.00 +CTUN, 285, 3.21, 29.90, 7.620000, 0, 1, -171, 702, 0 +NTUN, 1.93, 1.48, -72.442566, 75.225769, -72.442566, 75.225769, -121.906090, 42.171803, 116.917240, 237.234240, 12.89, -8.10 +ATT, 12.89, 10.33, -8.10, -0.59, 0.00, 5.52, 0.00 +GPS, 3, 309060600, 10, 1.49, 24.2398307, 54.5793387, 23.73, 42.77, 0.53, 216.08 +CTUN, 286, 2.31, 30.04, 7.620000, 0, 1, -173, 738, 0 +NTUN, 1.86, 1.46, -69.688171, 78.146729, -69.688171, 78.146729, -125.415000, 42.915031, 125.543950, 243.209590, 13.26, -8.48 +ATT, 13.26, 10.41, -8.48, -2.37, 0.00, 4.90, 0.00 +CTUN, 285, 3.17, 29.96, 7.620000, 0, 2, -180, 719, 0 +NTUN, 1.79, 1.44, -66.878143, 81.214050, -66.878143, 81.214050, -128.202960, 44.292957, 135.100280, 247.673220, 13.55, -8.89 +ATT, 13.55, 11.72, -8.89, -2.59, 0.00, 4.03, 0.00 +GPS, 3, 309060800, 10, 1.49, 24.2398299, 54.5793382, 24.11, 43.08, 0.56, 211.93 +CTUN, 286, 3.17, 30.33, 7.620000, 0, 2, -179, 733, 0 +NTUN, 1.72, 1.42, -64.658051, 83.979370, -64.658051, 83.979370, -131.136800, 50.835560, 137.200930, 243.653200, 13.53, -8.67 +ATT, 13.53, 11.31, -8.67, -3.60, 0.00, 2.60, 0.00 +CTUN, 286, 5.77, 30.63, 7.620000, 0, 2, -177, 727, 0 +NTUN, 1.66, 1.40, -62.646545, 86.223206, -62.646545, 86.223206, -129.445470, 56.498627, 137.720640, 234.998380, 13.12, -8.53 +GPS, 3, 309061000, 10, 1.49, 24.2398293, 54.5793375, 24.50, 43.36, 0.50, 216.98 +DU32, 7, 393457 +CURR, 286, 424188, 1132, 0, 4752, 0.000000 +ATT, 13.12, 11.58, -8.53, -4.59, 0.00, 2.07, 0.00 +CTUN, 286, 5.77, 30.87, 7.620000, 0, 3, -178, 758, 0 +NTUN, 1.59, 1.38, -61.451233, 88.951965, -61.451233, 88.951965, -127.707660, 51.428867, 134.073870, 250.563230, 14.00, -8.30 +ATT, 14.00, 11.75, -8.30, -4.56, 0.00, 1.95, 0.00 +CTUN, 286, 5.77, 30.75, 7.620000, 0, 2, -180, 739, 0 +NTUN, 1.55, 1.36, -60.707458, 92.117493, -60.707458, 92.117493, -127.047690, 53.482979, 132.364110, 257.341860, 14.43, -8.13 +GPS, 3, 309061200, 10, 1.49, 24.2398289, 54.5793368, 24.87, 43.66, 0.43, 224.30 +ATT, 14.43, 11.82, -8.13, -4.52, 0.00, 1.34, 0.00 +PM, 0, 0, 50, 66, 1000, 12400, 8, 0 +CTUN, 286, 5.70, 30.97, 7.620000, 0, 3, -183, 750, 0 +NTUN, 1.51, 1.34, -60.548523, 94.934509, -60.548523, 94.934509, -127.628040, 58.725327, 130.605410, 254.454710, 14.36, -7.85 +ATT, 14.36, 12.17, -7.85, -4.66, 0.00, 1.01, 3.00 +CTUN, 286, 5.70, 31.12, 7.620000, 0, 4, -188, 788, 0 +NTUN, 1.47, 1.32, -61.078476, 97.883728, -61.078476, 97.883728, -125.913880, 56.087589, 124.752940, 262.200200, 14.81, -7.48 +GPS, 3, 309061400, 10, 1.49, 24.2398288, 54.5793360, 25.23, 43.94, 0.41, 242.99 +ATT, 14.81, 12.52, -7.48, -4.55, 0.00, 1.14, 9.60 +CTUN, 286, 4.11, 31.45, 7.620000, 0, 3, -181, 760, 0 +NTUN, 1.44, 1.30, -62.905167, 101.729490, -62.905167, 101.729490, -120.153190, 56.559616, 106.733090, 277.457640, 15.60, -6.59 +CTUN, 285, 4.11, 31.41, 7.620000, 0, 3, -171, 741, 0 +ATT, 15.60, 12.78, -6.59, -4.31, 0.00, 3.32, 16.20 +NTUN, 1.43, 1.28, -65.524002, 105.725950, -65.524002, 105.725950, -116.297000, 60.898849, 95.070938, 279.568910, 15.50, -6.57 +GPS, 3, 309061600, 10, 1.49, 24.2398290, 54.5793353, 25.60, 44.26, 0.37, 266.37 +CTUN, 286, 3.37, 31.33, 7.620000, 0, 3, -166, 754, 0 +NTUN, 1.43, 1.27, -69.429855, 109.759400, -69.429855, 109.759400, -114.970630, 58.493195, 78.546936, 290.741880, 15.64, -7.09 +ATT, 15.64, 13.65, -7.09, -3.87, 0.00, 9.35, 23.40 +CTUN, 286, 4.11, 31.25, 7.620000, 0, 4, -165, 761, 0 +NTUN, 1.43, 1.26, -73.846603, 113.582610, -73.846603, 113.582610, -115.653020, 63.089626, 72.698547, 288.482480, 14.83, -8.36 +ATT, 14.83, 13.97, -8.36, -3.48, 0.00, 15.40, 29.40 +GPS, 3, 309061800, 10, 1.49, 24.2398295, 54.5793344, 25.95, 44.62, 0.53, 296.11 +MODE, RTL, 470 +ERR, 9, 1 +CTUN, 285, 4.11, 31.17, 7.620000, 0, 3, -153, 744, 0 +NTUN, 1.44, 2.38, -116.561460, 68.828918, -116.561460, 68.828918, -117.939540, 74.361435, -355.463230, -256.057500, -6.76, 23.29 +ATT, -6.76, 14.00, 23.29, -3.55, 0.00, 20.86, 29.40 +CTUN, 285, 4.11, 31.28, 26.007353, 0, 3, -155, 754, 0 +NTUN, 4.54, 2.38, -116.751720, 63.516907, -116.751720, 63.516907, -123.076180, 87.439728, 80.097458, 123.879880, 4.59, -7.24 +ATT, 4.59, 10.59, -7.24, -2.59, 0.00, 25.03, 23.40 +GPS, 3, 309062000, 10, 1.49, 24.2398304, 54.5793337, 26.26, 44.95, 0.59, 309.40 +CTUN, 286, 3.60, 31.31, 26.007261, 0, 0, -158, 722, 0 +NTUN, 4.53, 2.38, -118.601910, 55.516479, -118.601910, 55.516479, -128.416720, 65.827538, 66.681221, 110.787850, 4.12, -6.28 +DU32, 7, 393457 +CURR, 285, 431717, 1136, 0, 4772, 0.000000 +ATT, 4.12, 1.26, -6.28, 7.50, 0.00, 24.79, 16.20 +CTUN, 286, 4.11, 31.97, 26.007118, 0, 0, -135, 722, 0 +NTUN, 4.51, 2.38, -120.092270, 47.768860, -120.092270, 47.768860, -146.515870, 39.743057, 88.096436, 130.523800, 5.00, -7.66 +ATT, 5.00, 2.72, -7.66, 1.17, 0.00, 21.74, 10.20 +GPS, 3, 309062200, 10, 1.49, 24.2398311, 54.5793332, 26.60, 45.35, 0.49, 316.48 +CTUN, 285, 4.11, 32.18, 26.006931, 0, 0, -122, 714, 0 +NTUN, 4.46, 2.38, -122.387440, 38.706909, -122.387440, 38.706909, -137.244780, 31.979101, 69.275589, 116.277720, 5.27, -5.85 +ATT, 5.27, 7.49, -5.85, -1.90, 0.00, 14.76, 3.00 +CTUN, 286, 4.54, 32.55, 26.006695, 0, 0, -134, 733, 0 +NTUN, 4.41, 2.37, -125.742720, 29.505463, -125.742720, 29.505463, -134.736130, 36.504013, 52.779350, 102.896580, 5.17, -4.31 +GPS, 3, 309062400, 10, 1.49, 24.2398314, 54.5793323, 27.00, 45.78, 0.50, 306.77 +ATT, 5.17, 2.62, -4.31, 0.95, 0.00, 10.09, 356.40 +CTUN, 286, 4.11, 32.97, 26.006458, 0, 0, -147, 741, 0 +NTUN, 4.36, 2.37, -130.049560, 19.816406, -130.049560, 19.816406, -139.243870, 18.892578, 44.496574, 102.130740, 5.48, -3.47 +ATT, 5.48, 3.80, -3.47, -0.30, 0.00, 5.36, 349.80 +CTUN, 286, 4.11, 33.28, 26.006199, 0, 0, -131, 712, 0 +NTUN, 4.30, 2.36, -134.726350, 10.172516, -134.726350, 10.172516, -141.681260, 4.429316, 38.695168, 109.515940, 6.21, -2.65 +GPS, 3, 309062600, 10, 1.49, 24.2398318, 54.5793311, 27.42, 46.23, 0.60, 296.27 +ATT, 6.21, 4.44, -2.65, 0.25, 0.00, 359.45, 343.20 +CTUN, 285, 3.36, 33.57, 26.005909, 0, 0, -135, 734, 0 +NTUN, 4.22, 2.36, -139.962950, 0.800690, -139.962950, 0.800690, -143.129820, -4.244016, 29.633972, 111.281740, 6.51, -1.55 +CTUN, 286, 4.11, 34.07, 26.005610, 0, 0, -146, 750, 0 +ATT, 6.51, 4.45, -1.55, 0.91, 0.00, 354.48, 336.60 +NTUN, 4.15, 2.35, -145.331500, -8.914001, -145.331500, -8.914001, -147.048900, -21.910736, 26.314545, 115.853090, 6.85, -0.83 +GPS, 3, 309062800, 10, 1.49, 24.2398320, 54.5793295, 27.87, 46.64, 0.81, 288.06 +CTUN, 285, 4.11, 34.06, 26.005281, 0, 0, -159, 752, 0 +NTUN, 4.03, 2.34, -150.556500, -18.371948, -150.547350, -18.370831, -153.596500, -29.832338, 30.841492, 118.431710, 7.08, -0.60 +ATT, 7.08, 4.70, -0.60, 1.04, 0.00, 349.85, 329.40 +CTUN, 285, 4.11, 34.45, 26.004938, 0, 0, -143, 723, 0 +NTUN, 3.93, 2.33, -155.494190, -28.565094, -155.290160, -28.527613, -163.858870, -40.860458, 41.041454, 113.437810, 6.97, -0.68 +ATT, 6.97, 4.73, -0.68, 1.28, 0.00, 345.23, 323.40 +GPS, 3, 309063000, 10, 1.49, 24.2398324, 54.5793274, 28.31, 47.00, 1.06, 280.76 +CTUN, 285, 3.37, 35.14, 26.004572, 0, 0, -147, 762, 0 +NTUN, 3.81, 2.32, -160.361360, -38.716278, -159.699860, -38.556572, -171.781740, -54.282124, 48.903015, 117.710410, 7.38, -0.55 +DU32, 7, 393457 +CURR, 285, 438326, 1133, 0, 4752, 0.000000 +ATT, 7.38, 4.42, -0.55, 0.61, 0.00, 340.58, 316.20 +CTUN, 285, 4.11, 35.34, 26.004187, 0, 0, -158, 765, 0 +NTUN, 3.69, 2.31, -164.892960, -48.848343, -163.541110, -48.447865, -177.320240, -61.187126, 55.967846, 118.066410, 7.57, -0.46 +ATT, 7.57, 5.08, -0.46, 0.36, 0.00, 336.87, 310.20 +GPS, 3, 309063200, 10, 1.49, 24.2398325, 54.5793248, 28.80, 47.38, 1.32, 276.68 +CTUN, 286, 4.11, 35.75, 26.003784, 0, 0, -140, 727, 0 +NTUN, 3.55, 2.30, -169.144740, -58.958740, -166.893780, -58.174122, -186.540390, -70.662247, 67.134583, 117.754970, 7.85, -0.46 +ATT, 7.85, 4.66, -0.46, 1.26, 0.00, 331.78, 303.00 +CTUN, 286, 4.11, 36.22, 26.003368, 0, 0, -135, 733, 0 +NTUN, 3.41, 2.29, -172.793150, -69.594574, -169.484040, -68.261787, -197.717390, -76.447701, 86.353905, 113.122120, 8.18, -1.06 +GPS, 3, 309063400, 10, 1.49, 24.2398326, 54.5793216, 29.34, 47.77, 1.59, 274.16 +ATT, 8.18, 5.70, -1.06, 0.35, 0.00, 328.23, 296.40 +CTUN, 286, 2.69, 36.46, 26.002935, 0, 0, -165, 774, 0 +NTUN, 3.26, 2.27, -176.287640, -79.719635, -171.779390, -77.680939, -205.958070, -81.114418, 96.046509, 113.808490, 8.57, -1.05 +ATT, 8.57, 6.20, -1.05, 0.64, 0.00, 323.05, 289.80 +CTUN, 286, 4.11, 36.81, 26.002495, 0, 0, -146, 745, 0 +NTUN, 3.10, 2.26, -179.325650, -90.650391, -173.468380, -87.689507, -217.809300, -89.582626, 114.277280, 106.905270, 8.97, -1.29 +GPS, 3, 309063600, 10, 1.49, 24.2398327, 54.5793179, 29.89, 48.15, 1.88, 272.12 +ATT, 8.97, 5.94, -1.29, 0.11, 0.00, 317.29, 283.80 +CTUN, 286, 3.60, 37.20, 26.002031, 0, 0, -145, 747, 0 +NTUN, 2.93, 2.24, -182.462310, -102.810180, -174.961040, -98.583519, -227.430860, -94.845734, 126.922620, 91.959473, 8.94, -1.57 +ATT, 8.94, 6.70, -1.57, -1.04, 0.00, 312.31, 277.80 +CTUN, 285, 3.60, 37.26, 26.001532, 0, 1, -168, 800, 0 +NTUN, 2.76, 2.22, -186.141480, -118.401520, -176.350010, -112.173330, -234.282230, -98.348686, 136.382720, 57.766541, 8.18, -2.62 +GPS, 3, 309063800, 10, 1.49, 24.2398328, 54.5793137, 30.40, 48.54, 2.10, 271.18 +ATT, 8.18, 6.75, -2.62, -0.97, 0.00, 305.41, 271.20 +CTUN, 286, 1.54, 37.31, 26.000967, 0, 0, -160, 740, 0 +NTUN, 2.59, 2.19, -190.490780, -134.934480, -177.906540, -126.020410, -247.138310, -100.944930, 149.277440, 38.130539, 8.42, -2.98 +CTUN, 285, 3.60, 38.07, 26.000374, 0, 0, -149, 754, 0 +ATT, 8.42, 5.73, -2.98, -1.81, 0.00, 296.57, 264.60 +NTUN, 2.41, 2.17, -190.022130, -137.284910, -177.271360, -128.072910, -256.946810, -104.684620, 185.288880, 158.678240, 13.52, 3.60 +GPS, 3, 309064000, 10, 1.49, 24.2398328, 54.5793090, 30.95, 48.90, 2.37, 270.33 +CTUN, 285, 3.60, 38.26, 26.000000, 0, 1, -148, 788, 0 +NTUN, 2.23, 2.13, -183.254240, -115.529790, -174.370450, -109.929150, -268.978910, -113.215060, 228.009090, 386.437620, 19.12, 16.58 +ATT, 19.12, 8.22, 16.58, -3.46, 0.00, 288.19, 257.40 +DU32, 7, 393457 +CURR, 285, 445135, 1142, 0, 4732, 0.000000 +CTUN, 285, 3.60, 38.16, 26.000000, 0, 1, -151, 747, 0 +NTUN, 2.05, 2.09, -175.365540, -92.855225, -170.061950, -90.046989, -283.180210, -113.512470, 266.658450, 422.853030, 19.41, 20.21 +ATT, 19.41, 10.38, 20.21, 1.20, 0.00, 280.61, 251.40 +GPS, 3, 309064200, 10, 1.49, 24.2398329, 54.5793035, 31.51, 49.26, 2.76, 270.49 +CTUN, 286, 2.18, 38.31, 26.000000, 0, 3, -136, 732, 0 +NTUN, 1.86, 2.04, -167.545260, -69.886597, -164.997730, -68.823975, -290.040250, -96.994690, 292.642240, 444.230160, 17.38, 23.80 +ATT, 17.38, 12.48, 23.80, 8.83, 0.00, 269.40, 244.20 +CTUN, 286, 2.18, 38.46, 26.000000, 0, 7, -149, 797, 0 +NTUN, 1.68, 1.97, -159.898650, -48.467285, -159.060710, -48.213299, -288.339660, -76.990486, 311.782290, 438.066100, 14.47, 25.69 +ATT, 14.47, 13.05, 25.69, 11.69, 0.00, 260.65, 238.20 +GPS, 3, 309064400, 10, 1.49, 24.2398331, 54.5792975, 32.02, 49.59, 3.05, 270.68 +CTUN, 286, 1.56, 38.46, 26.000000, 0, 7, -156, 778, 0 +NTUN, 1.68, 1.97, -154.215550, -27.979004, -154.073200, -27.953176, -281.586980, -51.104553, 307.378970, 434.647710, 9.82, 27.15 +ATT, 9.82, 12.12, 27.15, 14.44, 0.00, 249.20, 238.02 +CTUN, 286, 2.18, 38.90, 26.000000, 0, 7, -145, 759, 0 +NTUN, 1.55, 1.89, -149.428530, -8.360474, -149.428530, -8.360474, -272.383640, -18.991434, 300.843870, 393.510830, 5.55, 26.33 +GPS, 3, 309064600, 10, 1.49, 24.2398335, 54.5792913, 32.49, 49.90, 3.15, 272.18 +ATT, 5.55, 8.59, 26.33, 17.58, 0.00, 240.18, 238.02 +CTUN, 285, 2.10, 39.10, 26.000000, 0, 7, -148, 762, 0 +NTUN, 1.48, 1.81, -147.574370, 8.431274, -147.574370, 8.431274, -264.438140, 11.551234, 276.541560, 371.917480, 2.45, 25.19 +ATT, 2.45, 6.33, 25.19, 18.54, 0.00, 236.73, 238.02 +CTUN, 285, 2.10, 39.10, 26.000000, 0, 9, -157, 783, 0 +NTUN, 1.47, 1.75, -146.593410, 22.129761, -146.593410, 22.129761, -257.983610, 47.775482, 268.712430, 316.628570, 2.65, 22.81 +GPS, 3, 309064800, 10, 1.49, 24.2398343, 54.5792853, 32.97, 50.22, 3.07, 274.31 +ATT, 2.65, 4.12, 22.81, 18.18, 0.00, 235.45, 238.02 +CTUN, 286, 1.81, 39.39, 26.000000, 0, 7, -145, 769, 0 +NTUN, 1.49, 1.69, -147.643250, 34.301758, -147.635280, 34.299904, -252.150130, 89.431076, 246.476060, 270.930730, 2.72, 20.31 +ATT, 2.72, 3.59, 20.31, 17.48, 0.00, 236.49, 238.02 +CTUN, 285, 2.10, 39.78, 26.000000, 0, 7, -146, 774, 0 +NTUN, 1.52, 1.65, -149.446260, 43.215942, -149.350460, 43.188244, -246.228990, 124.668880, 237.018020, 206.003360, 4.84, 17.10 +GPS, 3, 309065000, 10, 1.49, 24.2398354, 54.5792800, 33.43, 50.56, 2.80, 277.22 +CTUN, 285, 2.10, 39.93, 26.000000, 0, 6, -149, 769, 0 +ATT, 4.84, 4.08, 17.10, 16.51, 0.00, 240.03, 238.02 +NTUN, 1.57, 1.63, -152.812500, 51.274780, -152.444110, 51.151173, -242.990570, 158.569440, 221.063570, 166.629290, 6.12, 14.53 +DU32, 7, 393457 +CURR, 285, 452043, 1157, 0, 4712, 0.000000 +CTUN, 286, 2.10, 40.06, 26.000000, 0, 5, -152, 764, 0 +ATT, 6.12, 5.58, 14.53, 15.30, 0.00, 243.29, 238.02 +NTUN, 1.63, 1.60, -156.649690, 56.311157, -155.881680, 56.035080, -237.681820, 187.539760, 213.624240, 104.839070, 8.11, 10.89 +GPS, 3, 309065200, 10, 1.49, 24.2398369, 54.5792755, 33.88, 50.91, 2.46, 283.26 +CTUN, 286, 1.19, 40.31, 26.000000, 0, 4, -139, 752, 0 +ATT, 8.11, 6.68, 10.89, 13.50, 0.00, 245.78, 238.02 +NTUN, 1.69, 1.59, -162.472810, 61.180969, -160.963330, 60.612556, -227.246800, 214.581890, 185.183500, 72.774765, 7.88, 8.22 +CTUN, 286, 2.10, 40.57, 26.000000, 0, 3, -134, 757, 0 +ATT, 7.88, 7.70, 8.22, 10.80, 0.00, 247.90, 238.02 +NTUN, 1.78, 1.59, -169.239750, 64.218750, -166.737150, 63.269131, -222.786790, 235.284640, 171.833480, 25.302715, 8.55, 5.10 +GPS, 3, 309065400, 10, 1.49, 24.2398386, 54.5792718, 34.36, 51.30, 2.13, 289.80 +CTUN, 285, 2.10, 40.82, 26.000000, 0, 2, -130, 749, 0 +ATT, 8.55, 8.52, 5.10, 8.01, 0.00, 250.41, 238.02 +NTUN, 1.86, 1.59, -177.170990, 68.241821, -173.222600, 66.720993, -218.397250, 246.771670, 155.145570, 16.518623, 8.10, 3.91 +CTUN, 285, 3.41, 41.05, 26.000000, 0, 2, -139, 743, 0 +ATT, 8.10, 8.45, 3.91, 5.25, 0.00, 252.10, 238.02 +NTUN, 1.95, 1.58, -185.768740, 71.570374, -180.035030, 69.361374, -213.415130, 254.058690, 142.550110, -4.857616, 7.94, 2.25 +GPS, 3, 309065600, 10, 1.49, 24.2398405, 54.5792684, 34.88, 51.71, 2.02, 295.56 +CTUN, 285, 2.42, 41.24, 26.000000, 0, 1, -140, 763, 0 +NTUN, 2.05, 1.58, -194.828740, 76.809143, -186.821200, 73.652260, -218.035460, 258.277560, 141.138370, 1.908859, 7.81, 2.47 +ATT, 7.81, 8.41, 2.47, 1.65, 0.00, 253.37, 238.02 +CTUN, 286, 2.42, 41.39, 26.000000, 0, 1, -133, 753, 0 +NTUN, 2.15, 1.58, -203.692410, 82.278564, -193.173740, 78.029701, -220.331010, 259.197170, 142.474610, -3.225586, 7.99, 2.15 +ATT, 7.99, 8.13, 2.15, 0.12, 0.00, 253.66, 238.02 +GPS, 3, 309065800, 10, 1.49, 24.2398424, 54.5792650, 35.33, 52.07, 2.01, 299.62 +CTUN, 286, 2.42, 41.54, 26.000000, 0, 1, -134, 749, 0 +NTUN, 2.26, 1.57, -212.400180, 90.248108, -198.963810, 84.539040, -225.180210, 257.134310, 149.099300, 19.093384, 7.96, 3.57 +ATT, 7.96, 7.34, 3.57, -0.55, 0.00, 253.15, 238.02 +CTUN, 286, 2.88, 41.78, 26.000000, 0, 0, -131, 723, 0 +NTUN, 2.37, 1.56, -220.827610, 98.719604, -204.273300, 91.319115, -228.497760, 253.717090, 153.430760, 23.129456, 8.05, 4.04 +ATT, 8.05, 6.82, 4.04, -1.05, 0.00, 251.89, 238.02 +GPS, 3, 309066000, 10, 1.49, 24.2398441, 54.5792614, 35.80, 52.45, 2.05, 298.60 +CTUN, 286, 2.88, 41.81, 26.000000, 0, 0, -124, 720, 0 +NTUN, 2.48, 1.55, -228.623320, 108.689390, -208.784850, 99.258026, -229.901860, 250.132970, 158.884490, 39.389114, 7.96, 5.19 +ATT, 7.96, 7.07, 5.19, -1.15, 0.00, 250.80, 238.02 +DU32, 7, 393457 +CURR, 285, 459544, 1131, 0, 4752, 0.000000 +CTUN, 286, 2.88, 42.07, 26.000000, 0, 1, -132, 755, 0 +NTUN, 2.60, 1.53, -236.090270, 119.646360, -212.779560, 107.832910, -231.388610, 246.257710, 162.052950, 50.748825, 7.87, 5.94 +ATT, 7.87, 6.91, 5.94, -0.81, 0.00, 250.32, 238.02 +GPS, 3, 309066200, 10, 1.49, 24.2398456, 54.5792575, 36.26, 52.83, 2.18, 294.88 +CTUN, 286, 2.88, 42.14, 26.000000, 0, 0, -134, 735, 0 +NTUN, 2.72, 1.52, -244.176570, 133.745360, -216.654540, 118.670430, -231.830000, 241.656200, 161.633820, 82.302216, 7.11, 7.77 +ATT, 7.11, 6.48, 7.77, -0.76, 0.00, 249.35, 238.02 +CTUN, 286, 4.30, 42.44, 26.000000, 0, 0, -128, 720, 0 +NTUN, 2.87, 1.50, -252.236820, 148.599730, -220.216080, 129.735410, -236.044460, 238.654130, 164.384610, 94.649796, 6.82, 8.64 +ATT, 6.82, 6.50, 8.64, -0.35, 0.00, 248.03, 238.02 +GPS, 3, 309066400, 10, 1.49, 24.2398467, 54.5792533, 36.69, 53.17, 2.20, 290.63 +CTUN, 285, 4.30, 42.56, 26.000000, 0, 0, -148, 758, 0 +NTUN, 3.01, 1.48, -259.336700, 165.191650, -222.741260, 141.881180, -238.312520, 235.606540, 175.748230, 115.457670, 6.85, 10.07 +ATT, 6.85, 6.12, 10.07, 0.74, 0.00, 247.29, 238.02 +CTUN, 285, 5.91, 42.60, 26.000000, 0, 0, -150, 744, 0 +NTUN, 3.16, 1.46, -266.229800, 182.074710, -224.935620, 153.833600, -238.632400, 236.594700, 178.273610, 119.340820, 6.61, 10.50 +ATT, 6.61, 5.50, 10.50, 1.50, 0.00, 245.59, 238.02 +GPS, 3, 309066600, 10, 1.49, 24.2398476, 54.5792486, 37.11, 53.50, 2.40, 285.41 +CTUN, 285, 4.77, 42.84, 26.000000, 0, 0, -130, 714, 0 +NTUN, 3.31, 1.44, -272.541990, 200.444400, -226.417820, 166.521790, -240.757480, 238.017440, 187.178070, 134.881870, 6.18, 11.79 +ATT, 6.18, 6.27, 11.79, 2.60, 0.00, 243.05, 238.02 +CTUN, 286, 4.77, 43.09, 26.000000, 0, 1, -141, 772, 0 +NTUN, 3.48, 1.42, -278.764100, 219.112640, -227.688350, 178.966350, -241.147780, 235.744340, 188.420410, 143.213500, 5.79, 12.34 +ATT, 5.79, 5.49, 12.34, 4.21, 0.00, 242.19, 238.02 +GPS, 3, 309066800, 10, 1.49, 24.2398480, 54.5792439, 37.49, 53.86, 2.43, 281.34 +CTUN, 286, 4.77, 43.16, 26.000000, 0, 0, -163, 742, 0 +NTUN, 3.64, 1.40, -284.308900, 238.629910, -228.319850, 191.636440, -237.336350, 242.023010, 191.685000, 150.700900, 5.55, 12.88 +ATT, 5.55, 4.77, 12.88, 4.64, 0.00, 241.03, 238.02 +CTUN, 286, 4.77, 43.36, 26.000000, 0, 0, -140, 717, 0 +NTUN, 3.81, 1.38, -289.677920, 257.531490, -228.868290, 203.470090, -240.097790, 247.618930, 194.515690, 146.336490, 5.44, 12.89 +ATT, 5.44, 5.29, 12.89, 5.28, 0.00, 239.60, 238.02 +GPS, 3, 309067000, 10, 1.49, 24.2398484, 54.5792391, 37.86, 54.17, 2.46, 277.46 +CTUN, 286, 4.34, 43.59, 26.000000, 0, 1, -139, 771, 0 +NTUN, 3.97, 1.37, -294.554810, 277.193570, -228.953310, 215.458660, -235.956020, 249.197020, 196.149780, 156.885710, 5.27, 13.42 +ATT, 5.27, 4.80, 13.42, 6.52, 0.00, 240.01, 238.02 +DU32, 7, 393457 +CURR, 285, 466966, 1137, 0, 4793, 0.000000 +CTUN, 285, 4.34, 43.65, 26.000000, 0, 1, -153, 757, 0 +NTUN, 4.14, 1.35, -299.765200, 296.654720, -229.244920, 226.866200, -229.527570, 256.105260, 187.083890, 154.075320, 5.02, 12.99 +ATT, 5.02, 4.32, 12.99, 7.04, 0.00, 240.45, 238.02 +GPS, 3, 309067200, 10, 1.49, 24.2398484, 54.5792342, 38.24, 54.55, 2.49, 274.48 +CTUN, 286, 2.00, 43.99, 26.000000, 0, 0, -136, 709, 0 +NTUN, 4.32, 1.34, -304.450500, 316.436550, -229.149150, 238.170620, -228.783450, 263.824070, 190.948170, 153.925020, 5.18, 13.10 +ATT, 5.18, 4.56, 13.10, 6.97, 0.00, 240.34, 238.02 +CTUN, 286, 3.35, 44.09, 26.000000, 0, 1, -133, 713, 0 +NTUN, 4.49, 1.33, -309.388240, 335.666470, -229.282330, 248.756670, -221.861450, 266.254060, 180.681400, 154.812320, 4.66, 12.85 +ATT, 4.66, 4.11, 12.85, 7.13, 0.00, 240.49, 238.02 +GPS, 3, 309067400, 10, 1.49, 24.2398483, 54.5792297, 38.66, 54.89, 2.30, 271.91 +CTUN, 286, 3.35, 44.18, 26.000000, 0, 1, -142, 766, 0 +NTUN, 4.66, 1.31, -313.481450, 355.186550, -228.864230, 259.311980, -224.392590, 272.394350, 189.223300, 159.619320, 5.20, 13.23 +ATT, 5.20, 4.12, 13.23, 6.76, 0.00, 241.52, 238.02 +CTUN, 285, 3.35, 44.25, 26.000000, 0, 0, -127, 709, 0 +NTUN, 4.83, 1.30, -317.383790, 374.029140, -228.442600, 269.214110, -224.009370, 282.307400, 189.216310, 151.021300, 5.46, 12.80 +GPS, 3, 309067600, 10, 1.49, 24.2398481, 54.5792254, 38.97, 55.24, 2.20, 269.50 +ATT, 5.46, 4.75, 12.80, 7.44, 0.00, 241.45, 238.02 +CTUN, 285, 2.76, 44.63, 26.000000, 0, 1, -119, 709, 0 +NTUN, 5.00, 1.29, -320.219600, 392.585600, -227.445270, 278.845310, -221.923890, 282.860320, 193.874560, 156.358370, 5.52, 13.19 +ATT, 5.52, 5.46, 13.19, 8.55, 0.00, 241.63, 238.02 +CTUN, 285, 2.76, 44.83, 26.000000, 0, 2, -157, 778, 0 +NTUN, 5.16, 1.28, -323.410400, 411.284390, -226.662260, 288.248780, -216.251570, 284.852260, 185.830050, 162.034730, 4.97, 13.24 +GPS, 3, 309067800, 10, 1.49, 24.2398476, 54.5792215, 39.36, 55.62, 2.05, 267.02 +ATT, 4.97, 4.31, 13.24, 9.04, 0.00, 241.41, 238.02 +CTUN, 285, 2.76, 45.03, 26.000000, 0, 1, -146, 721, 0 +NTUN, 5.32, 1.27, -325.875850, 429.234250, -225.584530, 297.133420, -211.913300, 295.677830, 184.777280, 154.846440, 4.76, 13.00 +ATT, 4.76, 4.78, 13.00, 8.08, 0.00, 239.33, 238.02 +CTUN, 285, 2.76, 45.17, 26.000000, 0, 1, -140, 748, 0 +NTUN, 5.48, 1.26, -328.854370, 446.915440, -224.872020, 305.602660, -203.314590, 294.953090, 172.054550, 159.853850, 3.63, 12.99 +GPS, 3, 309068000, 10, 1.49, 24.2398471, 54.5792180, 39.73, 55.97, 1.83, 264.15 +ATT, 3.63, 4.95, 12.99, 7.92, 0.00, 238.20, 238.02 +CTUN, 285, 2.64, 45.14, 26.000000, 0, 1, -139, 744, 0 +NTUN, 5.64, 1.25, -331.271120, 464.268340, -223.904400, 313.796510, -200.947130, 296.623600, 172.676210, 165.938480, 3.27, 13.34 +DU32, 7, 393457 +CURR, 286, 474348, 1129, 0, 4732, 0.000000 +ATT, 3.27, 4.53, 13.34, 8.98, 0.00, 237.48, 238.02 +CTUN, 286, 2.76, 45.28, 26.000000, 0, 1, -153, 731, 0 +NTUN, 5.79, 1.25, -334.365480, 481.406370, -223.384340, 321.620060, -190.680440, 303.535250, 157.200650, 163.235470, 2.44, 12.78 +GPS, 3, 309068200, 10, 1.49, 24.2398465, 54.5792146, 40.08, 56.33, 1.77, 262.32 +ATT, 2.44, 3.41, 12.78, 8.65, 0.00, 236.28, 238.02 +CTUN, 285, 2.76, 45.60, 26.000000, 0, 1, -144, 728, 0 +NTUN, 5.95, 1.24, -337.077090, 497.785710, -222.768600, 328.978240, -182.719440, 304.815950, 148.096420, 165.853300, 1.66, 12.67 +ATT, 1.66, 2.98, 12.67, 7.92, 0.00, 235.17, 238.02 +CTUN, 285, 4.14, 45.91, 26.000000, 0, 1, -144, 755, 0 +NTUN, 6.10, 1.23, -339.982240, 513.778630, -222.336140, 335.992680, -177.899670, 307.291810, 139.324650, 168.144350, 0.98, 12.51 +GPS, 3, 309068400, 10, 1.49, 24.2398459, 54.5792117, 40.43, 56.68, 1.53, 260.03 +ATT, 0.98, 2.31, 12.51, 7.32, 0.00, 234.52, 238.02 +CTUN, 286, 3.86, 45.88, 26.000000, 0, 1, -143, 746, 0 +NTUN, 6.22, 1.23, -340.298650, 526.687380, -220.853970, 341.820370, -181.631590, 315.307860, 152.674880, 154.699980, 1.98, 12.34 +ATT, 1.98, 1.80, 12.34, 8.06, 0.00, 234.18, 238.02 +CTUN, 286, 4.14, 45.95, 26.000000, 0, 1, -151, 747, 0 +NTUN, 6.33, 1.22, -340.457520, 539.036130, -219.376270, 347.331820, -178.508940, 317.733760, 149.777070, 157.114440, 1.69, 12.36 +GPS, 3, 309068600, 10, 1.49, 24.2398452, 54.5792091, 40.78, 57.02, 1.38, 258.36 +CTUN, 286, 3.86, 46.21, 26.000000, 0, 1, -149, 717, 0 +ATT, 1.69, 1.13, 12.36, 8.20, 0.00, 233.22, 238.02 +NTUN, 6.45, 1.21, -342.000000, 553.154170, -218.478270, 353.368900, -171.318020, 324.885350, 134.979950, 162.370790, 0.60, 12.13 +CTUN, 286, 4.14, 46.61, 26.000000, 0, 1, -135, 741, 0 +ATT, 0.60, 1.77, 12.13, 7.13, 0.00, 232.44, 238.02 +NTUN, 6.58, 1.21, -343.853210, 566.919860, -217.818600, 359.123320, -171.582990, 329.468900, 131.531370, 161.974500, 0.29, 12.00 +GPS, 3, 309068800, 10, 1.49, 24.2398444, 54.5792071, 41.13, 57.38, 1.17, 253.36 +CTUN, 286, 4.14, 46.66, 26.000000, 0, 1, -143, 757, 0 +ATT, 0.29, 1.62, 12.00, 7.09, 0.00, 232.38, 238.02 +NTUN, 6.69, 1.20, -344.575500, 579.631960, -216.675000, 364.482540, -167.625170, 327.395450, 130.436000, 168.592220, 0.03, 12.26 +CTUN, 286, 4.14, 46.60, 26.000000, 0, 0, -141, 729, 0 +ATT, 0.03, 0.43, 12.26, 7.66, 0.00, 232.48, 238.02 +NTUN, 6.81, 1.20, -345.836300, 592.352970, -215.849080, 369.709140, -161.233540, 329.416750, 120.259280, 172.265930, -0.54, 12.07 +GPS, 3, 309069000, 9, 1.75, 24.2398434, 54.5792053, 41.49, 57.75, 1.07, 248.54 +CTUN, 286, 2.22, 47.10, 26.000000, 0, 0, -129, 691, 0 +ATT, -0.54, 0.32, 12.07, 6.83, 0.00, 232.73, 238.02 +NTUN, 6.92, 1.20, -345.988460, 603.685850, -214.591400, 374.422270, -164.382980, 338.283110, 125.452220, 163.664700, 0.04, 11.87 +DU32, 7, 393457 +CURR, 285, 480980, 1156, 0, 4793, 0.000000 +CTUN, 286, 2.22, 47.37, 26.000000, 0, 0, -125, 720, 0 +ATT, 0.04, 0.82, 11.87, 5.93, 0.00, 233.63, 238.02 +NTUN, 7.01, 1.19, -345.945370, 614.583370, -213.294130, 378.924070, -159.338410, 333.882230, 119.972720, 174.018010, -0.36, 12.15 +GPS, 3, 309069200, 10, 1.49, 24.2398423, 54.5792041, 41.87, 58.09, 0.87, 240.90 +CTUN, 285, 2.22, 47.39, 26.000000, 0, 0, -128, 725, 0 +NTUN, 7.10, 1.19, -344.909910, 624.684200, -211.559200, 383.165800, -158.106540, 334.174160, 122.349240, 176.417300, -0.07, 12.34 +ATT, -0.07, 0.52, 12.34, 6.07, 0.00, 235.06, 238.02 +CTUN, 285, 2.22, 47.54, 26.000000, 0, 0, -119, 698, 0 +NTUN, 7.18, 1.18, -343.665410, 634.397710, -209.770130, 387.230350, -163.395100, 339.155430, 127.890780, 176.645450, 0.32, 12.53 +GPS, 3, 309069400, 10, 1.49, 24.2398408, 54.5792035, 42.27, 58.49, 0.87, 221.69 +ATT, 0.32, 0.15, 12.53, 6.25, 0.00, 235.62, 238.02 +CTUN, 286, 2.22, 47.69, 26.000000, 0, 0, -116, 692, 0 +NTUN, 7.24, 1.18, -340.431760, 642.187190, -207.120000, 390.709200, -165.259080, 341.705870, 138.238920, 174.444080, 0.96, 12.75 +ATT, 0.96, 0.44, 12.75, 6.60, 0.00, 235.85, 238.02 +CTUN, 285, 2.90, 47.92, 26.000000, 0, 0, -126, 706, 0 +NTUN, 7.29, 1.17, -337.037350, 649.741460, -204.419390, 394.080200, -163.412050, 340.868930, 137.006070, 180.710020, 0.65, 13.00 +GPS, 3, 309069600, 10, 1.49, 24.2398391, 54.5792031, 42.65, 58.85, 0.98, 202.97 +ATT, 0.65, 0.13, 13.00, 6.53, 0.00, 235.69, 238.02 +CTUN, 286, 2.33, 48.12, 26.000000, 0, 0, -121, 704, 0 +NTUN, 7.34, 1.17, -332.289920, 655.960080, -201.130450, 397.043460, -163.437290, 341.678560, 145.889400, 180.632570, 0.97, 13.28 +ATT, 0.97, 0.67, 13.28, 6.72, 0.00, 235.22, 238.02 +CTUN, 285, 2.90, 48.29, 26.000000, 0, 0, -118, 711, 0 +NTUN, 7.37, 1.16, -327.215330, 661.725460, -197.715420, 399.838590, -162.341710, 340.264430, 146.812120, 185.674610, 0.89, 13.54 +GPS, 3, 309069800, 9, 1.75, 24.2398371, 54.5792032, 43.06, 59.17, 1.10, 188.06 +ATT, 0.89, 1.13, 13.54, 7.49, 0.00, 235.41, 238.02 +CTUN, 285, 2.90, 48.23, 26.000000, 0, 1, -141, 731, 0 +NTUN, 7.36, 1.15, -319.032960, 663.208740, -193.032840, 401.278500, -166.234760, 341.683810, 167.298860, 175.544560, 2.34, 13.70 +ATT, 2.34, 0.80, 13.70, 8.14, 0.00, 236.02, 238.02 +CTUN, 285, 2.90, 48.54, 26.000000, 0, 0, -151, 710, 0 +NTUN, 7.34, 1.15, -310.989750, 664.372130, -188.438520, 402.564090, -162.191270, 345.688840, 164.488270, 173.728550, 2.16, 13.54 +GPS, 3, 309070000, 10, 1.49, 24.2398348, 54.5792036, 43.39, 59.50, 1.29, 176.07 +ATT, 2.16, 0.86, 13.54, 8.40, 0.00, 235.51, 238.02 +CTUN, 285, 2.90, 48.75, 26.000000, 0, 1, -142, 720, 0 +NTUN, 7.33, 1.14, -303.699710, 667.282470, -184.067140, 404.428380, -159.892940, 347.619260, 163.713840, 182.642880, 1.53, 13.96 +ATT, 1.53, 2.02, 13.96, 8.56, 0.00, 234.22, 238.02 +DU32, 7, 393457 +CURR, 286, 488087, 1144, 0, 4732, 0.000000 +CTUN, 285, 4.41, 48.89, 26.000000, 0, 1, -153, 756, 0 +NTUN, 7.33, 1.14, -296.641850, 670.349910, -179.799440, 406.309970, -158.075380, 349.018740, 164.677000, 186.815920, 1.18, 14.20 +GPS, 3, 309070200, 10, 1.49, 24.2398321, 54.5792048, 43.72, 59.81, 1.58, 164.32 +ATT, 1.18, 2.04, 14.20, 8.32, 0.00, 233.25, 238.02 +CTUN, 285, 4.41, 48.79, 26.000000, 0, 0, -154, 721, 0 +NTUN, 7.31, 1.13, -288.256590, 671.208250, -174.988390, 407.462160, -157.362610, 352.735320, 172.634160, 178.407840, 1.54, 14.12 +ATT, 1.54, 1.78, 14.12, 7.49, 0.00, 232.00, 238.02 +CTUN, 285, 4.41, 49.25, 26.000000, 0, 0, -142, 701, 0 +NTUN, 7.28, 1.12, -279.346920, 670.934690, -169.963590, 408.218110, -156.925190, 354.027070, 178.247960, 177.559510, 1.67, 14.29 +GPS, 3, 309070400, 10, 1.49, 24.2398292, 54.5792066, 44.03, 60.13, 1.83, 156.03 +ATT, 1.67, 1.74, 14.29, 7.99, 0.00, 231.50, 238.02 +CTUN, 286, 1.95, 49.41, 26.000000, 0, 1, -158, 756, 0 +NTUN, 7.21, 1.12, -267.432370, 665.615970, -163.656890, 407.327790, -153.527920, 352.970280, 193.442600, 164.184950, 3.05, 14.19 +ATT, 3.05, 1.66, 14.19, 9.29, 0.00, 232.53, 238.02 +CTUN, 286, 2.05, 49.48, 26.000000, 0, 1, -163, 750, 0 +NTUN, 7.11, 1.11, -255.686280, 659.693790, -157.423290, 406.166350, -152.492430, 364.750890, 199.335970, 150.385620, 3.93, 13.76 +GPS, 3, 309070600, 9, 1.75, 24.2398264, 54.5792085, 44.34, 60.43, 1.83, 151.97 +ATT, 3.93, 2.21, 13.76, 8.79, 0.00, 232.86, 238.02 +CTUN, 286, 2.05, 49.55, 26.000000, 0, 1, -140, 712, 0 +NTUN, 7.02, 1.10, -244.875730, 655.042480, -151.542620, 405.376430, -150.823330, 367.755220, 199.806760, 152.100830, 3.70, 13.90 +ATT, 3.70, 3.65, 13.90, 8.19, 0.00, 232.04, 238.02 +CTUN, 286, 4.17, 49.66, 26.000000, 0, 1, -142, 739, 0 +NTUN, 6.94, 1.10, -234.145390, 650.135250, -145.664840, 404.457490, -149.149860, 367.624660, 202.195820, 151.901540, 3.81, 13.97 +GPS, 3, 309070800, 10, 1.49, 24.2398236, 54.5792108, 44.66, 60.70, 1.98, 146.74 +ATT, 3.81, 3.76, 13.97, 8.75, 0.00, 232.21, 238.02 +CTUN, 286, 4.17, 49.91, 26.000000, 0, 1, -149, 723, 0 +NTUN, 6.82, 1.09, -221.158570, 640.106990, -138.805860, 401.750700, -145.323870, 372.152500, 215.589780, 127.932130, 5.30, 13.37 +ATT, 5.30, 3.64, 13.37, 9.32, 0.00, 232.18, 238.02 +CTUN, 286, 5.86, 50.13, 26.000000, 0, 1, -141, 725, 0 +NTUN, 6.68, 1.08, -208.390260, 629.280760, -132.021640, 398.668700, -140.127750, 379.006010, 217.842250, 115.179990, 5.74, 12.93 +GPS, 3, 309071000, 10, 1.49, 24.2398207, 54.5792136, 44.98, 60.97, 2.16, 142.20 +ATT, 5.74, 4.05, 12.93, 9.73, 0.00, 231.63, 238.02 +CTUN, 286, 4.99, 50.13, 26.000000, 0, 1, -122, 715, 0 +NTUN, 6.53, 1.07, -195.790410, 617.031310, -125.326770, 394.965910, -132.318540, 382.060460, 214.285840, 103.338720, 5.87, 12.35 +DU32, 7, 393457 +CURR, 285, 495358, 1124, 0, 4772, 0.000000 +ATT, 5.87, 5.00, 12.35, 8.99, 0.00, 231.32, 238.02 +CTUN, 286, 5.86, 50.16, 26.000000, 0, 1, -130, 731, 0 +NTUN, 6.38, 1.07, -183.728030, 604.778750, -118.829840, 391.152980, -130.263210, 381.731990, 217.969250, 98.870728, 6.31, 12.23 +GPS, 3, 309071200, 9, 1.75, 24.2398177, 54.5792168, 45.28, 61.26, 2.30, 138.88 +ATT, 6.31, 6.07, 12.23, 8.35, 0.00, 231.91, 238.02 +PM, 0, 0, 50, 85, 1000, 11940, 10, 0 +CTUN, 286, 4.99, 50.44, 26.000000, 0, 1, -129, 711, 0 +NTUN, 6.24, 1.06, -172.782350, 594.940670, -112.722560, 388.137050, -122.122720, 380.562560, 213.689740, 104.536060, 6.06, 12.26 +ATT, 6.06, 6.60, 12.26, 9.02, 0.00, 232.59, 238.02 +CTUN, 285, 4.99, 50.57, 26.000000, 0, 1, -123, 694, 0 +NTUN, 6.12, 1.05, -162.874390, 585.215880, -107.161740, 385.037510, -107.915980, 374.831390, 197.517850, 108.612270, 5.38, 11.81 +GPS, 3, 309071400, 9, 1.75, 24.2398146, 54.5792205, 45.61, 61.53, 2.52, 135.23 +ATT, 5.38, 6.01, 11.81, 8.36, 0.00, 233.70, 238.02 +CTUN, 286, 4.36, 50.68, 26.000000, 0, 1, -132, 711, 0 +NTUN, 5.96, 1.05, -150.899290, 570.087460, -100.551220, 379.875820, -108.613270, 376.188480, 217.105190, 80.383179, 7.52, 11.02 +ATT, 7.52, 6.58, 11.02, 7.50, 0.00, 235.12, 238.02 +CTUN, 286, 4.36, 50.68, 26.000000, 0, 1, -129, 708, 0 +NTUN, 5.79, 1.04, -138.810790, 554.754520, -93.715622, 374.532590, -106.699210, 377.483860, 224.355940, 73.567688, 8.27, 10.80 +GPS, 3, 309071600, 9, 1.75, 24.2398117, 54.5792243, 45.94, 61.79, 2.55, 132.22 +ATT, 8.27, 7.99, 10.80, 7.83, 0.00, 235.85, 238.02 +CTUN, 285, 4.05, 50.77, 26.000000, 0, 1, -128, 719, 0 +NTUN, 5.63, 1.03, -128.352050, 542.695010, -87.581497, 370.309970, -93.047081, 369.845950, 209.733900, 87.191826, 7.20, 10.93 +ATT, 7.20, 7.73, 10.93, 7.68, 0.00, 236.03, 238.02 +CTUN, 285, 4.05, 51.05, 26.000000, 0, 1, -135, 710, 0 +NTUN, 5.49, 1.02, -118.590080, 530.822270, -81.776291, 366.039640, -87.997704, 366.642910, 208.052060, 86.296753, 7.17, 10.83 +GPS, 3, 309071800, 9, 1.75, 24.2398088, 54.5792285, 46.30, 62.01, 2.68, 129.66 +ATT, 7.17, 8.17, 10.83, 6.78, 0.00, 236.02, 238.02 +ERR, 9, 1 +CTUN, 285, 2.87, 51.20, 26.000000, 0, 1, -131, 689, 0 +NTUN, 5.32, 1.02, -106.992790, 513.796630, -74.890152, 359.634550, -83.157837, 362.458770, 222.556960, 62.302116, 8.57, 10.21 +ATT, 8.57, 8.82, 10.21, 6.70, 0.00, 235.72, 238.02 +CTUN, 285, 3.56, 51.31, 26.000000, 0, 1, -134, 711, 0 +NTUN, 5.13, 1.01, -95.990349, 497.293760, -68.188095, 353.259640, -76.990067, 356.633180, 219.356990, 62.882095, 8.37, 10.17 +GPS, 3, 309072000, 9, 1.75, 24.2398060, 54.5792328, 46.55, 62.21, 2.69, 127.65 +ATT, 8.37, 8.52, 10.17, 6.16, 0.00, 235.51, 238.02 +CTUN, 285, 3.56, 51.15, 26.000000, 0, 1, -128, 710, 0 +NTUN, 4.97, 1.00, -86.074089, 483.981450, -61.899845, 348.053410, -69.844109, 348.790800, 215.882510, 76.937622, 7.75, 10.72 +DU32, 7, 393457 +CURR, 285, 502439, 1140, 0, 4793, 0.000000 +ATT, 7.75, 10.03, 10.72, 6.03, 0.00, 235.41, 238.02 +CTUN, 285, 4.96, 51.34, 26.000000, 0, 2, -141, 723, 0 +NTUN, 4.83, 0.99, -76.682487, 471.793090, -55.781124, 343.196350, -65.359337, 341.990110, 216.187210, 81.429443, 7.61, 10.94 +GPS, 3, 309072200, 9, 1.75, 24.2398034, 54.5792372, 46.84, 62.43, 2.73, 125.27 +ATT, 7.61, 10.08, 10.94, 6.31, 0.00, 235.46, 238.02 +CTUN, 286, 4.44, 51.48, 26.000000, 0, 2, -149, 720, 0 +NTUN, 4.69, 0.98, -67.031364, 458.354980, -49.384010, 337.683810, -56.940434, 335.141940, 216.337750, 76.420372, 7.69, 10.77 +ATT, 7.69, 9.78, 10.77, 6.12, 0.00, 234.75, 238.02 +CTUN, 286, 4.80, 51.33, 26.000000, 0, 1, -136, 674, 0 +NTUN, 4.54, 0.97, -58.179192, 444.868290, -43.416084, 331.981900, -45.458557, 328.545140, 207.679260, 74.980957, 7.13, 10.57 +GPS, 3, 309072400, 9, 1.75, 24.2398008, 54.5792417, 47.11, 62.61, 2.71, 123.67 +ATT, 7.13, 9.99, 10.57, 5.34, 0.00, 233.45, 238.02 +CTUN, 285, 4.80, 51.31, 26.000000, 0, 1, -118, 687, 0 +NTUN, 4.37, 0.96, -48.362175, 426.742070, -36.721622, 324.027220, -41.282887, 320.414730, 217.281800, 53.240784, 8.22, 9.97 +ATT, 8.22, 10.23, 9.97, 5.71, 0.00, 233.62, 238.02 +CTUN, 286, 5.67, 51.50, 26.000000, 0, 2, -135, 724, 0 +NTUN, 4.18, 0.95, -38.931145, 409.327640, -30.068645, 316.146060, -36.100544, 315.724150, 218.871060, 50.968674, 8.59, 9.72 +GPS, 3, 309072600, 9, 1.75, 24.2397984, 54.5792462, 47.38, 62.81, 2.65, 121.90 +ATT, 8.59, 9.11, 9.72, 6.00, 0.00, 235.10, 238.02 +CTUN, 286, 4.80, 51.88, 26.000000, 0, 1, -138, 702, 0 +NTUN, 4.00, 0.94, -29.619865, 391.596190, -23.285477, 307.850980, -29.666311, 311.005220, 221.516850, 42.211372, 9.20, 9.22 +ATT, 9.20, 9.30, 9.22, 5.98, 0.00, 236.19, 238.02 +CTUN, 286, 4.80, 52.21, 26.000000, 0, 1, -136, 675, 0 +NTUN, 3.81, 0.93, -20.735466, 374.033690, -16.594879, 299.344300, -25.818489, 309.435420, 223.243530, 33.775414, 9.67, 8.74 +GPS, 3, 309072800, 10, 1.49, 24.2397960, 54.5792508, 47.62, 63.00, 2.70, 120.69 +ATT, 9.67, 10.20, 8.74, 5.52, 0.00, 236.84, 238.02 +CTUN, 286, 3.69, 52.21, 26.000000, 0, 1, -133, 695, 0 +NTUN, 3.63, 0.92, -11.606926, 355.792480, -9.466495, 290.180850, -19.643200, 303.147130, 229.283840, 24.365479, 10.32, 8.41 +ATT, 10.32, 10.34, 8.41, 4.23, 0.00, 237.14, 238.02 +CTUN, 285, 3.69, 52.03, 26.000000, 0, 1, -136, 695, 0 +NTUN, 3.45, 0.91, -3.034904, 338.230590, -2.521475, 281.010530, -13.778031, 294.234920, 229.450200, 22.296814, 10.43, 8.28 +GPS, 3, 309073000, 10, 1.49, 24.2397938, 54.5792554, 47.85, 63.21, 2.63, 119.38 +ATT, 10.43, 10.98, 8.28, 3.53, 0.00, 237.18, 238.02 +CTUN, 285, 2.43, 52.27, 26.000000, 0, 1, -123, 670, 0 +NTUN, 3.27, 0.89, 5.349739, 320.591550, 4.529256, 271.422820, -6.153962, 284.912350, 228.809220, 19.072205, 10.46, 8.15 +DU32, 7, 393457 +CURR, 286, 509386, 1134, 0, 4752, 0.000000 +ATT, 10.46, 11.86, 8.15, 3.77, 0.00, 237.06, 238.02 +CTUN, 285, 2.54, 52.44, 26.000000, 0, 1, -128, 701, 0 +NTUN, 3.10, 0.88, 13.168953, 303.886470, 11.352031, 261.959230, -1.071572, 276.136410, 230.227750, 17.364075, 10.60, 8.09 +GPS, 3, 309073200, 10, 1.49, 24.2397916, 54.5792600, 48.10, 63.41, 2.64, 118.20 +ATT, 10.60, 11.95, 8.09, 3.61, 0.00, 237.27, 238.02 +CTUN, 285, 2.54, 52.43, 26.000000, 0, 1, -143, 692, 0 +NTUN, 2.95, 0.86, 20.533577, 290.117310, 17.965347, 253.830980, 7.739331, 263.991150, 226.133160, 33.717499, 9.93, 8.72 +ATT, 9.93, 12.01, 8.72, 2.96, 0.00, 237.17, 238.02 +CTUN, 285, 3.96, 52.57, 26.000000, 0, 1, -127, 666, 0 +NTUN, 2.83, 0.85, 27.293098, 277.118530, 24.215338, 245.868700, 13.517757, 253.555160, 222.881090, 39.165543, 9.57, 8.93 +GPS, 3, 309073400, 10, 1.49, 24.2397895, 54.5792647, 48.33, 63.61, 2.63, 117.24 +ATT, 9.57, 12.62, 8.93, 2.87, 0.00, 237.18, 238.02 +CTUN, 285, 2.54, 52.68, 26.000000, 0, 2, -130, 709, 0 +NTUN, 2.68, 0.83, 34.460945, 260.539920, 31.124741, 235.316740, 19.215595, 243.002460, 231.094020, 12.480438, 10.92, 7.71 +ATT, 10.92, 11.82, 7.71, 2.77, 0.00, 238.55, 238.02 +CTUN, 286, 3.96, 52.79, 26.000000, 0, 1, -145, 694, 0 +NTUN, 2.53, 0.81, 41.224495, 244.788330, 37.859127, 224.805010, 25.212904, 234.121870, 231.343870, 9.882660, 11.20, 7.30 +GPS, 3, 309073600, 10, 1.49, 24.2397875, 54.5792691, 48.57, 63.83, 2.50, 116.93 +ATT, 11.20, 11.94, 7.30, 2.00, 0.00, 239.97, 238.02 +CTUN, 286, 3.96, 52.95, 26.000000, 0, 0, -129, 656, 0 +NTUN, 2.39, 0.79, 47.936653, 229.169920, 44.734993, 213.863800, 32.439617, 223.245450, 233.077880, 6.671211, 11.50, 7.00 diff --git a/Tools/LogAnalyzer/logs/underpowered.log b/Tools/LogAnalyzer/logs/underpowered.log new file mode 100644 index 0000000000..7c3cf66768 --- /dev/null +++ b/Tools/LogAnalyzer/logs/underpowered.log @@ -0,0 +1,9888 @@ +1 + +ArduCopter V3.0.1 +Free RAM: 1696 +APM 2 +FMT, 128, 89, FMT, BBnNZ, Type,Length,Name,Format +FMT, 129, 23, PARM, Nf, Name,Value +FMT, 130, 35, GPS, BIBcLLeeEe, Status,Time,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs +FMT, 131, 27, IMU, ffffff, GyrX,GyrY,GyrZ,AccX,AccY,AccZ +FMT, 132, 67, MSG, Z, Message +FMT, 9, 19, CURR, hIhhhf, Thr,ThrInt,Volt,Curr,Vcc,CurrTot +FMT, 11, 11, MOT, hhhh, Mot1,Mot2,Mot3,Mot4 +FMT, 12, 28, OF, hhBccffee, Dx,Dy,SQual,X,Y,Lat,Lng,Roll,Pitch +FMT, 5, 49, NTUN, Ecffffffffee, WPDst,WPBrg,PErX,PErY,DVelX,DVelY,VelX,VelY,DAcX,DAcY,DRol,DPit +FMT, 4, 25, CTUN, hcefhhhhh, ThrIn,SonAlt,BarAlt,WPAlt,NavThr,AngBst,CRate,ThrOut,DCRate +FMT, 15, 21, MAG, hhhhhhhhh, MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ +FMT, 6, 17, PM, BBBHHIhB, RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr +FMT, 8, 20, CMD, BBBBBeLL, CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng +FMT, 1, 17, ATT, cccccCC, RollIn,Roll,PitchIn,Pitch,YawIn,Yaw,NavYaw +FMT, 17, 37, INAV, cccfffiiff, BAlt,IAlt,IClb,ACorrX,ACorrY,ACorrZ,GLat,GLng,ILat,ILng +FMT, 3, 6, MODE, Mh, Mode,ThrCrs +FMT, 10, 3, STRT, , +FMT, 13, 4, EV, B, Id +FMT, 20, 6, D16, Bh, Id,Value +FMT, 21, 6, DU16, BH, Id,Value +FMT, 22, 8, D32, Bi, Id,Value +FMT, 23, 8, DU32, BI, Id,Value +FMT, 24, 8, DFLT, Bf, Id,Value +FMT, 14, 28, PID, Biiiiif, Id,Error,P,I,D,Out,Gain +FMT, 16, 15, DMP, ccccCC, DCMRoll,DMPRoll,DCMPtch,DMPPtch,DCMYaw,DMPYaw +FMT, 18, 25, CAM, ILLeccC, GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw +FMT, 19, 5, ERR, BB, Subsys,ECode +PARM, SYSID_SW_MREV, 120.000000 +PARM, SYSID_SW_TYPE, 10.000000 +PARM, SYSID_THISMAV, 1.000000 +PARM, SYSID_MYGCS, 253.000000 +PARM, SERIAL3_BAUD, 57.000000 +PARM, TELEM_DELAY, 0.000000 +PARM, RTL_ALT, 1500.000000 +PARM, SONAR_ENABLE, 1.000000 +PARM, SONAR_TYPE, 0.000000 +PARM, SONAR_GAIN, 0.200000 +PARM, BATT_MONITOR, 4.000000 +PARM, FS_BATT_ENABLE, 0.000000 +PARM, FS_GPS_ENABLE, 1.000000 +PARM, FS_GCS_ENABLE, 0.000000 +PARM, VOLT_DIVIDER, 15.701050 +PARM, AMP_PER_VOLT, 27.320000 +PARM, BATT_CAPACITY, 4000.000000 +PARM, MAG_ENABLE, 1.000000 +PARM, FLOW_ENABLE, 0.000000 +PARM, LOW_VOLT, 9.400000 +PARM, SUPER_SIMPLE, 0.000000 +PARM, RTL_ALT_FINAL, 200.000000 +PARM, BATT_VOLT_PIN, 1.000000 +PARM, BATT_CURR_PIN, 2.000000 +PARM, RSSI_PIN, -1.000000 +PARM, THR_ACC_ENABLE, 1.000000 +PARM, WP_YAW_BEHAVIOR, 2.000000 +PARM, WP_TOTAL, 2.000000 +PARM, WP_INDEX, 0.000000 +PARM, CIRCLE_RADIUS, 10.000000 +PARM, CIRCLE_RATE, 5.000000 +PARM, RTL_LOIT_TIME, 5000.000000 +PARM, LAND_SPEED, 50.000000 +PARM, PILOT_VELZ_MAX, 250.000000 +PARM, THR_MIN, 130.000000 +PARM, THR_MAX, 1000.000000 +PARM, FS_THR_ENABLE, 0.000000 +PARM, FS_THR_VALUE, 975.000000 +PARM, TRIM_THROTTLE, 782.000000 +PARM, THR_MID, 500.000000 +PARM, FLTMODE1, 0.000000 +PARM, FLTMODE2, 5.000000 +PARM, FLTMODE3, 2.000000 +PARM, FLTMODE4, 7.000000 +PARM, FLTMODE5, 6.000000 +PARM, FLTMODE6, 8.000000 +PARM, SIMPLE, 0.000000 +PARM, LOG_BITMASK, 830.000000 +PARM, TOY_RATE, 1.000000 +PARM, ESC, 0.000000 +PARM, TUNE, 0.000000 +PARM, TUNE_LOW, 0.000000 +PARM, TUNE_HIGH, 1000.000000 +PARM, FRAME, 2.000000 +PARM, CH7_OPT, 7.000000 +PARM, CH8_OPT, 0.000000 +PARM, ARMING_CHECK, 0.000000 +PARM, RC1_MIN, 988.000000 +PARM, RC1_TRIM, 1498.000000 +PARM, RC1_MAX, 2003.000000 +PARM, RC1_REV, -1.000000 +PARM, RC1_DZ, 30.000000 +PARM, RC2_MIN, 986.000000 +PARM, RC2_TRIM, 1498.000000 +PARM, RC2_MAX, 2010.000000 +PARM, RC2_REV, -1.000000 +PARM, RC2_DZ, 30.000000 +PARM, RC3_MIN, 986.000000 +PARM, RC3_TRIM, 989.000000 +PARM, RC3_MAX, 2014.000000 +PARM, RC3_REV, 1.000000 +PARM, RC3_DZ, 30.000000 +PARM, RC4_MIN, 985.000000 +PARM, RC4_TRIM, 1502.000000 +PARM, RC4_MAX, 2010.000000 +PARM, RC4_REV, 1.000000 +PARM, RC4_DZ, 40.000000 +PARM, RC5_MIN, 1175.000000 +PARM, RC5_TRIM, 1179.000000 +PARM, RC5_MAX, 1839.000000 +PARM, RC5_REV, 1.000000 +PARM, RC5_DZ, 0.000000 +PARM, RC5_FUNCTION, 0.000000 +PARM, RC6_MIN, 985.000000 +PARM, RC6_TRIM, 990.000000 +PARM, RC6_MAX, 2014.000000 +PARM, RC6_REV, 1.000000 +PARM, RC6_DZ, 0.000000 +PARM, RC6_FUNCTION, 0.000000 +PARM, RC7_MIN, 985.000000 +PARM, RC7_TRIM, 989.000000 +PARM, RC7_MAX, 2014.000000 +PARM, RC7_REV, 1.000000 +PARM, RC7_DZ, 0.000000 +PARM, RC7_FUNCTION, 0.000000 +PARM, RC8_MIN, 1498.000000 +PARM, RC8_TRIM, 1498.000000 +PARM, RC8_MAX, 1499.000000 +PARM, RC8_REV, 1.000000 +PARM, RC8_DZ, 0.000000 +PARM, RC8_FUNCTION, 0.000000 +PARM, RC10_MIN, 1100.000000 +PARM, RC10_TRIM, 1500.000000 +PARM, RC10_MAX, 1900.000000 +PARM, RC10_REV, 1.000000 +PARM, RC10_DZ, 0.000000 +PARM, RC10_FUNCTION, 0.000000 +PARM, RC11_MIN, 1100.000000 +PARM, RC11_TRIM, 1500.000000 +PARM, RC11_MAX, 1900.000000 +PARM, RC11_REV, 1.000000 +PARM, RC11_DZ, 0.000000 +PARM, RC11_FUNCTION, 0.000000 +PARM, RC_SPEED, 490.000000 +PARM, ACRO_P, 4.500000 +PARM, AXIS_ENABLE, 1.000000 +PARM, ACRO_BAL_ROLL, 200.000000 +PARM, ACRO_BAL_PITCH, 200.000000 +PARM, ACRO_TRAINER, 1.000000 +PARM, LED_MODE, 9.000000 +PARM, RATE_RLL_P, 0.150000 +PARM, RATE_RLL_I, 0.100000 +PARM, RATE_RLL_D, 0.004000 +PARM, RATE_RLL_IMAX, 500.000000 +PARM, RATE_PIT_P, 0.150000 +PARM, RATE_PIT_I, 0.100000 +PARM, RATE_PIT_D, 0.004000 +PARM, RATE_PIT_IMAX, 500.000000 +PARM, RATE_YAW_P, 0.200000 +PARM, RATE_YAW_I, 0.020000 +PARM, RATE_YAW_D, 0.000000 +PARM, RATE_YAW_IMAX, 800.000000 +PARM, LOITER_LAT_P, 1.000000 +PARM, LOITER_LAT_I, 0.500000 +PARM, LOITER_LAT_D, 0.000000 +PARM, LOITER_LAT_IMAX, 400.000000 +PARM, LOITER_LON_P, 1.000000 +PARM, LOITER_LON_I, 0.500000 +PARM, LOITER_LON_D, 0.000000 +PARM, LOITER_LON_IMAX, 400.000000 +PARM, THR_RATE_P, 6.000000 +PARM, THR_RATE_I, 0.000000 +PARM, THR_RATE_D, 0.000000 +PARM, THR_RATE_IMAX, 300.000000 +PARM, THR_ACCEL_P, 0.750000 +PARM, THR_ACCEL_I, 1.500000 +PARM, THR_ACCEL_D, 0.000000 +PARM, THR_ACCEL_IMAX, 500.000000 +PARM, OF_RLL_P, 2.500000 +PARM, OF_RLL_I, 0.500000 +PARM, OF_RLL_D, 0.120000 +PARM, OF_RLL_IMAX, 100.000000 +PARM, OF_PIT_P, 2.500000 +PARM, OF_PIT_I, 0.500000 +PARM, OF_PIT_D, 0.120000 +PARM, OF_PIT_IMAX, 100.000000 +PARM, STB_RLL_P, 4.500000 +PARM, STB_RLL_I, 0.000000 +PARM, STB_RLL_IMAX, 800.000000 +PARM, STB_PIT_P, 4.500000 +PARM, STB_PIT_I, 0.000000 +PARM, STB_PIT_IMAX, 800.000000 +PARM, STB_YAW_P, 4.500000 +PARM, STB_YAW_I, 0.000000 +PARM, STB_YAW_IMAX, 800.000000 +PARM, THR_ALT_P, 1.000000 +PARM, THR_ALT_I, 0.000000 +PARM, THR_ALT_IMAX, 300.000000 +PARM, HLD_LAT_P, 1.000000 +PARM, HLD_LAT_I, 0.000000 +PARM, HLD_LAT_IMAX, 3000.000000 +PARM, HLD_LON_P, 1.000000 +PARM, HLD_LON_I, 0.000000 +PARM, HLD_LON_IMAX, 3000.000000 +PARM, CAM_TRIGG_TYPE, 0.000000 +PARM, CAM_DURATION, 10.000000 +PARM, CAM_SERVO_ON, 1300.000000 +PARM, CAM_SERVO_OFF, 1100.000000 +PARM, COMPASS_OFS_X, 0.000000 +PARM, COMPASS_OFS_Y, 0.000000 +PARM, COMPASS_OFS_Z, 0.000000 +PARM, COMPASS_DEC, 0.000000 +PARM, COMPASS_LEARN, 0.000000 +PARM, COMPASS_USE, 1.000000 +PARM, COMPASS_AUTODEC, 1.000000 +PARM, COMPASS_MOTCT, 0.000000 +PARM, COMPASS_MOT_X, 0.000000 +PARM, COMPASS_MOT_Y, 0.000000 +PARM, COMPASS_MOT_Z, 0.000000 +PARM, COMPASS_ORIENT, 0.000000 +PARM, INS_PRODUCT_ID, 88.000000 +PARM, INS_ACCSCAL_X, 1.002061 +PARM, INS_ACCSCAL_Y, 1.000603 +PARM, INS_ACCSCAL_Z, 0.988811 +PARM, INS_ACCOFFS_X, -0.071901 +PARM, INS_ACCOFFS_Y, 0.362812 +PARM, INS_ACCOFFS_Z, 0.146283 +PARM, INS_GYROFFS_X, -0.000372 +PARM, INS_GYROFFS_Y, -0.027095 +PARM, INS_GYROFFS_Z, -0.009971 +PARM, INS_MPU6K_FILTER, 0.000000 +PARM, INAV_TC_XY, 2.500000 +PARM, INAV_TC_Z, 5.000000 +PARM, WPNAV_SPEED, 500.000000 +PARM, WPNAV_RADIUS, 200.000000 +PARM, WPNAV_SPEED_UP, 250.000000 +PARM, WPNAV_SPEED_DN, 150.000000 +PARM, WPNAV_LOIT_SPEED, 500.000000 +PARM, WPNAV_ACCEL, 100.000000 +PARM, SR0_RAW_SENS, 0.000000 +PARM, SR0_EXT_STAT, 0.000000 +PARM, SR0_RC_CHAN, 0.000000 +PARM, SR0_RAW_CTRL, 0.000000 +PARM, SR0_POSITION, 0.000000 +PARM, SR0_EXTRA1, 0.000000 +PARM, SR0_EXTRA2, 0.000000 +PARM, SR0_EXTRA3, 0.000000 +PARM, SR0_PARAMS, 0.000000 +PARM, SR3_RAW_SENS, 0.000000 +PARM, SR3_EXT_STAT, 0.000000 +PARM, SR3_RC_CHAN, 0.000000 +PARM, SR3_RAW_CTRL, 0.000000 +PARM, SR3_POSITION, 0.000000 +PARM, SR3_EXTRA1, 0.000000 +PARM, SR3_EXTRA2, 0.000000 +PARM, SR3_EXTRA3, 0.000000 +PARM, SR3_PARAMS, 0.000000 +PARM, AHRS_GPS_GAIN, 1.000000 +PARM, AHRS_GPS_USE, 1.000000 +PARM, AHRS_YAW_P, 0.100000 +PARM, AHRS_RP_P, 0.100000 +PARM, AHRS_WIND_MAX, 0.000000 +PARM, AHRS_TRIM_X, 0.002719 +PARM, AHRS_TRIM_Y, 0.013084 +PARM, AHRS_TRIM_Z, 0.000000 +PARM, AHRS_ORIENTATION, 0.000000 +PARM, AHRS_COMP_BETA, 0.100000 +PARM, AHRS_GPS_MINSATS, 6.000000 +PARM, MNT_MODE, 0.000000 +PARM, MNT_RETRACT_X, 0.000000 +PARM, MNT_RETRACT_Y, 0.000000 +PARM, MNT_RETRACT_Z, 0.000000 +PARM, MNT_NEUTRAL_X, 0.000000 +PARM, MNT_NEUTRAL_Y, 0.000000 +PARM, MNT_NEUTRAL_Z, 0.000000 +PARM, MNT_CONTROL_X, 0.000000 +PARM, MNT_CONTROL_Y, 0.000000 +PARM, MNT_CONTROL_Z, 0.000000 +PARM, MNT_STAB_ROLL, 0.000000 +PARM, MNT_STAB_TILT, 0.000000 +PARM, MNT_STAB_PAN, 0.000000 +PARM, MNT_RC_IN_ROLL, 0.000000 +PARM, MNT_ANGMIN_ROL, -4500.000000 +PARM, MNT_ANGMAX_ROL, 4500.000000 +PARM, MNT_RC_IN_TILT, 0.000000 +PARM, MNT_ANGMIN_TIL, -4500.000000 +PARM, MNT_ANGMAX_TIL, 4500.000000 +PARM, MNT_RC_IN_PAN, 0.000000 +PARM, MNT_ANGMIN_PAN, -4500.000000 +PARM, MNT_ANGMAX_PAN, 4500.000000 +PARM, MNT_JSTICK_SPD, 0.000000 +PARM, GND_ABS_PRESS, 99088.188000 +PARM, GND_TEMP, 27.673569 +PARM, SCHED_DEBUG, 0.000000 +PARM, FENCE_ENABLE, 0.000000 +PARM, FENCE_TYPE, 3.000000 +PARM, FENCE_ACTION, 1.000000 +PARM, FENCE_ALT_MAX, 100.000000 +PARM, FENCE_RADIUS, 150.000000 +PARM, MOT_TCRV_ENABLE, 1.000000 +PARM, MOT_TCRV_MIDPCT, 52.000000 +PARM, MOT_TCRV_MAXPCT, 93.000000 +D32, 9, 6794 +EV, 10 +EV, 15 +ERR, 7, 1 +CTUN, 164, 1.98, -0.01, 0.000000, 0, 0, 14, 165, 0 +ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.94, 67.94 +CTUN, 165, 1.98, 0.03, 0.000000, 0, 0, 13, 164, 0 +ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.91, 67.94 +CTUN, 165, 1.98, -0.11, 0.000000, 0, 0, 12, 165, 0 +ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.87, 67.94 +CTUN, 164, 1.98, -0.26, 0.000000, 0, 0, 11, 165, 0 +ATT, 0.00, 0.02, -2.24, 0.04, 0.00, 67.82, 67.94 +CTUN, 165, 1.98, -0.52, 0.000000, 0, 0, 10, 165, 0 +ATT, 0.00, 0.01, -2.24, 0.04, 0.00, 67.78, 67.94 +CTUN, 165, 1.98, -0.65, 0.000000, 0, 0, 9, 165, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.74, 67.94 +CTUN, 164, 1.99, -0.66, 0.000000, 0, 0, 7, 164, 0 +DU32, 7, 133372 +CURR, 164, 1153, 1198, 297, 5028, 0.654078 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.71, 67.94 +CTUN, 165, 1.98, -0.80, 0.000000, 0, 0, 6, 165, 0 +ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.69, 67.94 +CTUN, 165, 1.98, -0.76, 0.000000, 0, 0, 5, 164, 0 +ATT, 0.00, 0.02, -2.24, 0.03, 0.00, 67.66, 67.94 +CTUN, 164, 1.98, -0.71, 0.000000, 0, 0, 3, 164, 0 +ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.63, 67.94 +CTUN, 158, 1.99, -0.70, 0.000000, 0, 0, 2, 165, 0 +ATT, 0.00, 0.01, -2.14, 0.03, 0.00, 67.60, 67.60 +CTUN, 0, 1.99, -0.94, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.58, 67.58 +CTUN, 0, 1.99, -0.71, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.99, -0.51, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.02, -2.14, 0.03, 0.00, 67.59, 67.59 +CTUN, 0, 1.99, -0.42, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.02, 0.00, 67.57, 67.57 +CTUN, 0, 1.99, -0.23, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.59, 67.59 +PM, 0, 0, 0, 2, 1000, 6014860, 0, 0 +CTUN, 0, 1.99, -0.15, 0.000000, 0, 0, -3, 0, 0 +DU32, 7, 133308 +CURR, 0, 1811, 1210, 0, 5028, 1.030283 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.59, 67.59 +CTUN, 0, 1.99, -0.22, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 +CTUN, 0, 1.99, -0.24, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.59, 67.59 +CTUN, 0, 1.99, -0.09, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 +CTUN, 0, 1.99, -0.13, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 +CTUN, 0, 1.99, -0.10, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.14, 0.03, 0.00, 67.58, 67.58 +CTUN, 0, 1.99, -0.08, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 +CTUN, 0, 1.98, -0.14, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.58, 67.58 +CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.07, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.07, 0.000000, 0, 0, -4, 0, 0 +DU32, 7, 133308 +CURR, 0, 1811, 1212, 0, 5051, 1.031275 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.13, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.12, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.17, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, -0.11, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.15, 0.000000, 0, 0, -4, 0, 0 +DU32, 7, 133308 +CURR, 0, 1811, 1213, 0, 5051, 1.031928 +ATT, 0.00, 0.01, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.42, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.15, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.00, -2.33, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.56 +CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.57, 67.57 +CTUN, 133, 1.98, -0.06, 0.000000, 0, 0, -3, 0, 0 +EV, 15 +ATT, 0.00, 0.00, -2.33, 0.03, 0.00, 67.57, 67.57 +CTUN, 160, 1.98, 0.00, 0.000000, 0, 0, -3, 152, 0 +DU32, 7, 133372 +CURR, 163, 1963, 1195, 281, 5051, 1.110572 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.56, 67.57 +CTUN, 176, 1.98, -0.07, 0.000000, 0, 0, -3, 170, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.53, 67.57 +CTUN, 194, 1.98, -0.07, 0.000000, 0, 0, -3, 191, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.50, 67.57 +CTUN, 212, 1.98, -0.09, 0.000000, 0, 0, -2, 210, 0 +ATT, 0.00, 0.00, -2.24, 0.03, 0.00, 67.48, 67.57 +CTUN, 235, 1.98, -0.26, 0.000000, 0, 0, -2, 232, 0 +ATT, 0.00, -0.01, -2.24, 0.03, 0.00, 67.46, 67.57 +CTUN, 245, 1.98, -0.46, 0.000000, 0, 0, -2, 244, 0 +ATT, 0.00, 0.00, -2.24, 0.02, 0.00, 67.44, 67.57 +CTUN, 276, 1.98, -0.43, 0.000000, 0, 0, -3, 261, 0 +ATT, 0.00, 0.00, -2.24, 0.02, 0.00, 67.40, 67.57 +CTUN, 298, 1.98, -0.58, 0.000000, 0, 0, -3, 298, 0 +ATT, 0.00, 0.00, -2.24, 0.02, 0.00, 67.37, 67.57 +CTUN, 324, 1.98, -0.65, 0.000000, 0, 0, -4, 320, 0 +ATT, 0.00, -0.01, -2.24, 0.02, 0.00, 67.33, 67.57 +CTUN, 351, 1.98, -0.68, 0.000000, 0, 0, -4, 345, 0 +ATT, 0.00, -0.02, -2.24, 0.01, 0.00, 67.29, 67.57 +CTUN, 372, 1.98, -1.01, 0.000000, 0, 0, -4, 372, 0 +DU32, 7, 133372 +CURR, 381, 4606, 1179, 619, 5051, 2.136434 +ATT, 0.00, -0.02, -2.24, 0.01, 0.00, 67.24, 67.57 +CTUN, 395, 1.98, -1.06, 0.000000, 0, 0, -5, 395, 0 +ATT, 0.00, -0.02, -2.24, 0.01, 0.00, 67.18, 67.57 +CTUN, 406, 1.98, -1.30, 0.000000, 0, 0, -7, 406, 0 +ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 67.12, 67.57 +EV, 16 +CTUN, 422, 1.98, -1.34, 0.000000, 0, 0, -7, 422, 0 +ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 67.05, 67.57 +CTUN, 434, 1.99, -1.49, 0.000000, 0, 0, -8, 432, 0 +ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 66.98, 67.57 +CTUN, 439, 1.99, -1.52, 0.000000, 0, 0, -10, 438, 0 +ATT, 0.00, -0.03, -2.24, 0.00, 0.00, 66.92, 67.57 +CTUN, 442, 1.99, -1.61, 0.000000, 0, 0, -11, 439, 0 +ATT, 0.00, -0.04, -2.24, 0.00, 0.00, 66.84, 67.57 +CTUN, 453, 1.99, -1.75, 0.000000, 0, 0, -12, 453, 0 +ATT, 0.00, -0.04, -2.24, 0.00, 0.00, 66.77, 67.57 +CTUN, 469, 2.00, -1.81, 0.000000, 0, 0, -13, 468, 0 +ATT, 0.00, -0.05, -2.33, 0.00, 0.00, 66.68, 67.57 +CTUN, 488, 2.00, -1.98, 0.000000, 0, 0, -14, 488, 0 +ATT, 0.00, -0.07, -2.33, 0.00, 0.00, 66.60, 67.57 +CTUN, 508, 3.83, -1.99, 0.000000, 0, 0, -15, 504, 0 +DU32, 7, 166140 +CURR, 510, 9051, 1149, 1139, 5028, 4.570772 +ATT, 0.00, -0.07, -2.24, -0.01, 0.00, 66.51, 67.57 +CTUN, 510, 2.03, -2.03, 0.000000, 0, 0, -16, 510, 0 +ATT, 0.00, -0.08, -2.24, -0.02, 0.00, 66.40, 67.57 +CTUN, 519, 2.03, -2.20, 0.000000, 0, 0, -16, 517, 0 +ATT, 0.00, -0.09, -2.24, -0.02, 0.00, 66.31, 67.57 +CTUN, 535, 1.99, -2.46, 0.000000, 0, 0, -18, 535, 0 +ATT, 0.00, -0.10, -2.24, -0.01, 0.00, 66.21, 67.57 +CTUN, 543, 1.99, -2.24, 0.000000, 0, 0, -20, 541, 0 +ATT, 0.00, -0.12, -2.24, -0.02, 0.00, 66.10, 67.57 +CTUN, 545, 1.99, -2.40, 0.000000, 0, 0, -19, 545, 0 +ATT, 0.00, -0.14, -2.24, -0.03, 0.00, 65.99, 67.57 +CTUN, 571, 1.99, -2.24, 0.000000, 0, 0, -25, 565, 0 +ATT, 0.00, -0.20, -2.24, -0.04, 0.00, 65.88, 67.57 +CTUN, 588, 1.99, -2.37, 0.000000, 0, 0, -26, 588, 0 +ATT, 0.00, -0.38, -2.14, -0.03, 0.00, 65.79, 67.57 +CTUN, 597, 1.99, -2.22, 0.000000, 0, 0, -28, 597, 0 +ATT, 0.00, -0.60, -2.24, -0.01, 0.00, 65.72, 67.57 +CTUN, 621, 1.99, -2.71, 0.000000, 0, 0, -28, 621, 0 +ATT, 0.00, -1.44, -2.24, 0.04, 0.00, 65.68, 67.57 +CTUN, 636, 3.00, -2.47, 0.000000, 0, 0, -25, 636, 0 +DU32, 7, 166140 +CURR, 636, 14706, 1111, 1700, 5051, 8.368493 +ATT, 0.00, -2.69, -2.24, -0.44, 0.00, 65.88, 67.57 +CTUN, 639, 3.00, -2.12, 0.000000, 0, 0, -25, 639, 0 +ATT, 0.00, -3.88, -2.05, -2.01, 0.00, 66.52, 67.57 +CTUN, 639, 3.00, -1.85, 0.000000, 0, 1, -21, 638, 0 +ATT, 0.00, -5.46, -2.05, -3.96, 0.00, 67.51, 67.57 +CTUN, 639, 3.00, -1.11, 0.000000, 0, 4, -23, 643, 0 +ATT, 1.96, -7.33, -1.86, -5.06, 0.00, 68.76, 67.57 +CTUN, 639, 3.00, -0.93, 0.000000, 0, 7, -25, 646, 0 +ATT, 2.53, -8.21, -1.21, -6.58, 0.00, 70.50, 67.57 +CTUN, 639, 2.59, -1.00, 0.000000, 0, 9, -29, 648, 0 +ATT, 2.90, -8.33, 0.00, -7.53, 0.00, 72.38, 67.57 +CTUN, 639, 2.59, -0.78, 0.000000, 0, 9, -31, 648, 0 +ATT, 5.06, -8.06, 0.00, -7.18, 0.00, 73.85, 67.57 +CTUN, 639, 0.21, -0.72, 0.000000, 0, 8, -35, 647, 0 +ATT, 6.28, -6.97, 0.00, -6.10, 0.00, 75.00, 67.57 +CTUN, 638, 0.21, -1.16, 0.000000, 0, 5, -38, 643, 0 +ATT, 7.40, -4.56, 0.00, -5.31, 0.00, 76.14, 67.57 +CTUN, 639, 0.20, -1.86, 0.000000, 0, 2, -39, 641, 0 +ATT, 7.78, -2.30, 0.00, -3.88, 0.00, 76.58, 67.57 +CTUN, 641, 0.21, -1.72, 0.000000, 0, 1, -37, 643, 0 +DU32, 7, 166140 +CURR, 641, 21139, 1119, 1700, 5051, 13.092842 +ATT, 7.87, -0.48, 0.00, -2.13, 0.00, 76.59, 67.57 +CTUN, 655, 0.21, -2.22, 0.000000, 0, 0, -34, 653, 0 +ATT, 8.53, -0.11, 0.37, -0.19, 0.00, 76.29, 67.57 +CTUN, 662, 2.57, -2.02, 0.000000, 0, 0, -23, 661, 0 +ATT, 10.03, -0.78, 4.01, -0.78, 0.00, 76.19, 67.57 +CTUN, 663, 2.57, -1.90, 0.000000, 0, 0, -22, 663, 0 +ATT, 12.37, -1.41, 5.60, -0.77, 0.00, 76.10, 67.57 +CTUN, 666, 5.86, -2.13, 0.000000, 0, 0, -26, 666, 0 +ATT, 15.46, -0.51, 6.53, -1.91, 0.00, 76.35, 67.57 +CTUN, 666, 5.86, -2.17, 0.000000, 0, 0, -29, 666, 0 +ATT, 18.09, -0.18, 8.02, -1.83, 0.00, 76.12, 67.57 +CTUN, 666, 7.61, -1.94, 0.000000, 0, 0, -29, 666, 0 +ATT, 18.65, -0.01, 8.21, -0.67, 0.00, 75.66, 67.57 +CTUN, 680, 7.61, -2.30, 0.000000, 0, 0, -27, 678, 0 +ATT, 19.87, -0.07, 12.04, -0.72, 0.00, 75.50, 67.57 +CTUN, 711, 7.61, -2.32, 0.000000, 0, 0, -25, 702, 0 +ATT, 18.75, -0.20, 13.25, -1.65, 0.00, 75.27, 67.57 +CTUN, 711, 7.51, -2.44, 0.000000, 0, 0, -25, 711, 0 +ATT, 16.40, -0.60, 16.24, -1.70, 0.00, 74.87, 67.57 +CTUN, 713, 7.51, -2.31, 0.000000, 0, 0, -25, 711, 0 +DU32, 7, 166140 +CURR, 713, 27907, 1086, 2084, 5051, 18.359875 +ATT, 14.53, -1.87, 20.16, -0.42, 0.00, 74.30, 67.57 +CTUN, 711, 2.11, -2.13, 0.000000, 0, 0, -24, 711, 0 +ATT, 15.00, -2.86, 21.56, 0.01, 0.00, 74.29, 67.57 +CTUN, 711, 2.11, -1.97, 0.000000, 0, 0, -25, 711, 0 +ATT, 15.37, -3.63, 21.56, 0.16, 0.00, 74.57, 67.57 +CTUN, 711, 2.11, -1.83, 0.000000, 0, 1, -30, 711, 0 +ATT, 15.56, -3.58, 23.52, 0.17, 0.00, 74.74, 67.57 +CTUN, 713, 6.65, -1.50, 0.000000, 0, 1, -30, 713, 0 +ATT, 15.56, -2.99, 25.02, 0.11, 0.00, 74.67, 67.57 +CTUN, 723, 6.65, -1.92, 0.000000, 0, 0, -30, 723, 0 +ATT, 15.46, -2.17, 26.14, 0.03, 0.00, 74.46, 67.57 +CTUN, 750, 7.57, -1.99, 0.000000, 0, 0, -27, 748, 0 +ATT, 15.56, -2.01, 26.42, 0.00, 0.00, 74.29, 67.57 +CTUN, 765, 6.65, -1.75, 0.000000, 0, 0, -27, 765, 0 +ATT, 15.65, -2.04, 28.66, 0.00, 0.00, 74.07, 67.57 +CTUN, 771, 7.51, -1.74, 0.000000, 0, 0, -27, 770, 0 +ATT, 15.56, -1.79, 28.66, -0.04, 0.00, 73.89, 67.57 +CTUN, 796, 7.51, -1.44, 0.000000, 0, 0, -26, 796, 0 +ATT, 15.56, -1.43, 29.12, -0.09, 0.00, 73.72, 67.57 +CTUN, 835, 7.65, -1.41, 0.000000, 0, 0, -28, 821, 0 +DU32, 7, 166140 +CURR, 842, 35358, 1077, 2047, 5051, 24.099819 +ATT, 15.56, -1.17, 29.03, -0.13, 0.00, 73.53, 67.57 +CTUN, 868, 7.65, -1.84, 0.000000, 0, 0, -25, 868, 0 +ATT, 15.75, -1.19, 28.47, -0.13, 0.00, 73.37, 67.57 +CTUN, 867, 7.65, -1.42, 0.000000, 0, 0, -27, 871, 0 +ATT, 15.75, -1.25, 19.51, -0.15, 0.00, 73.21, 67.57 +CTUN, 522, 7.65, -1.10, 0.000000, 0, 0, -25, 606, 0 +ATT, 0.00, -1.65, 0.00, -0.18, 0.00, 73.04, 67.57 +CTUN, 133, 7.65, -2.46, 0.000000, 0, 0, -23, 294, 0 +ATT, 0.00, -1.05, -2.24, -0.28, 0.00, 73.14, 73.14 +CTUN, 0, 3.93, -1.91, 0.000000, 0, 0, -24, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.34, 0.00, 73.33, 73.33 +CTUN, 0, 3.93, -1.17, 0.000000, 0, 0, -26, 0, 0 +ATT, 0.00, -0.09, -2.24, -0.33, 0.00, 73.43, 73.43 +CTUN, 0, 1.99, -0.77, 0.000000, 0, 0, -24, 0, 0 +ATT, 0.00, -0.09, -2.24, -0.32, 0.00, 73.56, 73.56 +CTUN, 0, 1.99, -0.42, 0.000000, 0, 0, -23, 0, 0 +ATT, 0.00, -0.09, -2.24, -0.32, 0.00, 73.69, 73.69 +CTUN, 0, 1.99, -0.35, 0.000000, 0, 0, -21, 0, 0 +ATT, 0.00, -0.08, -2.24, -0.31, 0.00, 73.81, 73.81 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +CTUN, 0, 1.99, -0.32, 0.000000, 0, 0, -19, 0, 0 +DU32, 7, 166076 +CURR, 0, 38117, 1193, 0, 5051, 26.202591 +ATT, 0.00, -0.09, -2.24, -0.31, 0.00, 73.95, 73.95 +CTUN, 0, 1.98, -0.16, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.31, 0.00, 74.07, 74.07 +CTUN, 0, 1.98, -0.21, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.31, 0.00, 74.21, 74.21 +CTUN, 0, 1.98, -0.14, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.30, 0.00, 74.34, 74.34 +CTUN, 0, 1.98, -0.17, 0.000000, 0, 0, -10, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.30, 0.00, 74.46, 74.46 +CTUN, 0, 1.98, -0.10, 0.000000, 0, 0, -8, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.30, 0.00, 74.58, 74.58 +CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, -6, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 74.71, 74.71 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 74.83, 74.83 +CTUN, 0, 1.98, -0.05, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 74.95, 74.95 +CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.30, 0.00, 75.08, 75.08 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 0, 0, 0 +DU32, 7, 166076 +CURR, 0, 38117, 1198, 0, 5028, 26.203243 +ATT, 0.00, -0.12, -2.24, -0.30, 0.00, 75.19, 75.19 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.29, 0.00, 75.31, 75.31 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.29, 0.00, 75.42, 75.42 +CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.28, 0.00, 75.53, 75.53 +CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.28, 0.00, 75.64, 75.64 +CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.13, -2.24, -0.28, 0.00, 75.75, 75.75 +CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 9, 0, 0 +ATT, 0.00, -0.13, -2.24, -0.28, 0.00, 75.86, 75.86 +CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.13, -2.24, -0.28, 0.00, 75.96, 75.96 +CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.13, -2.24, -0.27, 0.00, 76.07, 76.07 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.27, 0.00, 76.17, 76.17 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 14, 0, 0 +DU32, 7, 166076 +CURR, 0, 38117, 1200, 0, 5051, 26.203243 +ATT, 0.00, -0.14, -2.24, -0.27, 0.00, 76.28, 76.28 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.27, 0.00, 76.38, 76.38 +CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 16, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.26, 0.00, 76.48, 76.48 +CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 17, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.26, 0.00, 76.58, 76.58 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 18, 0, 0 +ATT, 0.00, -0.15, -2.24, -0.26, 0.00, 76.68, 76.68 +CTUN, 0, 1.98, 0.12, 0.000000, 0, 0, 18, 0, 0 +ATT, 0.00, -0.15, -2.24, -0.26, 0.00, 76.78, 76.78 +CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -0.15, -2.24, -0.26, 0.00, 76.88, 76.88 +CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 20, 0, 0 +ATT, 0.00, -0.15, -2.14, -0.26, 0.00, 76.97, 76.97 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 21, 0, 0 +ATT, 0.00, -0.16, -2.24, -0.26, 0.00, 77.07, 77.07 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 21, 0, 0 +ATT, 0.00, -0.16, -2.24, -0.26, 0.00, 77.16, 77.16 +EV, 15 +CTUN, 191, 1.98, 0.05, 0.000000, 0, 0, 22, 147, 0 +DU32, 7, 166140 +CURR, 244, 38117, 1200, 0, 5051, 26.203583 +ATT, 0.00, -0.16, -2.33, -0.25, 0.00, 77.25, 77.20 +CTUN, 304, 1.98, 0.06, 0.000000, 0, 0, 23, 304, 0 +ATT, 0.00, -0.16, -2.24, -0.25, 0.00, 77.33, 77.20 +CTUN, 171, 1.98, -0.05, 0.000000, 0, 0, 23, 216, 0 +ATT, 0.00, -0.16, -2.24, -0.25, 0.00, 77.38, 77.38 +CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.17, -2.24, -0.25, 0.00, 77.42, 77.42 +CTUN, 0, 1.98, -0.01, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.16, -2.24, -0.24, 0.00, 77.53, 77.53 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.17, -2.24, -0.24, 0.00, 77.62, 77.62 +CTUN, 0, 1.98, -0.08, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.17, -2.24, -0.24, 0.00, 77.70, 77.70 +CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.24, 0.00, 77.80, 77.80 +CTUN, 0, 1.98, -0.05, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.23, 0.00, 77.89, 77.89 +CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.18, -2.14, -0.23, 0.00, 77.98, 77.98 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 26, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1201, 0, 5051, 26.528595 +ATT, 0.00, -0.18, -2.24, -0.23, 0.00, 78.06, 78.06 +CTUN, 0, 1.98, -0.03, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.15, 78.15 +CTUN, 0, 1.98, -0.08, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.23, 78.23 +CTUN, 0, 1.98, -0.06, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.32, 78.32 +CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.41, 78.41 +CTUN, 0, 1.98, 0.11, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.22, 0.00, 78.49, 78.49 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.57, 78.57 +CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.65, 78.65 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.74, 78.74 +CTUN, 0, 1.98, 0.10, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.22, 0.00, 78.82, 78.82 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 28, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1202, 0, 5028, 26.529558 +ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 78.90, 78.90 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 78.98, 78.98 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 79.06, 79.06 +CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.21, 0.00, 79.14, 79.14 +CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.21, 0.00, 79.22, 79.22 +CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.21, 0.00, 79.30, 79.30 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.21, 0.00, 79.39, 79.39 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.20, 0.00, 79.46, 79.46 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.20, 0.00, 79.53, 79.53 +CTUN, 0, 1.98, 0.11, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.61, 79.61 +CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 28, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1203, 0, 5051, 26.530550 +ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.69, 79.69 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.76, 79.76 +CTUN, 0, 1.98, 0.13, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.84, 79.84 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.92, 79.92 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.20, 0.00, 79.99, 79.99 +CTUN, 0, 1.98, 0.09, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.06, 80.06 +CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.14, 80.14 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 28, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.21, 80.21 +CTUN, 0, 1.99, 0.18, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.19, 0.00, 80.28, 80.28 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.18, 0.00, 80.35, 80.35 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 27, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1206, 0, 5028, 26.530890 +ATT, 0.00, -0.21, -2.24, -0.18, 0.00, 80.42, 80.42 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.18, 0.00, 80.49, 80.49 +CTUN, 0, 1.98, 0.01, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.56, 80.56 +CTUN, 0, 1.98, 0.10, 0.000000, 0, 0, 27, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.63, 80.63 +CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.70, 80.70 +CTUN, 0, 1.98, 0.09, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.77, 80.77 +CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.17, 0.00, 80.84, 80.84 +CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 80.90, 80.90 +CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 26, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 80.97, 80.97 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 81.04, 81.04 +CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 25, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1206, 0, 5051, 26.531910 +ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 81.10, 81.10 +CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.16, 0.00, 81.17, 81.17 +CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 25, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.23, 81.23 +CTUN, 0, 1.98, 0.12, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.33, -0.15, 0.00, 81.29, 81.29 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.36, 81.36 +CTUN, 0, 1.98, 0.04, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.42, 81.42 +CTUN, 0, 1.98, 0.03, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.48, 81.48 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.15, 0.00, 81.54, 81.54 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.60, 81.60 +CTUN, 0, 1.98, 0.02, 0.000000, 0, 0, 24, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.66, 81.66 +CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 23, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1206, 0, 5028, 26.531910 +ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.72, 81.72 +CTUN, 0, 1.98, 0.06, 0.000000, 0, 0, 23, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.77, 81.77 +CTUN, 0, 1.98, 0.10, 0.000000, 0, 0, 23, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.83, 81.83 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 23, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.14, 0.00, 81.89, 81.89 +CTUN, 0, 1.99, 0.10, 0.000000, 0, 0, 22, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 81.95, 81.95 +CTUN, 0, 1.99, 0.04, 0.000000, 0, 0, 22, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.01, 82.01 +CTUN, 0, 1.99, 0.10, 0.000000, 0, 0, 22, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.06, 82.06 +CTUN, 0, 1.98, 0.05, 0.000000, 0, 0, 22, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.11, 82.11 +CTUN, 0, 1.98, 0.08, 0.000000, 0, 0, 22, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.17, 82.17 +CTUN, 0, 1.98, -0.02, 0.000000, 0, 0, 21, 0, 0 +PM, 0, 0, 0, 0, 1000, 10460, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.23, 82.23 +CTUN, 0, 1.98, 0.00, 0.000000, 0, 0, 21, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1206, 0, 5051, 26.532589 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.28, 82.28 +CTUN, 0, 1.98, -0.04, 0.000000, 0, 0, 21, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.34, 82.34 +CTUN, 0, 1.99, 0.15, 0.000000, 0, 0, 20, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.39, 82.39 +CTUN, 0, 1.99, 0.06, 0.000000, 0, 0, 20, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.45, 82.45 +CTUN, 0, 1.99, 0.08, 0.000000, 0, 0, 20, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.50, 82.50 +CTUN, 0, 1.99, 0.08, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.55, 82.55 +CTUN, 0, 1.99, 0.10, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -0.21, -2.24, -0.13, 0.00, 82.60, 82.60 +CTUN, 0, 1.99, 0.01, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.13, 0.00, 82.65, 82.65 +CTUN, 0, 1.99, 0.06, 0.000000, 0, 0, 19, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.70, 82.70 +CTUN, 0, 1.99, 0.05, 0.000000, 0, 0, 18, 0, 0 +ATT, 0.00, -0.20, -2.14, -0.12, 0.00, 82.75, 82.75 +CTUN, 0, 1.99, 0.08, 0.000000, 0, 0, 18, 0, 0 +DU32, 7, 166076 +CURR, 0, 38626, 1206, 1, 5028, 26.533581 +ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.80, 82.80 +CTUN, 0, 1.99, 0.07, 0.000000, 0, 0, 18, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.86, 82.86 +CTUN, 0, 1.99, 0.03, 0.000000, 0, 0, 18, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.91, 82.91 +CTUN, 0, 1.98, 0.07, 0.000000, 0, 0, 17, 0, 0 +EV, 15 +ATT, 0.00, -0.20, -2.24, -0.12, 0.00, 82.96, 82.93 +CTUN, 163, 1.98, 0.05, 0.000000, 0, 0, 17, 163, 0 +ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.00, 82.93 +CTUN, 181, 1.98, 0.04, 0.000000, 0, 0, 17, 181, 0 +ATT, 0.00, -0.20, -2.24, -0.11, 0.00, 83.03, 82.93 +CTUN, 181, 1.98, -0.07, 0.000000, 0, 0, 16, 180, 0 +ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.04, 82.93 +CTUN, 181, 1.98, -0.12, 0.000000, 0, 0, 16, 180, 0 +ATT, 0.00, -0.19, -2.24, -0.12, 0.00, 83.07, 82.93 +CTUN, 180, 1.98, -0.13, 0.000000, 0, 0, 16, 181, 0 +ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.11, 82.93 +CTUN, 181, 1.98, -0.24, 0.000000, 0, 0, 15, 180, 0 +ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.15, 82.93 +CTUN, 180, 1.98, -0.16, 0.000000, 0, 0, 15, 181, 0 +DU32, 7, 166140 +CURR, 181, 39870, 1193, 181, 5028, 26.998184 +ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.18, 82.93 +CTUN, 181, 1.98, -0.26, 0.000000, 0, 0, 14, 181, 0 +ATT, 0.00, -0.19, -2.24, -0.12, 0.00, 83.20, 82.93 +CTUN, 181, 1.98, -0.32, 0.000000, 0, 0, 13, 181, 0 +ATT, 0.00, -0.19, -2.24, -0.11, 0.00, 83.25, 82.93 +CTUN, 180, 1.98, -0.33, 0.000000, 0, 0, 13, 181, 0 +ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.28, 82.93 +CTUN, 177, 1.98, -0.42, 0.000000, 0, 0, 12, 178, 0 +ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.31, 82.93 +CTUN, 171, 1.98, -0.38, 0.000000, 0, 0, 12, 171, 0 +ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.34, 82.93 +CTUN, 172, 1.99, -0.37, 0.000000, 0, 0, 10, 171, 0 +ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.37, 82.93 +CTUN, 172, 1.99, -0.39, 0.000000, 0, 0, 10, 171, 0 +ATT, 0.00, -0.18, -2.24, -0.11, 0.00, 83.41, 82.93 +CTUN, 176, 1.99, -0.37, 0.000000, 0, 0, 9, 171, 0 +ATT, 0.00, -0.18, -2.24, -0.10, 0.00, 83.44, 82.93 +CTUN, 226, 1.99, -0.39, 0.000000, 0, 0, 9, 226, 0 +ATT, 0.00, -0.18, -2.24, -0.09, 0.00, 83.47, 82.93 +CTUN, 268, 1.99, -0.29, 0.000000, 0, 0, 9, 263, 0 +DU32, 7, 166140 +CURR, 273, 41732, 1190, 276, 5028, 27.512407 +ATT, 0.00, -0.18, -2.24, -0.09, 0.00, 83.50, 82.93 +CTUN, 279, 1.98, -0.52, 0.000000, 0, 0, 8, 279, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.52, 82.93 +CTUN, 279, 1.98, -0.60, 0.000000, 0, 0, 7, 279, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.53, 82.93 +CTUN, 279, 1.98, -0.76, 0.000000, 0, 0, 7, 279, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.55, 82.93 +CTUN, 284, 1.98, -0.69, 0.000000, 0, 0, 6, 281, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.57, 82.93 +CTUN, 302, 1.98, -0.74, 0.000000, 0, 0, 5, 302, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.59, 82.93 +CTUN, 327, 1.98, -0.65, 0.000000, 0, 0, 5, 324, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.60, 82.93 +CTUN, 357, 1.98, -0.77, 0.000000, 0, 0, 4, 355, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.60, 82.93 +CTUN, 376, 1.99, -0.91, 0.000000, 0, 0, 4, 374, 0 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.60, 82.93 +CTUN, 396, 1.99, -1.04, 0.000000, 0, 0, 2, 396, 0 +ATT, 0.00, -0.20, -2.24, -0.09, 0.00, 83.59, 82.93 +CTUN, 411, 1.99, -1.16, 0.000000, 0, 0, 1, 402, 0 +DU32, 7, 166140 +CURR, 420, 44988, 1164, 716, 5028, 28.847597 +ATT, 0.00, -0.19, -2.24, -0.09, 0.00, 83.58, 82.93 +CTUN, 434, 1.98, -1.35, 0.000000, 0, 0, 0, 434, 0 +ATT, 0.00, -0.20, -2.24, -0.09, 0.00, 83.56, 82.93 +CTUN, 458, 1.99, -1.29, 0.000000, 0, 0, 0, 449, 0 +ATT, 0.00, -0.21, -2.24, -0.10, 0.00, 83.52, 82.93 +CTUN, 499, 1.99, -1.50, 0.000000, 0, 0, 0, 490, 0 +ATT, 0.00, -0.22, -2.24, -0.10, 0.00, 83.49, 82.93 +CTUN, 510, 1.99, -1.61, 0.000000, 0, 0, 4, 510, 0 +ATT, 0.00, -0.23, -2.24, -0.11, 0.00, 83.43, 82.93 +CTUN, 530, 1.99, -2.04, 0.000000, 0, 0, 2, 530, 0 +ATT, 0.00, -0.23, -2.05, -0.11, 0.00, 83.37, 82.93 +CTUN, 544, 3.36, -1.93, 0.000000, 0, 0, 4, 542, 0 +ATT, 0.00, -0.25, -2.05, -0.14, 0.00, 83.31, 82.93 +CTUN, 577, 3.36, -1.95, 0.000000, 0, 0, 8, 571, 0 +ATT, 0.00, -0.30, -1.30, -0.17, 0.00, 83.22, 82.93 +CTUN, 596, 3.45, -2.23, 0.000000, 0, 0, 4, 592, 0 +ATT, 0.00, -0.31, -2.14, -0.18, 0.00, 83.16, 82.93 +CTUN, 622, 3.45, -2.37, 0.000000, 0, 0, 5, 597, 0 +ATT, 0.00, -0.64, -2.24, -0.22, 0.00, 83.08, 82.93 +CTUN, 639, 3.80, -2.34, 0.000000, 0, 0, 6, 639, 0 +DU32, 7, 166140 +CURR, 640, 50327, 1097, 1659, 5051, 32.284740 +ATT, 0.00, -1.69, -2.05, -0.20, 0.00, 83.10, 82.93 +CTUN, 663, 3.45, -2.20, 0.000000, 0, 0, 7, 660, 0 +ATT, 0.00, -3.27, -2.05, -0.59, 0.00, 83.38, 82.93 +CTUN, 681, 3.69, -2.01, 0.000000, 0, 1, 6, 680, 0 +ATT, 0.00, -4.80, -2.05, -1.97, 0.00, 84.18, 82.93 +CTUN, 680, 3.69, -1.75, 0.000000, 0, 3, 8, 682, 0 +ATT, 0.00, -6.70, -2.05, -4.07, 0.00, 85.36, 82.93 +CTUN, 680, 4.25, -1.42, 0.000000, 0, 6, 10, 686, 0 +ATT, 0.00, -9.28, -2.05, -6.55, 0.00, 87.02, 82.93 +CTUN, 680, 3.69, -0.89, 0.000000, 0, 14, 12, 694, 0 +ATT, 0.00, -11.94, -1.40, -8.88, 0.00, 89.02, 82.93 +CTUN, 680, 3.69, -0.12, 0.000000, 0, 22, 9, 702, 0 +ATT, 0.09, -14.27, 8.12, -10.52, 0.00, 91.04, 82.93 +CTUN, 623, 0.21, 0.31, 0.000000, 0, 27, 6, 650, 0 +ATT, 6.28, -16.64, 20.35, -10.29, 0.00, 92.42, 82.93 +CTUN, 330, 0.21, 0.23, 0.000000, 0, 14, 2, 372, 0 +ATT, 6.28, -17.34, 25.20, -7.79, 0.00, 93.22, 83.22 +CTUN, 171, 0.20, 0.24, 0.000000, 0, 3, -20, 197, 0 +ATT, 6.37, -13.62, 26.70, -2.14, 0.00, 94.19, 84.19 +CTUN, 133, 0.21, -0.11, 0.000000, 0, 0, -50, 134, 0 +DU32, 7, 166140 +CURR, 0, 55792, 1171, 295, 5051, 36.564842 +ATT, 6.18, -0.31, 25.76, -0.47, 0.00, 96.72, 96.72 +CTUN, 0, 0.21, -0.92, 0.000000, 0, 0, 13, 0, 0 +ATT, 3.37, -1.54, 23.71, -0.59, 0.00, 96.61, 96.61 +CTUN, 0, 1.79, -0.73, 0.000000, 0, 0, 6, 0, 0 +ATT, 2.25, -0.37, 20.07, -0.75, 0.00, 96.81, 96.81 +CTUN, 0, 1.79, -0.60, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, -0.33, 10.54, -0.74, 0.00, 96.83, 96.83 +CTUN, 0, 7.18, -0.31, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, -0.33, -1.12, -0.73, 0.00, 96.86, 96.86 +CTUN, 0, 7.18, -0.24, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, -0.33, -2.14, -0.73, 0.00, 96.89, 96.89 +CTUN, 0, 7.65, -0.12, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, -0.32, -2.14, -0.71, 0.00, 96.93, 96.93 +CTUN, 0, 7.65, -0.17, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, -0.33, -2.14, -0.72, 0.00, 96.95, 96.95 +CTUN, 0, 7.65, -0.12, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, -0.32, -2.24, -0.71, 0.00, 96.99, 96.99 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, -0.32, -2.14, -0.69, 0.00, 97.03, 97.03 +CTUN, 0, 7.65, -0.14, 0.000000, 0, 0, 5, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1198, 0, 5051, 36.645130 +ATT, 0.00, -0.31, -2.14, -0.69, 0.00, 97.07, 97.07 +CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, -0.30, -2.14, -0.69, 0.00, 97.10, 97.10 +CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.30, -2.14, -0.69, 0.00, 97.13, 97.13 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 7, 0, 0 +ATT, 0.00, -0.30, -2.14, -0.68, 0.00, 97.17, 97.17 +CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, 7, 0, 0 +ATT, 0.00, -0.29, -2.05, -0.67, 0.00, 97.20, 97.20 +CTUN, 0, 7.65, -0.12, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.29, -2.14, -0.67, 0.00, 97.23, 97.23 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 9, 0, 0 +ATT, 0.00, -0.29, -2.14, -0.66, 0.00, 97.27, 97.27 +CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 9, 0, 0 +ATT, 0.00, -0.28, -2.05, -0.66, 0.00, 97.30, 97.30 +CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.28, -2.05, -0.66, 0.00, 97.33, 97.33 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.28, -2.14, -0.65, 0.00, 97.36, 97.36 +CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 11, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1199, 0, 5051, 36.645130 +ATT, 0.00, -0.27, -2.14, -0.65, 0.00, 97.40, 97.40 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 11, 0, 0 +ATT, 0.00, -0.27, -2.14, -0.64, 0.00, 97.43, 97.43 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.27, -2.05, -0.64, 0.00, 97.46, 97.46 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.26, -2.14, -0.63, 0.00, 97.49, 97.49 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.26, -2.05, -0.63, 0.00, 97.52, 97.52 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.26, -2.05, -0.62, 0.00, 97.54, 97.54 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.26, -2.05, -0.62, 0.00, 97.57, 97.57 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.25, -2.14, -0.61, 0.00, 97.61, 97.61 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.25, -2.14, -0.61, 0.00, 97.63, 97.63 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.25, -2.05, -0.61, 0.00, 97.66, 97.66 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 14, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1200, 0, 5028, 36.645130 +ATT, 0.00, -0.25, -2.14, -0.60, 0.00, 97.69, 97.69 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.25, -2.14, -0.60, 0.00, 97.72, 97.72 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.25, -2.14, -0.60, 0.00, 97.74, 97.74 +CTUN, 0, 7.65, -0.07, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.24, -2.14, -0.60, 0.00, 97.77, 97.77 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.24, -2.14, -0.59, 0.00, 97.80, 97.80 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.24, -2.14, -0.59, 0.00, 97.82, 97.82 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.23, -2.14, -0.58, 0.00, 97.85, 97.85 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.23, -2.14, -0.58, 0.00, 97.88, 97.88 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.23, -2.14, -0.57, 0.00, 97.90, 97.90 +CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, 15, 0, 0 +PM, 0, 0, 0, 0, 1000, 10476, 0, 0 +ATT, 0.00, -0.22, -2.05, -0.57, 0.00, 97.93, 97.93 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 15, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1201, 0, 5028, 36.645470 +ATT, 0.00, -0.22, -2.14, -0.57, 0.00, 97.95, 97.95 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.22, -2.14, -0.56, 0.00, 97.98, 97.98 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.22, -2.14, -0.56, 0.00, 98.00, 98.00 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.21, -2.14, -0.55, 0.00, 98.03, 98.03 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.21, -2.14, -0.55, 0.00, 98.06, 98.06 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.21, -2.14, -0.54, 0.00, 98.08, 98.08 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.21, -2.14, -0.54, 0.00, 98.10, 98.10 +CTUN, 0, 3.67, 0.06, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.20, -2.14, -0.54, 0.00, 98.12, 98.12 +CTUN, 0, 3.67, 0.07, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.20, -2.14, -0.53, 0.00, 98.14, 98.14 +CTUN, 0, 3.26, 0.05, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.20, -2.24, -0.53, 0.00, 98.17, 98.17 +CTUN, 0, 3.67, 0.04, 0.000000, 0, 0, 15, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1201, 0, 5028, 36.646122 +ATT, 0.00, -0.19, -2.24, -0.53, 0.00, 98.20, 98.20 +CTUN, 0, 3.67, 0.12, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.19, -2.14, -0.53, 0.00, 98.22, 98.22 +CTUN, 0, 7.55, 0.11, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.19, -2.24, -0.52, 0.00, 98.24, 98.24 +CTUN, 0, 7.55, 0.08, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.26, 98.26 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 15, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.28, 98.28 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.30, 98.30 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.18, -2.24, -0.52, 0.00, 98.32, 98.32 +CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.17, -2.24, -0.52, 0.00, 98.34, 98.34 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.17, -2.24, -0.51, 0.00, 98.37, 98.37 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.17, -2.14, -0.51, 0.00, 98.39, 98.39 +CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 14, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1203, 2, 5028, 36.646748 +ATT, 0.00, -0.17, -2.14, -0.50, 0.00, 98.42, 98.42 +CTUN, 0, 2.41, -0.02, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.16, -2.05, -0.50, 0.00, 98.44, 98.44 +CTUN, 0, 3.17, 0.05, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.16, -2.24, -0.49, 0.00, 98.46, 98.46 +CTUN, 0, 2.41, 0.04, 0.000000, 0, 0, 14, 0, 0 +ATT, 0.00, -0.15, -2.24, -0.49, 0.00, 98.49, 98.49 +CTUN, 0, 2.41, 0.06, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.15, -2.24, -0.48, 0.00, 98.51, 98.51 +CTUN, 0, 0.73, 0.12, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.15, -2.24, -0.48, 0.00, 98.53, 98.53 +CTUN, 0, 2.41, 0.09, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.48, 0.00, 98.55, 98.55 +CTUN, 0, 2.41, 0.09, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.47, 0.00, 98.58, 98.58 +CTUN, 0, 7.12, 0.06, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.14, -2.24, -0.47, 0.00, 98.60, 98.60 +CTUN, 0, 7.12, 0.02, 0.000000, 0, 0, 13, 0, 0 +ATT, 0.00, -0.13, -2.24, -0.47, 0.00, 98.62, 98.62 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 13, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1203, 0, 5028, 36.646748 +ATT, 0.00, -0.13, -2.24, -0.46, 0.00, 98.64, 98.64 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.46, 0.00, 98.67, 98.67 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.46, 0.00, 98.69, 98.69 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.12, -2.24, -0.45, 0.00, 98.71, 98.71 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.45, 0.00, 98.73, 98.73 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.11, -2.24, -0.45, 0.00, 98.75, 98.75 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.44, 0.00, 98.77, 98.77 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 12, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.44, 0.00, 98.79, 98.79 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 11, 0, 0 +ATT, 0.00, -0.10, -2.24, -0.44, 0.00, 98.81, 98.81 +CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 11, 0, 0 +ATT, 0.00, -0.09, -2.24, -0.43, 0.00, 98.83, 98.83 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 11, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1204, 0, 5028, 36.647427 +ATT, 0.00, -0.09, -2.24, -0.44, 0.00, 98.85, 98.85 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 11, 0, 0 +ATT, 0.00, -0.09, -2.24, -0.43, 0.00, 98.87, 98.87 +CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 11, 0, 0 +ATT, 0.00, -0.09, -2.24, -0.43, 0.00, 98.89, 98.89 +CTUN, 0, 7.65, 0.14, 0.000000, 0, 0, 11, 0, 0 +ATT, 0.00, -0.08, -2.24, -0.43, 0.00, 98.91, 98.91 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.08, -2.24, -0.42, 0.00, 98.92, 98.92 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.08, -2.24, -0.42, 0.00, 98.94, 98.94 +CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.07, -2.24, -0.42, 0.00, 98.96, 98.96 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.07, -2.24, -0.41, 0.00, 98.97, 98.97 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 10, 0, 0 +ATT, 0.00, -0.07, -2.24, -0.41, 0.00, 98.99, 98.99 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 9, 0, 0 +ATT, 0.00, -0.06, -2.24, -0.41, 0.00, 99.01, 99.01 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 9, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1204, 0, 5051, 36.648075 +ATT, 0.00, -0.06, -2.24, -0.40, 0.00, 99.03, 99.03 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 9, 0, 0 +ATT, 0.00, -0.06, -2.24, -0.40, 0.00, 99.04, 99.04 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 9, 0, 0 +ATT, 0.00, -0.05, -2.24, -0.40, 0.00, 99.06, 99.06 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.05, -2.24, -0.40, 0.00, 99.07, 99.07 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.05, -2.24, -0.39, 0.00, 99.09, 99.09 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.04, -2.24, -0.39, 0.00, 99.11, 99.11 +CTUN, 0, 7.65, 0.13, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.04, -2.24, -0.39, 0.00, 99.12, 99.12 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 8, 0, 0 +ATT, 0.00, -0.04, -2.24, -0.39, 0.00, 99.14, 99.14 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 7, 0, 0 +ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.16, 99.16 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 7, 0, 0 +ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.17, 99.17 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 7, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1204, 0, 5028, 36.648415 +ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.19, 99.19 +CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, 7, 0, 0 +ATT, 0.00, -0.03, -2.24, -0.38, 0.00, 99.20, 99.20 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.02, -2.24, -0.37, 0.00, 99.22, 99.22 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.02, -2.24, -0.37, 0.00, 99.24, 99.24 +CTUN, 0, 7.65, 0.11, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.02, -2.14, -0.37, 0.00, 99.25, 99.25 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.01, -2.24, -0.37, 0.00, 99.27, 99.27 +CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.01, -2.24, -0.37, 0.00, 99.28, 99.28 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 6, 0, 0 +ATT, 0.00, -0.01, -2.24, -0.36, 0.00, 99.30, 99.30 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.00, -2.24, -0.36, 0.00, 99.32, 99.32 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.00, -2.24, -0.36, 0.00, 99.34, 99.34 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 5, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1203, 0, 5028, 36.648415 +ATT, 0.00, 0.00, -2.24, -0.36, 0.00, 99.36, 99.36 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.38, 99.38 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.40, 99.40 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.42, 99.42 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.00, -2.24, -0.35, 0.00, 99.44, 99.44 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 5, 0, 0 +ATT, 0.00, 0.01, -2.24, -0.35, 0.00, 99.45, 99.45 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.01, -2.24, -0.34, 0.00, 99.47, 99.47 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.01, -2.24, -0.34, 0.00, 99.48, 99.48 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.01, -2.24, -0.34, 0.00, 99.50, 99.50 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.02, -2.24, -0.34, 0.00, 99.52, 99.52 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, 4, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1204, 0, 5051, 36.648754 +ATT, 0.00, 0.02, -2.24, -0.33, 0.00, 99.54, 99.54 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.02, -2.24, -0.33, 0.00, 99.56, 99.56 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.03, -2.24, -0.33, 0.00, 99.57, 99.57 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.03, -2.24, -0.32, 0.00, 99.59, 99.59 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 4, 0, 0 +ATT, 0.00, 0.03, -2.24, -0.32, 0.00, 99.61, 99.61 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.04, -2.24, -0.32, 0.00, 99.62, 99.62 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.04, -2.24, -0.32, 0.00, 99.64, 99.64 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.04, -2.24, -0.31, 0.00, 99.66, 99.66 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.05, -2.24, -0.31, 0.00, 99.67, 99.67 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.05, -2.24, -0.31, 0.00, 99.69, 99.69 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 3, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5028, 36.649067 +ATT, 0.00, 0.05, -2.24, -0.31, 0.00, 99.70, 99.70 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.05, -2.24, -0.30, 0.00, 99.72, 99.72 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 3, 0, 0 +ATT, 0.00, 0.05, -2.24, -0.30, 0.00, 99.73, 99.73 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.06, -2.24, -0.30, 0.00, 99.75, 99.75 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.06, -2.24, -0.29, 0.00, 99.76, 99.76 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.06, -2.24, -0.29, 0.00, 99.78, 99.78 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.07, -2.24, -0.29, 0.00, 99.79, 99.79 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.07, -2.24, -0.29, 0.00, 99.80, 99.80 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 2, 0, 0 +ATT, 0.00, 0.07, -2.61, -0.29, 0.00, 99.82, 99.82 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 1, 0, 0 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +ATT, 0.00, 0.07, -2.24, -0.28, 0.00, 99.83, 99.83 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 1, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5028, 36.649406 +ATT, 0.00, 0.07, -2.24, -0.28, 0.00, 99.84, 99.84 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.08, -2.24, -0.28, 0.00, 99.85, 99.85 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.08, -2.24, -0.28, 0.00, 99.87, 99.87 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.08, -2.24, -0.27, 0.00, 99.89, 99.89 +CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.09, -2.24, -0.27, 0.00, 99.90, 99.90 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.09, -2.24, -0.27, 0.00, 99.91, 99.91 +CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, 1, 0, 0 +ATT, 0.00, 0.09, -2.61, -0.27, 0.00, 99.92, 99.92 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.09, -2.24, -0.27, 0.00, 99.94, 99.94 +CTUN, 0, 7.65, -0.07, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.10, -2.24, -0.27, 0.00, 99.95, 99.95 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 99.96, 99.96 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5028, 36.649406 +ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 99.97, 99.97 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 99.99, 99.99 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.10, -2.24, -0.26, 0.00, 100.00, 100.00 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.11, -2.24, -0.25, 0.00, 100.01, 100.01 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.11, -2.24, -0.25, 0.00, 100.02, 100.02 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.12, -2.24, -0.25, 0.00, 100.03, 100.03 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.12, -2.24, -0.25, 0.00, 100.05, 100.05 +CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.12, -2.24, -0.25, 0.00, 100.06, 100.06 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.12, -2.24, -0.24, 0.00, 100.07, 100.07 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.08, 100.08 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, 0, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1207, 0, 5028, 36.649746 +ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.10, 100.10 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.11, 100.11 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.12, 100.12 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.13, 100.13 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.14, 100.14 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.15, 100.15 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.16, 100.16 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.23, 0.00, 100.17, 100.17 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.23, 0.00, 100.19, 100.19 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.23, 0.00, 100.20, 100.20 +CTUN, 0, 7.65, 0.12, 0.000000, 0, 0, -1, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1208, 0, 5028, 36.649746 +ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.22, 100.22 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.23, 100.23 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.22, 0.00, 100.23, 100.23 +CTUN, 0, 7.65, 0.10, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.22, 0.00, 100.24, 100.24 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.25, 100.25 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.22, 0.00, 100.27, 100.27 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.21, 0.00, 100.27, 100.27 +CTUN, 0, 7.65, 0.02, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.21, 0.00, 100.28, 100.28 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.20, 0.00, 100.29, 100.29 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, 0, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.20, 0.00, 100.29, 100.29 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5051, 36.650372 +ATT, 0.00, 0.18, -2.24, -0.20, 0.00, 100.31, 100.31 +CTUN, 0, 7.65, 0.09, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.21, 0.00, 100.31, 100.31 +CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.20, 0.00, 100.32, 100.32 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.22, 0.00, 100.31, 100.31 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 100.36, 100.36 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.11, -2.24, -0.27, 0.00, 100.37, 100.37 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.09, -2.33, -0.29, 0.00, 100.40, 100.40 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.08, -2.24, -0.30, 0.00, 100.44, 100.44 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.07, -2.24, -0.32, 0.00, 100.45, 100.45 +CTUN, 0, 7.65, -0.02, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.06, -2.24, -0.34, 0.00, 100.45, 100.45 +CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -1, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5028, 36.650372 +ATT, 0.00, 0.04, -2.24, -0.35, 0.00, 100.35, 100.35 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.04, -2.24, -0.32, 0.00, 100.32, 100.32 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.07, -2.24, -0.26, 0.00, 100.45, 100.45 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, -1, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.22, 0.00, 100.44, 100.44 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.21, 0.00, 100.44, 100.44 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.14, -2.24, -0.21, 0.00, 100.46, 100.46 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.21, 0.00, 100.45, 100.45 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.20, 0.00, 100.44, 100.44 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.20, 0.00, 100.47, 100.47 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.19, 0.00, 100.46, 100.46 +CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, -2, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 1, 5028, 36.651051 +ATT, 0.00, 0.16, -2.24, -0.19, 0.00, 100.47, 100.47 +CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.15, -2.24, -0.19, 0.00, 100.46, 100.46 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.18, 0.00, 100.49, 100.49 +CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.19, 0.00, 100.44, 100.44 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.18, 0.00, 100.50, 100.50 +CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.18, 0.00, 100.51, 100.51 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.54, 100.54 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.53, 100.53 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.18, 0.00, 100.53, 100.53 +CTUN, 0, 7.65, -0.17, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.18, -2.24, -0.17, 0.00, 100.54, 100.54 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, -3, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1205, 0, 5051, 36.651390 +ATT, 0.00, 0.18, -2.24, -0.17, 0.00, 100.54, 100.54 +CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.18, -2.24, -0.17, 0.00, 100.56, 100.56 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.16, -2.24, -0.17, 0.00, 100.58, 100.58 +CTUN, 0, 7.65, -0.08, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.58, 100.58 +CTUN, 0, 7.65, 0.06, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.17, 0.00, 100.58, 100.58 +CTUN, 0, 7.65, -0.03, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.18, -2.24, -0.16, 0.00, 100.60, 100.60 +CTUN, 0, 7.65, 0.03, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.18, -2.24, -0.16, 0.00, 100.60, 100.60 +CTUN, 0, 7.33, -0.06, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.17, -2.14, -0.16, 0.00, 100.61, 100.61 +CTUN, 0, 7.33, 0.02, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.17, -2.24, -0.16, 0.00, 100.61, 100.61 +CTUN, 0, 7.24, 0.04, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.18, -2.24, -0.15, 0.00, 100.61, 100.61 +CTUN, 0, 7.33, 0.03, 0.000000, 0, 0, -3, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5028, 36.651703 +ATT, 0.00, 0.18, -2.24, -0.15, 0.00, 100.62, 100.62 +CTUN, 0, 7.33, -0.07, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.19, -2.24, -0.14, 0.00, 100.63, 100.63 +CTUN, 0, 7.65, 0.01, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.19, -2.24, -0.14, 0.00, 100.63, 100.63 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.19, -2.24, -0.14, 0.00, 100.64, 100.64 +CTUN, 0, 7.65, 0.04, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.14, -0.13, 0.00, 100.65, 100.65 +CTUN, 0, 7.65, -0.05, 0.000000, 0, 0, -2, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.14, 0.00, 100.63, 100.63 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.14, 0.00, 100.64, 100.64 +CTUN, 0, 7.65, -0.10, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.14, 0.00, 100.65, 100.65 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.21, -2.33, -0.14, 0.00, 100.63, 100.63 +CTUN, 0, 7.65, -0.04, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.66, 100.66 +CTUN, 0, 7.65, -0.09, 0.000000, 0, 0, -3, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1205, 0, 5028, 36.652355 +ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 +CTUN, 0, 7.65, -0.07, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.20, -2.24, -0.13, 0.00, 100.67, 100.67 +CTUN, 0, 7.65, 0.00, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.21, -2.24, -0.11, 0.00, 100.67, 100.67 +CTUN, 0, 7.65, -0.01, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.22, -2.24, -0.10, 0.00, 100.68, 100.68 +CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.19, -2.24, -0.13, 0.00, 100.69, 100.69 +CTUN, 0, 7.65, 0.07, 0.000000, 0, 0, -3, 0, 0 +ATT, 0.00, 0.22, -2.24, -0.09, 0.00, 100.69, 100.69 +CTUN, 0, 7.65, -0.06, 0.000000, 0, 0, -4, 0, 0 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +ATT, 0.00, 0.21, -2.24, -0.11, 0.00, 100.69, 100.69 +CTUN, 0, 7.65, 0.05, 0.000000, 0, 0, -3, 0, 0 +DU32, 7, 166076 +CURR, 0, 55792, 1206, 0, 5051, 36.652695 +EV, 11 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +PM, 0, 0, 0, 1, 1000, 113444, 0, 0 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +PM, 0, 0, 0, 0, 1000, 10480, 0, 0 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +PM, 0, 0, 0, 0, 1000, 10484, 0, 0 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +DU32, 7, 133308 +D32, 9, 10058 +EV, 10 +CTUN, 154, 7.65, 0.00, 0.000000, 0, 0, 0, 0, 0 +EV, 15 +ATT, 0.00, 0.09, -2.24, -0.30, 0.00, 100.59, 100.58 +CTUN, 244, 7.65, 0.10, 0.000000, 0, 0, -1, 241, 0 +ATT, 0.00, 0.09, -2.24, -0.30, 0.00, 100.55, 100.58 +CTUN, 244, 7.65, -0.12, 0.000000, 0, 0, 0, 243, 0 +ATT, 0.00, 0.08, -2.24, -0.30, 0.00, 100.52, 100.58 +CTUN, 244, 7.65, -0.31, 0.000000, 0, 0, -1, 244, 0 +ATT, 0.00, 0.09, -2.24, -0.29, 0.00, 100.46, 100.58 +CTUN, 244, 7.65, -0.86, 0.000000, 0, 0, -1, 244, 0 +ATT, 0.00, 0.10, -2.24, -0.29, 0.00, 100.43, 100.58 +CTUN, 243, 7.65, -0.93, 0.000000, 0, 0, -2, 243, 0 +ATT, 0.00, 0.09, -2.24, -0.30, 0.00, 100.41, 100.58 +CTUN, 144, 7.65, -1.07, 0.000000, 0, 0, -3, 181, 0 +ATT, 0.00, 0.10, -2.24, -0.29, 0.00, 100.37, 100.37 +DU32, 7, 133308 +CURR, 0, 57309, 1189, 246, 5028, 37.295242 +CTUN, 0, 7.65, -1.07, 0.000000, 0, 0, -4, 0, 0 +ATT, 0.00, 0.11, -2.24, -0.29, 0.00, 100.36, 100.36 +CTUN, 0, 7.65, -0.64, 0.000000, 0, 0, -5, 0, 0 +ATT, 0.00, 0.12, -2.24, -0.28, 0.00, 100.36, 100.36 +CTUN, 0, 7.65, -0.61, 0.000000, 0, 0, -6, 0, 0 +ATT, 0.00, 0.10, -2.24, -0.29, 0.00, 100.41, 100.41 +CTUN, 0, 7.65, -0.59, 0.000000, 0, 0, -6, 0, 0 +ATT, 0.00, 0.12, -2.24, -0.28, 0.00, 100.38, 100.38 +CTUN, 0, 7.65, -0.34, 0.000000, 0, 0, -7, 0, 0 +ATT, 0.00, 0.11, -2.24, -0.28, 0.00, 100.37, 100.37 +CTUN, 0, 7.65, -0.27, 0.000000, 0, 0, -6, 0, 0 +EV, 15 +ATT, 0.00, 0.11, -2.24, -0.27, 0.00, 100.38, 100.39 +CTUN, 200, 7.65, -0.22, 0.000000, 0, 0, -6, 191, 0 +ATT, 0.00, 0.12, -2.24, -0.27, 0.00, 100.39, 100.39 +CTUN, 205, 7.65, -0.39, 0.000000, 0, 0, -6, 205, 0 +ATT, 0.00, 0.13, -2.24, -0.27, 0.00, 100.33, 100.39 +CTUN, 205, 7.65, -0.55, 0.000000, 0, 0, -7, 205, 0 +ATT, 0.00, 0.12, -2.33, -0.27, 0.00, 100.34, 100.39 +CTUN, 226, 7.65, -0.66, 0.000000, 0, 0, -7, 226, 0 +ATT, 0.00, 0.11, -2.24, -0.27, 0.00, 100.34, 100.39 +DU32, 7, 133372 +CURR, 248, 58281, 1191, 233, 5028, 37.561947 +CTUN, 252, 7.65, -0.80, 0.000000, 0, 0, -7, 248, 0 +ATT, 0.00, 0.12, -2.24, -0.26, 0.00, 100.29, 100.39 +CTUN, 287, 7.65, -0.93, 0.000000, 0, 0, -8, 287, 0 +ATT, 0.00, 0.12, -2.24, -0.27, 0.00, 100.27, 100.39 +CTUN, 328, 7.65, -1.14, 0.000000, 0, 0, -8, 328, 0 +EV, 16 +ATT, 0.00, 0.12, -2.24, -0.27, 0.00, 100.23, 100.39 +CTUN, 361, 7.65, -1.73, 0.000000, 0, 0, -9, 357, 0 +ATT, 0.00, 0.13, -2.24, -0.26, 0.00, 100.16, 100.39 +CTUN, 378, 7.65, -1.88, 0.000000, 0, 0, -10, 378, 0 +ATT, 0.00, 0.13, -2.24, -0.25, 0.00, 100.09, 100.39 +CTUN, 403, 7.65, -2.38, 0.000000, 0, 0, -12, 403, 0 +ATT, 0.00, 0.14, -2.24, -0.25, 0.00, 100.03, 100.39 +CTUN, 441, 7.65, -2.51, 0.000000, 0, 0, -14, 438, 0 +ATT, 0.00, 0.13, -2.24, -0.24, 0.00, 99.96, 100.39 +CTUN, 468, 7.65, -3.13, 0.000000, 0, 0, -17, 468, 0 +ATT, 0.00, 0.13, -2.24, -0.23, 0.00, 99.87, 100.39 +CTUN, 501, 7.65, -3.45, 0.000000, 0, 0, -19, 501, 0 +ATT, 0.00, 0.13, -2.24, -0.20, 0.00, 99.76, 100.39 +CTUN, 524, 7.65, -4.07, 0.000000, 0, 0, -20, 524, 0 +ATT, 0.37, 0.14, -2.05, -0.20, 0.00, 99.63, 100.39 +DU32, 7, 166140 +CURR, 544, 62282, 1134, 1271, 5051, 39.683720 +CTUN, 545, 7.65, -4.64, 0.000000, 0, 0, -20, 545, 0 +ATT, 0.65, 0.14, -2.05, -0.06, 0.00, 99.50, 100.39 +CTUN, 563, 6.46, -4.67, 0.000000, 0, 0, -21, 563, 0 +ATT, 1.40, 0.13, -1.30, 0.43, 0.00, 99.38, 100.39 +CTUN, 588, 7.55, -4.72, 0.000000, 0, 0, -24, 588, 0 +ATT, 1.40, 0.00, -1.49, 1.88, 0.00, 99.43, 100.39 +CTUN, 593, 6.46, -4.56, 0.000000, 0, 0, -25, 593, 0 +ATT, 1.68, 0.17, -1.77, 3.78, 0.00, 99.90, 100.39 +CTUN, 595, 6.46, -4.22, 0.000000, 0, 1, -25, 593, 0 +ATT, 2.90, 0.65, -2.24, 4.90, 0.00, 100.69, 100.39 +CTUN, 597, 5.28, -4.40, 0.000000, 0, 1, -29, 598, 0 +ATT, 5.34, 0.84, -5.60, 4.35, 0.00, 101.54, 100.39 +CTUN, 602, 6.46, -3.51, 0.000000, 0, 1, -34, 603, 0 +ATT, 6.00, 2.67, -13.53, 2.88, 0.00, 102.39, 100.39 +CTUN, 602, 5.28, -3.56, 0.000000, 0, 1, -35, 603, 0 +ATT, 6.18, 4.66, -14.28, -0.82, 0.00, 102.90, 100.39 +CTUN, 602, 5.28, -2.79, 0.000000, 0, 1, -41, 603, 0 +ATT, 6.18, 4.93, -14.28, -6.62, 0.00, 103.28, 100.39 +CTUN, 602, 1.94, -2.79, 0.000000, 0, 5, -44, 607, 0 +ATT, 6.09, 5.52, -12.88, -9.87, 0.00, 103.74, 100.39 +DU32, 7, 166140 +CURR, 608, 68184, 1106, 1533, 5051, 43.800499 +CTUN, 616, 1.94, -2.53, 0.000000, 0, 9, -43, 617, 0 +ATT, 3.93, 5.93, -9.33, -9.88, 0.00, 104.59, 100.39 +CTUN, 626, 0.28, -1.99, 0.000000, 0, 9, -47, 635, 0 +ATT, 0.28, 4.22, -2.05, -8.51, 0.00, 105.50, 100.39 +CTUN, 639, 0.29, -2.01, 0.000000, 0, 6, -46, 642, 0 +ATT, 0.00, 1.31, -1.40, -5.40, 0.00, 106.51, 100.39 +CTUN, 639, 0.28, -2.25, 0.000000, 0, 2, -42, 641, 0 +ATT, 0.00, -1.19, -0.56, -2.04, 0.00, 107.45, 100.39 +CTUN, 640, 0.28, -1.64, 0.000000, 0, 0, -42, 640, 0 +ATT, 0.00, -2.80, -0.84, 0.32, 0.00, 108.33, 100.39 +CTUN, 639, 0.22, -1.67, 0.000000, 0, 0, -37, 639, 0 +ATT, 0.00, -2.60, -2.24, 1.51, 0.00, 109.31, 100.39 +CTUN, 642, 0.22, -1.95, 0.000000, 0, 0, -34, 642, 0 +ATT, 0.00, -2.05, -2.24, 1.92, 0.00, 110.12, 100.39 +CTUN, 646, 0.20, -1.13, 0.000000, 0, 0, -32, 645, 0 +ATT, 0.00, -2.01, -2.24, 1.61, 0.00, 110.59, 100.59 +CTUN, 646, 0.20, -0.80, 0.000000, 0, 0, -29, 646, 0 +ATT, 0.00, -1.98, -2.05, 1.03, -0.09, 110.62, 100.62 +CTUN, 646, 0.20, -0.57, 0.000000, 0, 0, -27, 646, 0 +ATT, 0.00, -1.83, -2.05, 0.38, -3.20, 110.25, 100.25 +DU32, 7, 166140 +CURR, 644, 74588, 1101, 1738, 5028, 48.557549 +CTUN, 645, 0.20, -0.11, 0.000000, 0, 0, -26, 645, 0 +ATT, 0.00, -1.46, -2.05, 0.10, -3.30, 109.36, 99.36 +CTUN, 645, 0.20, 0.03, 0.000000, 0, 0, -25, 644, 0 +ATT, 0.00, -0.83, -2.05, 0.22, -4.24, 108.04, 98.04 +CTUN, 644, 0.20, 0.09, 0.000000, 0, 0, -25, 644, 0 +ATT, 0.00, -0.63, -1.58, -0.19, -8.01, 106.37, 96.37 +CTUN, 644, 0.20, 0.08, 0.000000, 0, 0, -28, 644, 0 +ATT, 0.00, -0.41, -1.68, -0.54, -9.71, 104.09, 94.09 +CTUN, 645, 0.20, 0.10, 0.000000, 0, 0, -29, 645, 0 +ATT, 0.00, -0.44, -1.58, -0.50, -11.03, 101.19, 91.19 +CTUN, 645, 0.20, 0.00, 0.000000, 0, 0, -28, 645, 0 +ATT, 0.00, -0.52, -1.40, -0.16, -11.88, 97.51, 87.51 +CTUN, 645, 0.20, 0.14, 0.000000, 0, 0, -28, 645, 0 +ATT, 0.00, -0.44, -0.93, -0.15, -11.88, 93.63, 83.63 +CTUN, 653, 0.20, 0.10, 0.000000, 0, 0, -29, 653, 0 +ATT, 0.00, -0.03, -0.84, -0.21, -11.88, 89.40, 79.40 +CTUN, 656, 0.20, 0.20, 0.000000, 0, 0, -29, 656, 0 +ATT, 0.00, 0.07, 0.00, -0.42, -11.88, 84.87, 74.87 +CTUN, 660, 0.20, 0.13, 0.000000, 0, 0, -26, 660, 0 +ATT, 0.00, -0.34, 0.00, 0.05, -11.79, 80.00, 70.00 +DU32, 7, 166140 +CURR, 666, 81069, 1075, 1811, 5051, 53.439949 +CTUN, 666, 0.20, 0.15, 0.000000, 0, 0, -23, 666, 0 +ATT, 0.00, -0.78, 0.00, 0.64, -8.67, 74.95, 65.29 +CTUN, 666, 0.20, -0.08, 0.000000, 0, 0, -19, 666, 0 +ATT, 0.00, -0.34, 0.28, 1.36, -3.67, 69.96, 62.72 +CTUN, 666, 0.20, -0.30, 0.000000, 0, 0, -14, 666, 0 +ATT, 0.00, 0.06, 0.00, 1.43, 0.00, 65.55, 62.38 +CTUN, 666, 0.20, -0.45, 0.000000, 0, 0, -11, 666, 0 +ATT, 0.00, 0.36, 0.00, 1.13, 0.00, 62.44, 62.38 +CTUN, 665, 0.20, -0.40, 0.000000, 0, 0, -9, 665, 0 +ATT, 0.00, 0.15, 0.00, 1.18, 0.00, 60.46, 62.38 +CTUN, 665, 0.20, -0.20, 0.000000, 0, 0, -4, 665, 0 +ATT, 0.00, 0.18, 0.00, 1.41, 0.00, 59.28, 62.38 +CTUN, 665, 0.20, -0.20, 0.000000, 0, 0, -3, 665, 0 +ATT, 0.00, 0.16, -0.74, 1.67, 0.00, 58.82, 62.38 +CTUN, 665, 0.20, -0.44, 0.000000, 0, 0, -2, 665, 0 +ATT, 0.00, 0.29, -2.05, 1.67, 0.00, 58.92, 62.38 +CTUN, 666, 0.20, -0.35, 0.000000, 0, 0, 0, 665, 0 +ATT, 0.00, 0.75, -2.24, 0.89, 0.00, 59.51, 62.38 +PM, 0, 0, 0, 1, 1000, 2055856, 0, 0 +CTUN, 665, 0.20, -0.16, 0.000000, 0, 0, -3, 665, 0 +ATT, 0.00, 0.51, -1.96, 0.14, 0.00, 60.46, 62.38 +DU32, 7, 166140 +CURR, 666, 87723, 1094, 1780, 5028, 58.453716 +CTUN, 666, 0.20, -0.11, 0.000000, 0, 0, -3, 666, 0 +ATT, 0.00, -0.65, -2.14, -0.69, 0.00, 61.81, 62.38 +CTUN, 666, 0.20, 0.01, 0.000000, 0, 0, -2, 666, 0 +ATT, 0.00, -1.18, -2.24, -1.59, 0.00, 63.35, 62.38 +CTUN, 666, 0.20, 0.23, 0.000000, 0, 0, -1, 666, 0 +ATT, 0.00, -1.20, -2.24, -2.01, 0.00, 64.98, 62.38 +CTUN, 666, 0.20, 0.17, 0.000000, 0, 0, 0, 665, 0 +ATT, 0.00, -1.02, -2.24, -1.38, 0.00, 66.50, 62.38 +CTUN, 665, 0.20, 0.09, 0.000000, 0, 0, 0, 664, 0 +ATT, 0.00, -0.43, -2.24, -0.97, 0.00, 67.95, 62.38 +CTUN, 665, 0.20, 0.16, 0.000000, 0, 0, 0, 665, 0 +ATT, 0.00, -0.12, -2.24, -1.39, 0.00, 69.04, 62.38 +CTUN, 666, 0.20, 0.26, 0.000000, 0, 0, -1, 666, 0 +ATT, 0.00, 0.00, -2.14, -2.15, 0.00, 69.78, 62.38 +CTUN, 666, 0.20, 0.42, 0.000000, 0, 0, 0, 666, 0 +ATT, 0.00, 0.26, -2.24, -1.39, 0.00, 70.20, 62.38 +CTUN, 665, 0.20, 0.32, 0.000000, 0, 0, 3, 665, 0 +ATT, 0.00, -0.42, -2.24, -0.56, 0.00, 70.42, 62.38 +CTUN, 665, 0.20, 0.39, 0.000000, 0, 0, 0, 666, 0 +ATT, 0.00, -0.33, -2.14, -0.73, 0.00, 70.56, 62.38 +DU32, 7, 166140 +CURR, 665, 94378, 1093, 1827, 5051, 63.492470 +CTUN, 665, 0.20, 0.31, 0.000000, 0, 0, 0, 665, 0 +ATT, 0.00, -0.03, -2.24, -1.22, 0.00, 70.46, 62.38 +CTUN, 665, 0.20, 0.42, 0.000000, 0, 0, 1, 665, 0 +ATT, 0.00, -0.26, -2.14, -1.07, 0.00, 70.10, 62.38 +CTUN, 665, 0.20, 0.26, 0.000000, 0, 0, 0, 665, 0 +ATT, 0.00, -0.48, -2.24, -1.22, 0.00, 69.59, 62.38 +CTUN, 665, 0.20, 0.28, 0.000000, 0, 0, -1, 665, 0 +MODE, ALT_HOLD, 634 +ATT, 0.00, -0.54, -2.24, -1.36, 0.00, 68.92, 62.38 +CTUN, 665, 0.20, -0.13, -0.282000, 0, 0, -2, 653, 40 +ATT, 0.00, 0.26, -2.24, -1.30, 0.00, 68.15, 62.38 +CTUN, 665, 0.20, 0.19, -0.221400, 0, 0, -3, 675, 41 +ATT, 0.00, 1.09, -2.24, -1.30, 0.00, 67.41, 62.38 +CTUN, 669, 0.20, 0.00, -0.161200, 0, 0, -1, 705, 40 +ATT, 0.00, 1.64, -2.14, -1.07, 0.00, 66.68, 62.38 +CTUN, 665, 0.20, -0.36, -0.100400, 0, 0, 4, 701, 40 +ATT, 0.00, 0.87, -2.05, -0.59, 0.00, 66.10, 62.38 +CTUN, 666, 0.20, -0.02, -0.059800, 0, 0, 10, 704, 41 +ATT, 0.00, -0.34, -2.24, -0.08, 0.00, 65.50, 62.38 +CTUN, 666, 0.20, 0.15, 0.001000, 0, 0, 15, 696, 41 +ATT, 0.00, -0.91, -2.24, 0.15, 0.00, 64.99, 62.38 +DU32, 7, 166132 +CURR, 666, 101172, 1073, 1933, 5028, 68.649132 +CTUN, 665, 0.20, 0.17, 0.081600, 0, 0, 19, 693, 41 +ATT, 0.00, -0.48, -2.24, 0.40, 0.00, 64.69, 62.38 +CTUN, 666, 0.20, 0.22, 0.161800, 0, 0, 24, 703, 41 +ATT, 0.00, 0.02, -2.24, 0.32, 0.00, 64.53, 62.38 +CTUN, 666, 0.20, 0.35, 0.234200, 0, 0, 24, 715, 40 +ATT, 0.00, 0.10, -2.24, -0.03, 0.00, 64.44, 62.38 +CTUN, 665, 0.20, 0.35, 0.334800, 0, 0, 31, 708, 40 +ATT, 0.00, -0.20, -2.24, -0.19, 0.00, 64.35, 62.38 +CTUN, 665, 0.20, 0.48, 0.397400, 0, 0, 34, 720, 41 +ATT, 0.00, -0.47, -2.24, -0.36, 0.00, 64.15, 62.38 +CTUN, 665, 0.20, 0.38, 0.507600, 0, 0, 37, 736, 40 +ATT, 0.00, 0.31, -2.24, -0.79, 0.00, 63.89, 62.38 +CTUN, 666, 0.23, 0.33, 0.608000, 0, 0, 41, 718, 40 +ATT, 0.46, 0.63, -2.05, -0.90, 0.00, 63.75, 62.38 +CTUN, 665, 0.23, 0.49, 0.678200, 0, 0, 42, 737, 40 +ATT, 3.00, 0.48, -2.05, -1.02, 0.00, 63.85, 62.38 +CTUN, 666, 0.27, 0.46, 0.750200, 0, 0, 43, 728, 40 +ATT, 5.34, 1.38, -2.05, -0.79, 0.00, 64.10, 62.38 +CTUN, 666, 0.27, 0.56, 0.812600, 0, 0, 46, 726, 40 +ATT, 5.06, 3.00, -2.05, -0.02, 0.00, 64.37, 62.38 +CTUN, 666, 0.34, 0.53, 0.913200, 0, 1, 47, 743, 40 +DU32, 7, 166132 +CURR, 665, 109100, 1072, 2158, 5028, 74.936569 +ATT, 5.43, 4.44, -2.05, 0.19, 0.00, 64.60, 62.38 +CTUN, 666, 0.34, 0.61, 0.935800, 0, 2, 46, 729, 41 +ATT, 4.50, 4.97, -2.05, -0.11, 0.00, 64.80, 62.38 +CTUN, 665, 0.41, 0.86, 1.028200, 0, 2, 46, 758, 41 +ATT, 3.18, 4.73, -2.05, -0.58, 0.00, 65.06, 62.38 +CTUN, 666, 0.41, 0.89, 1.068400, 0, 1, 48, 732, 40 +ATT, 3.00, 3.93, -2.24, -0.59, 0.00, 65.34, 62.38 +CTUN, 666, 0.48, 1.05, 1.160800, 0, 1, 49, 750, 41 +ATT, 1.87, 2.59, -2.24, -1.01, 0.00, 65.65, 62.38 +CTUN, 666, 0.48, 0.94, 1.211401, 0, 0, 49, 738, 41 +ATT, 0.84, 1.43, -2.05, -1.56, 0.00, 65.91, 62.38 +CTUN, 665, 0.55, 0.98, 1.303800, 0, 0, 48, 753, 41 +ATT, 0.46, 0.70, -2.24, -1.73, 0.00, 66.09, 62.38 +CTUN, 665, 0.55, 0.90, 1.344601, 0, 0, 48, 740, 41 +ATT, 0.46, -0.25, -2.24, -2.00, 0.00, 66.12, 62.38 +CTUN, 666, 0.62, 0.83, 1.417001, 0, 0, 50, 753, 41 +ATT, 0.37, -0.95, -2.24, -2.39, 0.00, 66.07, 62.38 +CTUN, 665, 0.62, 0.91, 1.447201, 0, 0, 50, 727, 40 +ATT, 0.46, -1.03, -2.24, -2.43, 0.00, 65.97, 62.38 +CTUN, 666, 0.69, 1.03, 1.527401, 0, 0, 51, 745, 40 +DU32, 7, 166132 +CURR, 666, 116510, 1059, 2112, 5051, 80.906990 +ATT, 0.46, -1.21, -2.24, -2.27, 0.00, 65.94, 62.38 +CTUN, 665, 0.69, 0.91, 1.558201, 0, 0, 52, 729, 40 +ATT, 0.46, -1.14, -2.24, -1.94, 0.00, 65.94, 62.38 +CTUN, 662, 0.76, 1.06, 1.638001, 0, 0, 52, 739, 39 +ATT, 0.46, -0.73, -2.24, -1.49, 0.00, 65.86, 62.38 +CTUN, 657, 0.76, 1.05, 1.655201, 0, 0, 53, 729, 35 +ATT, 0.46, -0.16, -2.24, -1.34, 0.00, 65.73, 62.38 +CTUN, 645, 0.82, 1.09, 1.719001, 0, 0, 50, 742, 28 +ATT, 0.84, 0.21, -2.24, -1.62, 0.00, 65.68, 62.38 +CTUN, 644, 0.82, 1.15, 1.736601, 0, 0, 51, 725, 27 +ATT, 1.03, 0.63, -2.24, -1.92, 0.00, 65.64, 62.38 +CTUN, 630, 0.89, 1.23, 1.796000, 0, 0, 51, 735, 22 +ATT, 1.59, 1.17, -2.24, -2.01, 0.00, 65.67, 62.38 +CTUN, 615, 0.89, 1.23, 1.799200, 0, 0, 50, 718, 9 +ATT, 1.78, 1.62, -2.24, -1.67, 0.00, 65.80, 62.38 +CTUN, 588, 0.96, 1.28, 1.839200, 0, 0, 49, 721, 0 +ATT, 1.78, 1.92, -2.24, -1.31, 0.00, 65.87, 62.38 +CTUN, 575, 0.96, 1.24, 1.819200, 0, 0, 46, 694, 0 +ATT, 1.78, 2.09, -2.05, -0.80, 0.00, 66.01, 62.38 +CTUN, 575, 1.03, 1.26, 1.849200, 0, 0, 42, 709, 0 +DU32, 7, 166132 +CURR, 575, 123751, 1073, 1922, 5028, 86.622047 +ATT, 1.21, 2.50, -2.05, -0.75, 0.00, 66.23, 62.38 +CTUN, 575, 1.03, 1.36, 1.809200, 0, 0, 37, 688, 0 +ATT, 0.46, 2.69, -2.05, -0.72, 0.00, 66.45, 62.38 +CTUN, 575, 1.09, 1.23, 1.839200, 0, 0, 31, 710, 0 +ATT, 0.00, 2.32, -2.05, -0.48, 0.00, 66.66, 62.38 +CTUN, 575, 1.09, 1.35, 1.789200, 0, 0, 27, 707, 0 +ATT, 0.00, 1.36, -0.18, -0.18, 0.00, 66.89, 62.38 +CTUN, 578, 1.13, 1.43, 1.809200, 0, 0, 24, 712, 0 +ATT, 0.00, 0.78, 0.00, 0.37, 0.00, 67.13, 62.38 +CTUN, 584, 1.13, 1.38, 1.789200, 0, 0, 21, 706, 0 +ATT, 0.00, 0.61, 0.00, 1.28, 0.00, 67.38, 62.38 +CTUN, 585, 1.17, 1.39, 1.799200, 0, 0, 19, 716, 0 +ATT, 0.00, 0.56, 0.00, 1.68, 0.00, 67.65, 62.38 +CTUN, 584, 1.17, 1.37, 1.769200, 0, 0, 17, 701, 0 +ATT, 0.00, 0.64, 0.00, 1.53, 0.00, 67.91, 62.38 +CTUN, 585, 1.17, 1.41, 1.769200, 0, 0, 15, 718, 0 +ATT, 0.00, 0.95, 0.00, 1.30, 0.00, 68.21, 62.38 +CTUN, 585, 1.09, 1.41, 1.779200, 0, 0, 14, 714, 0 +ATT, 0.00, 0.63, 0.00, 1.14, 0.00, 68.42, 62.38 +CTUN, 584, 1.09, 1.54, 1.859200, 0, 0, 15, 745, 0 +DU32, 7, 166132 +CURR, 584, 130868, 1061, 2233, 5051, 92.162010 +ATT, 0.00, -0.13, 0.00, 0.88, 0.00, 68.62, 62.38 +CTUN, 587, 1.09, 1.39, 1.869200, 0, 0, 19, 746, 0 +ATT, 0.00, -0.41, 0.00, 0.62, 0.00, 68.81, 62.38 +CTUN, 590, 1.12, 1.37, 1.879200, 0, 0, 23, 741, 0 +ATT, 0.00, -0.42, 0.00, 0.52, 0.00, 68.94, 62.38 +CTUN, 591, 1.12, 1.31, 1.869200, 0, 0, 27, 701, 0 +ATT, 0.00, -0.25, 0.00, 0.67, 0.00, 68.93, 62.38 +CTUN, 589, 1.20, 1.37, 1.879200, 0, 0, 25, 713, 0 +ATT, 0.00, -0.06, 0.00, 0.85, 0.00, 68.79, 62.38 +CTUN, 585, 1.15, 1.49, 1.799200, 0, 0, 23, 686, 0 +ATT, 0.00, 0.42, 0.00, 0.79, 0.00, 68.66, 62.38 +CTUN, 567, 1.15, 1.45, 1.869200, 0, 0, 19, 717, 0 +ATT, 0.00, 0.94, 0.00, 0.70, 0.00, 68.46, 62.38 +CTUN, 554, 1.15, 1.49, 1.869200, 0, 0, 16, 737, 0 +ATT, 0.00, 1.17, -0.09, 0.61, 0.00, 68.39, 62.38 +CTUN, 558, 1.23, 1.44, 1.879200, 0, 0, 17, 722, 0 +ATT, 0.00, 1.23, 0.00, 0.50, 0.00, 68.26, 62.38 +CTUN, 549, 1.23, 1.48, 1.809200, 0, 0, 18, 677, 0 +ATT, 0.00, 1.32, 0.00, 0.59, 0.00, 68.09, 62.38 +CTUN, 565, 1.27, 1.46, 1.809200, 0, 0, 13, 696, 0 +DU32, 7, 166132 +CURR, 575, 138004, 1066, 1895, 5028, 97.808418 +ATT, 0.00, 0.90, 0.00, 0.87, 0.00, 67.92, 62.38 +CTUN, 578, 1.27, 1.49, 1.769200, 0, 0, 9, 707, 0 +ATT, 0.00, -0.03, 0.00, 0.99, 0.00, 67.94, 62.38 +CTUN, 575, 1.28, 1.48, 1.769200, 0, 0, 5, 721, 0 +ATT, -2.27, -0.80, -2.24, 0.65, 0.00, 67.99, 62.38 +CTUN, 575, 1.28, 1.54, 1.749200, 0, 0, 1, 734, 0 +ATT, -2.36, -1.97, -2.33, -0.26, 0.00, 68.18, 62.38 +CTUN, 574, 1.28, 1.48, 1.739200, 0, 0, 1, 732, 0 +ATT, -4.26, -3.01, -2.52, -1.49, 0.00, 68.29, 62.38 +CTUN, 577, 1.22, 1.47, 1.729200, 0, 1, 1, 728, 0 +ATT, -4.26, -3.74, -2.52, -2.28, 0.00, 68.26, 62.38 +CTUN, 575, 1.22, 1.52, 1.789200, 0, 2, 1, 767, 0 +ATT, -2.93, -4.38, -2.89, -2.81, 0.00, 67.98, 62.38 +CTUN, 576, 1.22, 1.43, 1.779200, 0, 2, 8, 757, 0 +ATT, -0.18, -4.13, -2.80, -3.24, 0.00, 67.37, 62.38 +CTUN, 578, 1.22, 1.40, 1.779200, 0, 2, 11, 736, 0 +ATT, -0.09, -3.15, -2.42, -3.18, 0.00, 66.63, 62.38 +CTUN, 578, 1.22, 1.56, 1.779200, 0, 1, 14, 733, 0 +ATT, 0.00, -2.05, -2.42, -2.79, 0.00, 65.83, 62.38 +CTUN, 576, 1.25, 1.54, 1.789200, 0, 0, 13, 731, 0 +DU32, 7, 166132 +CURR, 577, 145350, 1063, 2069, 5051, 103.655980 +ATT, 0.00, -1.61, -2.61, -2.74, 0.00, 65.08, 62.38 +CTUN, 562, 1.22, 1.55, 1.769200, 0, 0, 13, 726, 0 +ATT, -0.09, -1.44, -2.61, -2.68, 0.00, 64.37, 62.38 +CTUN, 560, 1.25, 1.43, 1.799200, 0, 0, 11, 738, 0 +ATT, 0.00, -0.95, -2.70, -2.62, 0.00, 63.69, 62.38 +CTUN, 562, 1.25, 1.67, 1.769200, 0, 0, 11, 724, 0 +ATT, 0.00, -0.38, -2.42, -2.76, 0.00, 63.20, 62.38 +CTUN, 562, 1.29, 1.68, 1.779200, 0, 0, 11, 713, 0 +ATT, 0.00, 0.15, -2.52, -2.65, 0.00, 62.82, 62.38 +CTUN, 562, 1.29, 1.63, 1.759200, 0, 0, 11, 715, 0 +ATT, 0.00, 0.78, -2.42, -2.24, 0.00, 62.51, 62.38 +CTUN, 560, 1.30, 1.58, 1.759200, 0, 0, 9, 720, 0 +ATT, 0.00, 1.25, -2.52, -2.01, 0.00, 62.16, 62.38 +CTUN, 560, 1.30, 1.59, 1.749200, 0, 0, 5, 719, 0 +ATT, 0.00, 1.61, -2.52, -1.91, 0.00, 61.75, 62.38 +CTUN, 560, 1.32, 1.59, 1.759200, 0, 0, 6, 713, 0 +ATT, 0.00, 1.39, -2.42, -1.72, 0.00, 61.26, 62.38 +CTUN, 560, 1.32, 1.55, 1.739200, 0, 0, 7, 708, 0 +ATT, 0.00, 0.88, -2.52, -1.41, 0.00, 60.65, 62.38 +CTUN, 561, 1.32, 1.57, 1.729200, 0, 0, 5, 731, 0 +DU32, 7, 166132 +CURR, 562, 152557, 1065, 1969, 5051, 109.220810 +ATT, 0.00, 0.56, -2.24, -1.50, 0.00, 59.98, 62.38 +CTUN, 556, 1.32, 1.60, 1.729200, 0, 0, 2, 719, 0 +ATT, 0.00, 1.14, -2.52, -1.77, 0.00, 59.55, 62.38 +CTUN, 558, 1.33, 1.61, 1.729200, 0, 0, 2, 720, 0 +ATT, 0.00, 1.59, -2.52, -1.93, 0.00, 59.27, 62.38 +CTUN, 561, 1.33, 1.73, 1.719200, 0, 0, 1, 714, 0 +ATT, 0.00, 1.37, -2.52, -1.79, 0.00, 59.08, 62.38 +CTUN, 560, 1.33, 1.66, 1.719200, 0, 0, 0, 711, 0 +ATT, 0.00, 1.23, -2.42, -1.40, 0.00, 59.00, 62.38 +CTUN, 561, 1.33, 1.63, 1.719200, 0, 0, 0, 735, 0 +ATT, 0.00, 1.39, -2.52, -0.88, 0.00, 59.15, 62.38 +CTUN, 561, 1.33, 1.62, 1.719200, 0, 0, -3, 729, 0 +ATT, 0.00, 1.10, -2.52, -0.82, 0.00, 59.54, 62.38 +CTUN, 555, 1.32, 1.71, 1.709200, 0, 0, -1, 729, 0 +ATT, 0.00, 0.86, -2.42, -1.14, 0.00, 60.01, 62.38 +CTUN, 555, 1.32, 1.75, 1.719200, 0, 0, 0, 742, 0 +ATT, 0.00, 1.17, -2.52, -1.51, 0.00, 60.34, 62.38 +PM, 0, 0, 0, 0, 1000, 10484, 0, 0 +CTUN, 552, 1.31, 1.85, 1.729200, 0, 0, 1, 741, 0 +ATT, 0.00, 1.24, -2.42, -1.58, 0.00, 60.42, 62.38 +CTUN, 553, 1.31, 1.66, 1.749200, 0, 0, 1, 742, 0 +DU32, 7, 166132 +CURR, 553, 159835, 1063, 2079, 5051, 114.962650 +ATT, 0.00, 0.82, -2.42, -1.28, 0.00, 60.33, 62.38 +CTUN, 551, 1.31, 1.70, 1.749200, 0, 0, 4, 729, 0 +ATT, 0.00, 0.20, -2.52, -1.01, 0.00, 60.16, 62.38 +CTUN, 553, 1.31, 1.70, 1.759200, 0, 0, 5, 729, 0 +ATT, 0.00, -0.14, -2.52, -1.02, 0.00, 59.76, 62.38 +CTUN, 599, 1.31, 1.65, 1.759200, 0, 0, 7, 731, 0 +ATT, 0.00, -0.29, -2.42, -1.07, 0.00, 59.19, 62.38 +CTUN, 551, 1.31, 1.70, 1.769200, 0, 0, 4, 731, 0 +ATT, 0.00, -0.18, -2.52, -1.28, 0.00, 58.54, 62.38 +CTUN, 551, 1.31, 1.66, 1.769200, 0, 0, 5, 730, 0 +ATT, 0.00, -0.51, -2.24, -1.59, 0.00, 57.82, 62.38 +CTUN, 597, 1.31, 1.70, 1.769200, 0, 0, 2, 741, 0 +ATT, 0.00, -1.11, -2.24, -2.18, 0.00, 57.13, 62.38 +CTUN, 551, 1.30, 1.81, 1.769200, 0, 0, 1, 740, 0 +ATT, 0.00, -1.49, -2.42, -2.80, 0.00, 56.64, 62.38 +CTUN, 551, 1.31, 1.74, 1.789200, 0, 1, 2, 748, 0 +ATT, 0.00, -1.80, -2.24, -2.70, 0.00, 56.51, 62.38 +CTUN, 551, 1.31, 1.67, 1.779200, 0, 0, 2, 748, 0 +ATT, 0.00, -1.71, -2.05, -2.12, 0.00, 56.63, 62.38 +CTUN, 551, 1.33, 1.74, 1.779200, 0, 0, 3, 741, 0 +DU32, 7, 166132 +CURR, 595, 167190, 1055, 2103, 5051, 120.729560 +ATT, 0.00, -1.21, -1.96, -1.48, 0.00, 57.05, 62.38 +CTUN, 564, 1.31, 1.74, 1.769200, 0, 0, 1, 736, 0 +ATT, 0.00, -0.87, -0.93, -0.95, 0.00, 57.72, 62.38 +CTUN, 563, 1.31, 1.65, 1.789200, 0, 0, 3, 748, 0 +ATT, 0.00, -0.95, -0.93, -0.49, 0.00, 58.72, 62.38 +CTUN, 562, 1.31, 1.66, 1.789200, 0, 0, 2, 751, 0 +ATT, 0.00, -0.98, 0.00, -0.41, 0.00, 59.59, 62.38 +CTUN, 562, 1.34, 1.67, 1.789200, 0, 0, 4, 735, 0 +ATT, 0.00, -0.97, 0.00, -0.07, 0.00, 60.35, 62.38 +CTUN, 562, 1.34, 1.55, 1.759200, 0, 0, 4, 725, 0 +ATT, 0.00, -0.89, 0.00, 0.61, 0.00, 61.07, 62.38 +CTUN, 558, 1.34, 1.74, 1.749200, 0, 0, 4, 737, 0 +ATT, 0.28, -0.73, 0.00, 1.32, 0.00, 61.71, 62.38 +CTUN, 558, 1.34, 1.65, 1.759200, 0, 0, 2, 729, 0 +ATT, 0.65, -0.31, 0.00, 1.82, 0.00, 62.24, 62.38 +CTUN, 558, 1.35, 1.63, 1.749200, 0, 0, 1, 728, 0 +ATT, 1.96, 0.17, 0.00, 1.77, 0.00, 62.74, 62.38 +CTUN, 557, 1.35, 1.68, 1.739200, 0, 0, 1, 725, 0 +ATT, 3.18, 1.04, 0.00, 1.46, 0.00, 63.28, 62.38 +CTUN, 557, 1.36, 1.67, 1.739200, 0, 0, 1, 722, 0 +DU32, 7, 166132 +CURR, 557, 174538, 1055, 2045, 5051, 126.465110 +ATT, 4.40, 2.16, 0.00, 1.06, 0.00, 63.90, 62.38 +CTUN, 556, 1.36, 1.64, 1.729200, 0, 0, 2, 734, 0 +ATT, 6.00, 3.14, 0.00, 0.88, 0.00, 64.46, 62.38 +CTUN, 555, 1.36, 1.54, 1.719200, 0, 1, 1, 734, 0 +ATT, 5.25, 4.71, 0.00, 0.64, 0.00, 64.85, 62.38 +CTUN, 555, 1.36, 1.72, 1.719200, 0, 2, 2, 732, 0 +ATT, 3.46, 5.50, -0.93, 0.67, 0.00, 64.91, 62.38 +CTUN, 557, 1.36, 1.54, 1.719200, 0, 2, 1, 739, 0 +ATT, 3.18, 4.43, -1.49, 0.46, 0.00, 64.72, 62.38 +CTUN, 556, 1.36, 1.60, 1.709200, 0, 1, 0, 749, 0 +ATT, 2.43, 3.07, -2.24, -0.17, 0.00, 64.39, 62.38 +CTUN, 556, 1.36, 1.62, 1.699200, 0, 0, -1, 745, 0 +ATT, 0.46, 2.32, -2.52, -0.66, 0.00, 63.95, 62.38 +CTUN, 556, 1.35, 1.63, 1.699200, 0, 0, 0, 746, 0 +ATT, 0.28, 1.36, -2.52, -0.91, 0.00, 63.35, 62.38 +CTUN, 555, 1.36, 1.62, 1.699200, 0, 0, -1, 738, 0 +ATT, 0.09, 0.84, -2.52, -1.34, 0.00, 62.79, 62.38 +CTUN, 554, 1.35, 1.58, 1.689200, 0, 0, 0, 736, 0 +ATT, 0.28, 0.63, -2.52, -1.79, 0.00, 62.18, 62.38 +CTUN, 555, 1.36, 1.58, 1.699200, 0, 0, 0, 742, 0 +DU32, 7, 166132 +CURR, 555, 181912, 1051, 2088, 5051, 132.255620 +ATT, 0.28, 0.39, -2.24, -2.40, 0.00, 61.72, 62.38 +CTUN, 555, 1.36, 1.71, 1.679200, 0, 0, 1, 750, 0 +ATT, 0.37, 0.43, -2.52, -2.72, 0.00, 61.31, 62.38 +CTUN, 555, 1.36, 1.62, 1.679200, 0, 0, 1, 736, 0 +ATT, 0.28, 0.29, -2.42, -2.59, 0.00, 61.03, 62.38 +CTUN, 555, 1.36, 1.67, 1.679200, 0, 0, 1, 741, 0 +ATT, 0.09, -0.03, -2.42, -2.85, 0.00, 60.92, 62.38 +CTUN, 553, 1.38, 1.62, 1.679200, 0, 0, 3, 736, 0 +ATT, 0.28, -0.49, -2.52, -3.18, 0.00, 60.99, 62.38 +CTUN, 553, 1.38, 1.61, 1.659200, 0, 1, 2, 725, 0 +ATT, 0.28, -0.62, -2.52, -3.51, 0.00, 61.19, 62.38 +CTUN, 552, 1.38, 1.64, 1.659200, 0, 1, 4, 720, 0 +ATT, 0.18, -0.41, -2.42, -3.37, 0.00, 61.42, 62.38 +CTUN, 553, 1.38, 1.64, 1.669200, 0, 0, 2, 725, 0 +ATT, 0.28, 0.06, -2.33, -2.92, 0.00, 61.57, 62.38 +CTUN, 550, 1.39, 1.60, 1.669200, 0, 0, 1, 727, 0 +ATT, 0.93, 0.33, -2.14, -2.44, 0.00, 61.68, 62.38 +CTUN, 544, 1.39, 1.56, 1.649200, 0, 0, 0, 729, 0 +ATT, 1.03, 0.46, -2.24, -2.53, 0.00, 61.85, 62.38 +CTUN, 546, 1.40, 1.53, 1.639200, 0, 0, -3, 723, 0 +DU32, 7, 166132 +CURR, 546, 189240, 1060, 2009, 5051, 137.897920 +ATT, 0.46, 0.84, -2.24, -2.73, 0.00, 62.07, 62.38 +CTUN, 547, 1.40, 1.61, 1.619200, 0, 0, -3, 724, 0 +ATT, 0.37, 0.73, -2.33, -2.57, 0.00, 62.34, 62.38 +CTUN, 546, 1.41, 1.64, 1.609200, 0, 0, -6, 735, 0 +ATT, 0.46, 0.31, -2.24, -2.44, 0.00, 62.83, 62.38 +CTUN, 546, 1.40, 1.63, 1.599200, 0, 0, -7, 732, 0 +ATT, 0.46, 0.18, -2.24, -2.44, 0.00, 63.38, 62.38 +CTUN, 547, 1.40, 1.65, 1.599200, 0, 0, -8, 735, 0 +ATT, 0.46, 0.31, -2.24, -2.39, 0.00, 64.14, 62.38 +CTUN, 546, 1.40, 1.66, 1.589200, 0, 0, -7, 733, 0 +ATT, 0.46, 0.39, -2.24, -2.41, 0.00, 65.11, 62.38 +CTUN, 546, 1.40, 1.64, 1.589200, 0, 0, -6, 732, 0 +ATT, 0.46, 0.55, -2.24, -2.53, 0.00, 66.29, 62.38 +CTUN, 546, 1.39, 1.55, 1.579200, 0, 0, -7, 734, 0 +ATT, 0.18, 0.58, -2.24, -2.52, 0.00, 67.61, 62.38 +CTUN, 597, 1.39, 1.66, 1.579200, 0, 0, -6, 735, 0 +ATT, 0.00, 0.37, -2.14, -2.45, 0.00, 68.78, 62.38 +CTUN, 544, 1.38, 1.60, 1.579200, 0, 0, -4, 734, 0 +ATT, 0.00, -0.02, -2.24, -2.21, 0.00, 69.81, 62.38 +CTUN, 547, 1.38, 1.57, 1.589200, 0, 0, -2, 729, 0 +ATT, 0.00, -0.02, -2.24, -1.67, 0.00, 70.71, 62.38 +DU32, 7, 166132 +CURR, 546, 196582, 1056, 2093, 5051, 143.629650 +CTUN, 546, 1.38, 1.72, 1.579200, 0, 0, -4, 737, 0 +ATT, 0.00, 0.08, -2.24, -1.25, 0.00, 71.56, 62.38 +CTUN, 546, 1.38, 1.61, 1.579200, 0, 0, -2, 724, 0 +ATT, 0.00, 0.32, -2.24, -1.07, 0.00, 72.27, 62.38 +CTUN, 546, 1.38, 1.59, 1.579200, 0, 0, -3, 726, 0 +ATT, 0.00, 0.23, -2.24, -1.23, 0.00, 72.82, 62.82 +CTUN, 547, 1.38, 1.62, 1.579200, 0, 0, -3, 729, 0 +ATT, 0.00, -0.13, -2.52, -1.35, 0.00, 73.31, 63.31 +CTUN, 547, 1.38, 1.66, 1.579200, 0, 0, -5, 736, 0 +ATT, 0.00, -0.80, -2.42, -1.52, 0.00, 73.63, 63.63 +CTUN, 547, 1.38, 1.65, 1.569200, 0, 0, -6, 738, 0 +ATT, 0.00, -0.97, -2.42, -1.83, 0.00, 73.98, 63.98 +CTUN, 546, 1.38, 1.76, 1.569200, 0, 0, -4, 751, 0 +ATT, 0.00, -0.40, -2.24, -1.97, 0.00, 74.22, 64.22 +CTUN, 547, 1.38, 1.63, 1.579200, 0, 0, -4, 735, 0 +ATT, 0.00, 0.17, -2.33, -2.01, 0.00, 74.32, 64.32 +CTUN, 546, 1.36, 1.73, 1.579200, 0, 0, 0, 714, 0 +ATT, 0.00, 0.87, -2.42, -2.20, 0.00, 74.31, 64.32 +CTUN, 547, 1.37, 1.73, 1.599200, 0, 0, -2, 747, 0 +ATT, 0.00, 1.56, -2.42, -2.27, 0.00, 74.24, 64.32 +DU32, 7, 166132 +CURR, 546, 203936, 1056, 2049, 5028, 149.429180 +CTUN, 546, 1.36, 1.64, 1.599200, 0, 0, -2, 737, 0 +ATT, 0.00, 2.07, -2.24, -1.77, 0.00, 73.99, 64.32 +CTUN, 546, 1.36, 1.71, 1.609200, 0, 0, -1, 735, 0 +ATT, 0.00, 2.28, -2.24, -0.88, 0.00, 73.43, 64.32 +CTUN, 546, 1.36, 1.76, 1.619200, 0, 0, 0, 739, 0 +ATT, 0.00, 1.93, -2.24, 0.11, 0.00, 72.55, 64.32 +CTUN, 546, 1.36, 1.61, 1.619200, 0, 0, 0, 736, 0 +ATT, 0.00, 1.71, -2.24, 1.00, 0.00, 71.43, 64.32 +CTUN, 546, 1.32, 1.61, 1.629200, 0, 0, 0, 752, 0 +ATT, 0.00, 1.94, -2.24, 1.36, 0.00, 70.08, 64.32 +CTUN, 546, 1.36, 1.67, 1.669200, 0, 0, -1, 754, 0 +ATT, 0.00, 1.79, -2.24, 1.26, 0.00, 68.80, 64.32 +CTUN, 546, 1.36, 1.72, 1.629200, 0, 0, 0, 745, 0 +ATT, 0.00, 1.27, -2.24, 0.52, 0.00, 67.67, 64.32 +CTUN, 546, 1.37, 1.69, 1.639200, 0, 0, 4, 731, 0 +ATT, 0.00, 0.47, -2.24, -0.42, 0.00, 66.68, 64.32 +CTUN, 546, 1.36, 1.81, 1.639200, 0, 0, 3, 734, 0 +ATT, 0.00, 0.03, -2.33, -0.94, 0.00, 65.82, 64.32 +CTUN, 537, 1.36, 1.68, 1.659200, 0, 0, 3, 735, 0 +ATT, 0.00, 0.37, -2.33, -1.12, 0.00, 65.11, 64.32 +DU32, 7, 166132 +CURR, 537, 211302, 1064, 1979, 5028, 155.222180 +CTUN, 537, 1.36, 1.72, 1.659200, 0, 0, 2, 729, 0 +ATT, 0.00, 1.06, -2.42, -1.17, 0.00, 64.57, 64.32 +CTUN, 535, 1.36, 1.70, 1.669200, 0, 0, 1, 732, 0 +ATT, 0.00, 1.04, -2.42, -0.95, 0.00, 64.29, 64.32 +CTUN, 535, 1.36, 1.71, 1.679200, 0, 0, 0, 739, 0 +ATT, 0.00, 0.56, -2.42, -1.02, 0.00, 64.21, 64.32 +CTUN, 536, 1.37, 1.84, 1.679200, 0, 0, 0, 737, 0 +ATT, 0.00, 0.10, -2.42, -1.31, 0.00, 64.32, 64.32 +CTUN, 537, 1.37, 1.70, 1.679200, 0, 0, 0, 723, 0 +ATT, 0.00, -0.27, -2.52, -1.69, 0.00, 64.63, 64.32 +CTUN, 535, 1.38, 1.68, 1.679200, 0, 0, 1, 726, 0 +ATT, 0.00, -0.60, -2.52, -1.78, 0.00, 64.98, 64.32 +CTUN, 535, 1.38, 1.70, 1.669200, 0, 0, 0, 716, 0 +ATT, 0.00, -1.19, -2.33, -1.83, 0.00, 65.49, 64.32 +CTUN, 533, 1.44, 1.65, 1.669200, 0, 0, 0, 720, 0 +ATT, -2.46, -1.94, -2.42, -1.83, 0.00, 66.11, 64.32 +CTUN, 535, 1.44, 1.74, 1.609200, 0, 0, -3, 701, 0 +ATT, 0.00, -1.90, -2.42, -2.25, 0.00, 66.73, 64.32 +CTUN, 535, 1.44, 1.62, 1.609200, 0, 0, -6, 716, 0 +ATT, -2.55, -1.84, -2.42, -2.38, 0.00, 67.18, 64.32 +DU32, 7, 166132 +CURR, 534, 218592, 1063, 1893, 5051, 160.758710 +CTUN, 533, 1.44, 1.70, 1.599200, 0, 0, -10, 735, 0 +ATT, 0.00, -2.50, -2.33, -2.34, 0.00, 67.50, 64.32 +CTUN, 535, 1.44, 1.68, 1.589200, 0, 1, -13, 727, 0 +ATT, 0.00, -2.75, -2.33, -2.19, 0.00, 67.69, 64.32 +CTUN, 535, 1.43, 1.70, 1.569200, 0, 0, -13, 734, 0 +ATT, 0.00, -2.05, -2.52, -1.85, 0.00, 67.60, 64.32 +CTUN, 535, 1.43, 1.74, 1.569200, 0, 0, -14, 752, 0 +ATT, 0.00, -1.44, -2.33, -1.54, 0.00, 67.09, 64.32 +CTUN, 535, 1.40, 1.70, 1.559200, 0, 0, -13, 752, 0 +ATT, 0.00, -1.17, -2.52, -1.21, 0.00, 66.32, 64.32 +CTUN, 535, 1.40, 1.67, 1.589200, 0, 0, -10, 757, 0 +ATT, 0.00, -1.41, -2.42, -0.90, 0.00, 65.44, 64.32 +CTUN, 535, 1.39, 1.63, 1.579200, 0, 0, -7, 749, 0 +ATT, 0.00, -1.13, -2.52, -0.74, 0.00, 64.55, 64.32 +CTUN, 535, 1.39, 1.70, 1.589200, 0, 0, -5, 739, 0 +ATT, 0.00, -0.53, -2.52, -0.67, 0.00, 63.65, 64.32 +CTUN, 535, 1.39, 1.59, 1.589200, 0, 0, -3, 741, 0 +ATT, 0.00, -0.30, -2.52, -0.77, 0.00, 62.73, 64.32 +CTUN, 535, 1.39, 1.62, 1.589200, 0, 0, -1, 727, 0 +ATT, 0.00, -0.19, -2.52, -0.90, 0.00, 61.83, 64.32 +DU32, 7, 166132 +CURR, 535, 226032, 1056, 2017, 5051, 166.545200 +CTUN, 529, 1.39, 1.77, 1.589200, 0, 0, -1, 741, 0 +ATT, 0.00, -0.39, -2.24, -1.17, 0.00, 61.03, 64.32 +CTUN, 519, 1.39, 1.58, 1.589200, 0, 0, -3, 724, 0 +ATT, 0.00, -0.48, -2.42, -1.24, 0.00, 60.32, 64.32 +CTUN, 513, 1.39, 1.60, 1.589200, 0, 0, -2, 733, 0 +ATT, 0.00, -0.47, -2.42, -1.02, 0.00, 59.78, 64.32 +CTUN, 510, 1.39, 1.70, 1.589200, 0, 0, -2, 735, 0 +ATT, 0.00, -0.28, -2.42, -0.93, 0.00, 59.60, 64.32 +CTUN, 510, 1.39, 1.72, 1.589200, 0, 0, -3, 746, 0 +ATT, 0.00, -0.34, -2.42, -1.01, 0.00, 59.81, 64.32 +CTUN, 503, 1.39, 1.62, 1.589200, 0, 0, -4, 732, 0 +ATT, 0.00, -0.17, -2.52, -1.44, 0.00, 60.15, 64.32 +CTUN, 502, 1.39, 1.67, 1.589200, 0, 0, -4, 727, 0 +ATT, 0.00, -0.20, -2.24, -1.77, 0.00, 60.56, 64.32 +CTUN, 504, 1.40, 1.60, 1.589200, 0, 0, -4, 733, 0 +ATT, 0.00, -0.65, -2.05, -1.91, 0.00, 60.86, 64.32 +PM, 0, 0, 0, 1, 1000, 10508, 0, 0 +CTUN, 503, 1.40, 1.64, 1.569200, 0, 0, -4, 730, 0 +ATT, 0.28, -1.07, -2.24, -2.30, 0.00, 61.06, 64.32 +CTUN, 503, 1.40, 1.68, 1.569200, 0, 0, -6, 735, 0 +ATT, 0.28, -1.04, -2.24, -2.81, 0.00, 61.28, 64.32 +DU32, 7, 166132 +CURR, 503, 233339, 1044, 2026, 5051, 172.191180 +CTUN, 504, 1.40, 1.67, 1.569200, 0, 0, -7, 740, 0 +ATT, 2.15, -1.04, -2.24, -3.11, 0.00, 61.71, 64.32 +CTUN, 504, 1.40, 1.68, 1.559200, 0, 1, -7, 739, 0 +ATT, 2.15, -0.54, -2.24, -3.34, 0.00, 62.34, 64.32 +CTUN, 500, 1.40, 1.73, 1.559200, 0, 0, -6, 743, 0 +ATT, 3.18, 0.54, -2.14, -2.98, 0.00, 63.27, 64.32 +CTUN, 495, 1.40, 1.63, 1.559200, 0, 0, -7, 745, 0 +ATT, 3.46, 1.56, -2.24, -2.39, 0.00, 64.48, 64.32 +CTUN, 503, 1.39, 1.63, 1.559200, 0, 0, -8, 757, 0 +ATT, 6.00, 2.32, -2.05, -2.08, 0.00, 65.91, 64.32 +CTUN, 503, 1.39, 1.71, 1.559200, 0, 1, -7, 754, 0 +ATT, 5.90, 3.93, -2.05, -1.98, 0.00, 67.38, 64.32 +CTUN, 503, 1.39, 1.77, 1.559200, 0, 2, -4, 742, 0 +ATT, 6.09, 5.64, -2.05, -1.93, 0.00, 68.74, 64.32 +CTUN, 503, 1.39, 1.73, 1.569200, 0, 3, -2, 729, 0 +ATT, 6.28, 5.97, -2.05, -1.83, 0.00, 70.00, 64.32 +CTUN, 503, 1.33, 1.80, 1.579200, 0, 3, -2, 741, 0 +ATT, 6.00, 5.64, -2.05, -1.94, 0.00, 70.80, 64.32 +CTUN, 503, 1.33, 1.79, 1.649200, 0, 3, 0, 759, 0 +ATT, 2.81, 5.78, -2.24, -2.17, 0.00, 71.20, 64.32 +DU32, 7, 166132 +CURR, 503, 240746, 1046, 2093, 5051, 177.979870 +CTUN, 503, 1.30, 1.71, 1.659200, 0, 3, 4, 725, 0 +ATT, 0.18, 5.35, -2.24, -2.53, 0.00, 71.15, 64.32 +CTUN, 503, 1.32, 1.76, 1.699200, 0, 2, 5, 734, 0 +ATT, 0.00, 4.09, -2.24, -2.81, 0.00, 70.85, 64.32 +CTUN, 503, 1.32, 1.69, 1.689200, 0, 1, 8, 730, 0 +ATT, 0.00, 3.19, -2.14, -2.92, 0.00, 70.33, 64.32 +CTUN, 503, 1.34, 1.77, 1.699200, 0, 1, 9, 724, 0 +ATT, 0.00, 2.62, -2.24, -2.50, 0.00, 69.63, 64.32 +CTUN, 503, 1.34, 1.73, 1.699200, 0, 0, 9, 705, 0 +ATT, 0.00, 2.15, -2.24, -1.86, 0.00, 68.76, 64.32 +CTUN, 502, 1.43, 1.67, 1.709200, 0, 0, 5, 700, 0 +ATT, 0.00, 1.70, -2.24, -1.69, 0.00, 67.71, 64.32 +CTUN, 499, 1.43, 1.69, 1.629200, 0, 0, 1, 684, 0 +ATT, 0.00, 1.09, -2.24, -1.62, 0.00, 66.78, 64.32 +CTUN, 495, 1.45, 1.69, 1.619200, 0, 0, -1, 708, 0 +ATT, 0.00, 0.46, -2.24, -1.33, 0.00, 65.83, 64.32 +CTUN, 490, 1.45, 1.79, 1.599200, 0, 0, -10, 712, 0 +ATT, 0.00, -0.03, -2.24, -0.80, 0.00, 64.97, 64.32 +CTUN, 488, 1.45, 1.64, 1.589200, 0, 0, -12, 725, 0 +ATT, 0.00, -0.14, -2.24, -0.30, 0.00, 64.19, 64.32 +DU32, 7, 166132 +CURR, 488, 247874, 1055, 2014, 5051, 183.449490 +CTUN, 486, 1.45, 1.76, 1.569200, 0, 0, -16, 738, 0 +ATT, 0.00, -0.07, -2.24, -0.33, 0.00, 63.70, 64.32 +MODE, STABILIZE, 700 +CTUN, 486, 1.45, 1.71, 0.000000, 0, 0, -15, 486, 0 +ATT, 0.00, -0.16, -2.24, -0.77, 0.00, 63.45, 64.32 +CTUN, 489, 1.42, 1.52, 0.000000, 0, 0, -26, 489, 0 +ATT, 0.00, -0.49, -2.14, -1.01, 0.00, 63.54, 64.32 +CTUN, 495, 1.42, 1.59, 0.000000, 0, 0, -61, 493, 0 +ATT, 0.00, -0.56, -2.05, -1.51, 0.00, 63.64, 64.32 +CTUN, 507, 1.39, 1.65, 0.000000, 0, 0, -96, 501, 0 +ATT, 0.00, -0.20, -2.42, -2.36, 0.00, 63.62, 64.32 +CTUN, 553, 1.39, 1.45, 0.000000, 0, 0, -139, 553, 0 +ATT, 0.00, 0.02, -2.24, -3.18, 0.00, 63.60, 64.32 +CTUN, 680, 1.25, 1.26, 0.000000, 0, 0, -166, 654, 0 +ATT, 0.00, 0.05, -2.52, -3.22, 0.00, 63.53, 64.32 +CTUN, 804, 1.25, 1.27, 0.000000, 0, 0, -185, 779, 0 +ATT, 0.00, -0.10, -2.33, -2.30, 0.00, 63.18, 64.32 +CTUN, 900, 0.97, 1.01, 0.000000, 0, 0, -192, 879, 0 +ATT, 0.00, -0.54, -2.14, -0.97, 0.00, 62.48, 64.32 +CTUN, 924, 0.97, 0.77, 0.000000, 0, 0, -176, 924, 0 +ATT, 0.00, -0.48, -2.52, -0.12, 0.00, 61.39, 64.32 +DU32, 7, 166140 +CURR, 985, 254361, 989, 3240, 5051, 188.248660 +CTUN, 1000, 0.97, 0.72, 0.000000, 0, 0, -148, 1000, 0 +ATT, 0.00, -0.54, -2.24, 1.57, 0.00, 60.12, 64.32 +CTUN, 1000, 0.97, 0.48, 0.000000, 0, 0, -104, 1000, 0 +ATT, 0.00, -0.51, -2.52, 2.43, 0.00, 59.27, 64.32 +CTUN, 999, 0.29, -1.73, 0.000000, 0, 0, -61, 1000, 0 +ATT, 0.00, -0.30, -2.33, 2.23, 0.00, 58.88, 64.32 +CTUN, 1000, 0.29, -3.65, 0.000000, 0, 0, 0, 1000, 0 +ATT, -6.63, 0.46, -2.52, 1.63, 0.00, 58.58, 64.32 +CTUN, 991, 0.21, -2.49, 0.000000, 0, 0, 41, 999, 0 +ATT, -8.14, -2.07, -4.76, 1.13, 0.00, 58.58, 64.32 +CTUN, 768, 0.21, -0.25, 0.000000, 0, 1, 83, 856, 0 +ATT, -10.13, -5.99, -8.12, 0.95, 0.00, 59.21, 64.32 +CTUN, 653, 0.21, 0.38, 0.000000, 0, 3, 101, 694, 0 +ATT, -12.60, -7.79, -9.14, -1.78, 0.00, 60.33, 64.32 +CTUN, 632, 0.22, 0.42, 0.000000, 0, 5, 96, 637, 0 +ATT, -13.64, -8.93, -10.92, -6.39, 0.00, 61.53, 64.32 +CTUN, 636, 0.22, 0.83, 0.000000, 0, 11, 78, 645, 0 +ATT, -14.87, -11.22, -10.73, -10.17, 0.00, 62.38, 64.32 +CTUN, 636, 0.40, 1.05, 0.000000, 0, 20, 53, 656, 0 +ATT, -10.70, -12.92, -8.02, -12.03, 0.00, 62.63, 64.32 +DU32, 7, 166140 +CURR, 634, 262848, 1066, 1595, 5051, 195.187640 +CTUN, 628, 0.40, 0.80, 0.000000, 0, 25, 32, 658, 0 +ATT, 0.00, -12.73, -2.05, -11.29, 0.00, 62.09, 64.32 +CTUN, 633, 0.56, 1.02, 0.000000, 0, 20, 11, 653, 0 +ATT, 0.00, -8.42, 0.00, -8.04, 0.00, 61.07, 64.32 +CTUN, 637, 0.56, 0.95, 0.000000, 0, 6, -7, 642, 0 +ATT, 0.00, -2.12, 2.05, -3.23, 0.00, 60.35, 64.32 +CTUN, 674, 0.62, 0.92, 0.000000, 0, 0, -25, 665, 0 +ATT, 2.62, 1.35, 2.52, 1.05, 0.00, 60.14, 64.32 +CTUN, 681, 0.60, 0.78, 0.000000, 0, 0, -43, 681, 0 +ATT, 6.18, 2.30, 2.52, 3.68, 0.00, 60.02, 64.32 +CTUN, 683, 0.60, 0.91, 0.000000, 0, 2, -55, 683, 0 +ATT, 6.93, 3.80, 2.33, 4.80, 0.00, 59.98, 64.32 +CTUN, 694, 0.57, 0.86, 0.000000, 0, 3, -67, 697, 0 +ATT, 6.09, 5.79, 0.93, 4.80, 0.00, 60.02, 64.32 +CTUN, 765, 0.57, 0.66, 0.000000, 0, 5, -77, 759, 0 +ATT, 4.87, 6.66, 0.00, 4.39, 0.00, 60.07, 64.32 +CTUN, 821, 0.45, 0.68, 0.000000, 0, 6, -79, 822, 0 +ATT, 4.87, 6.34, 0.00, 3.55, 0.00, 60.16, 64.32 +CTUN, 856, 0.45, 0.53, 0.000000, 0, 5, -69, 847, 0 +ATT, 4.40, 5.80, -2.24, 2.95, 0.00, 60.36, 64.32 +DU32, 7, 166140 +CURR, 857, 269908, 1008, 2652, 5028, 200.430210 +CTUN, 861, 0.32, 0.42, 0.000000, 0, 4, -50, 863, 0 +ATT, 2.53, 5.27, -2.24, 2.29, 0.00, 60.64, 64.32 +CTUN, 859, 0.32, 0.28, 0.000000, 0, 2, -28, 863, 0 +ATT, 1.87, 2.98, -2.24, 1.18, 0.00, 61.14, 64.32 +CTUN, 835, 0.20, 0.36, 0.000000, 0, 0, -4, 850, 0 +ATT, 0.00, 1.01, -3.45, -0.06, 0.00, 61.88, 64.32 +CTUN, 789, 0.21, 0.16, 0.000000, 0, 0, 21, 800, 0 +ATT, 0.00, -0.25, -6.16, -0.38, 0.00, 62.57, 64.32 +CTUN, 743, 0.20, 0.32, 0.000000, 0, 0, 36, 752, 0 +ATT, 0.00, -0.72, -8.86, -1.46, 0.00, 63.01, 64.32 +CTUN, 716, 0.21, 0.61, 0.000000, 0, 0, 42, 720, 0 +ATT, 0.00, -0.62, -8.86, -3.74, 0.00, 63.29, 64.32 +CTUN, 715, 0.21, 0.65, 0.000000, 0, 2, 43, 718, 0 +ATT, 0.00, 0.36, -6.81, -5.90, 0.00, 63.23, 64.32 +CTUN, 709, 0.28, 0.61, 0.000000, 0, 3, 37, 716, 0 +ATT, 0.00, 1.01, -2.05, -6.09, 0.00, 62.78, 64.32 +CTUN, 675, 0.28, 0.50, 0.000000, 0, 2, 28, 682, 0 +ATT, 0.00, 1.16, -2.05, -4.30, 0.00, 62.19, 64.32 +CTUN, 661, 0.35, 0.53, 0.000000, 0, 0, 14, 660, 0 +ATT, 0.00, 0.87, -2.52, -2.00, 0.00, 61.64, 64.32 +DU32, 7, 166140 +CURR, 665, 277560, 1066, 1618, 5051, 206.555770 +CTUN, 675, 0.35, 0.69, 0.000000, 0, 0, 0, 675, 0 +ATT, 0.00, 0.91, -3.73, -0.59, 0.00, 61.12, 64.32 +CTUN, 719, 0.40, 0.70, 0.000000, 0, 0, -14, 717, 0 +ATT, 0.00, 1.27, -4.38, -0.99, 0.00, 60.64, 64.32 +CTUN, 735, 0.39, 0.66, 0.000000, 0, 0, -21, 731, 0 +ATT, 0.00, 1.18, -6.53, -2.27, 0.00, 60.31, 64.32 +CTUN, 743, 0.39, 0.62, 0.000000, 0, 0, -26, 741, 0 +ATT, 0.00, 0.50, -6.81, -3.69, 0.00, 60.00, 64.32 +CTUN, 747, 0.38, 0.86, 0.000000, 0, 1, -28, 747, 0 +ATT, 0.00, 0.33, -7.56, -5.09, 0.00, 59.59, 64.32 +CTUN, 746, 0.38, 0.56, 0.000000, 0, 2, -23, 748, 0 +ATT, 0.00, 0.07, -7.56, -5.72, 0.00, 59.30, 64.32 +CTUN, 746, 0.32, 0.64, 0.000000, 0, 3, -20, 750, 0 +ATT, 0.00, -0.33, -7.46, -5.80, 0.00, 59.06, 64.32 +CTUN, 746, 0.32, 0.61, 0.000000, 0, 3, -15, 749, 0 +ATT, 0.00, -0.03, -5.41, -5.10, 0.00, 58.99, 64.32 +CTUN, 746, 0.28, 0.65, 0.000000, 0, 1, -10, 747, 0 +ATT, 0.00, 0.55, -2.42, -3.35, 0.00, 59.12, 64.32 +CTUN, 746, 0.28, 0.37, 0.000000, 0, 0, -4, 745, 0 +ATT, -0.56, 0.50, -2.33, -1.06, 0.00, 59.41, 64.32 +DU32, 7, 166140 +CURR, 746, 284901, 1046, 2086, 5051, 212.131620 +CTUN, 746, 0.25, 0.52, 0.000000, 0, 0, -2, 745, 0 +ATT, -2.27, 0.08, -2.24, 0.30, 0.00, 59.64, 64.32 +CTUN, 746, 0.25, 0.53, 0.000000, 0, 0, 0, 746, 0 +ATT, -3.88, -0.50, -1.77, 0.97, 0.00, 60.00, 64.32 +CTUN, 741, 0.23, 0.64, 0.000000, 0, 0, 4, 741, 0 +ATT, -5.21, -1.15, -1.68, 1.66, 0.00, 60.74, 64.32 +CTUN, 742, 0.23, 0.57, 0.000000, 0, 0, 7, 741, 0 +ATT, -6.25, -2.59, -1.40, 1.75, 0.00, 61.80, 64.32 +CTUN, 742, 0.23, 0.47, 0.000000, 0, 1, 6, 743, 0 +ATT, -6.63, -4.13, -1.40, 1.67, 0.00, 62.92, 64.32 +CTUN, 742, 0.23, 0.63, 0.000000, 0, 2, 8, 743, 0 +ATT, -6.72, -5.19, -1.96, 1.78, 0.00, 63.87, 64.32 +CTUN, 741, 0.23, 0.58, 0.000000, 0, 2, 9, 742, 0 +ATT, -6.72, -5.30, -2.52, 1.43, 0.00, 64.63, 64.32 +CTUN, 737, 0.24, 0.61, 0.000000, 0, 2, 12, 741, 0 +ATT, -2.27, -5.56, -2.24, 0.71, 0.00, 65.11, 64.32 +CTUN, 737, 0.24, 0.57, 0.000000, 0, 2, 10, 739, 0 +ATT, 0.00, -4.20, -2.42, 0.53, 0.00, 65.10, 64.32 +CTUN, 739, 0.25, 0.51, 0.000000, 0, 0, 6, 738, 0 +ATT, 0.00, -0.44, -2.42, 0.39, 0.00, 64.58, 64.32 +DU32, 7, 166140 +CURR, 739, 292325, 1034, 2020, 5051, 217.817120 +CTUN, 739, 0.25, 0.61, 0.000000, 0, 0, 6, 738, 0 +ATT, 0.00, 1.48, -2.24, 0.56, 0.00, 63.61, 64.32 +CTUN, 738, 0.26, 0.43, 0.000000, 0, 0, 6, 738, 0 +ATT, 0.00, 1.30, -2.24, 0.87, 0.00, 62.42, 64.32 +CTUN, 737, 0.25, 0.55, 0.000000, 0, 0, 7, 738, 0 +ATT, 0.00, 1.77, -2.24, 0.72, 0.00, 61.14, 64.32 +CTUN, 740, 0.25, 0.56, 0.000000, 0, 0, 6, 739, 0 +ATT, 0.00, 1.68, -2.52, 0.49, 0.00, 60.01, 64.32 +CTUN, 740, 0.25, 0.59, 0.000000, 0, 0, 5, 740, 0 +ATT, 0.00, 1.32, -2.24, -0.26, 0.00, 59.18, 64.32 +CTUN, 741, 0.26, 0.53, 0.000000, 0, 0, 5, 740, 0 +ATT, 0.00, 0.68, -2.24, -0.85, 0.00, 58.56, 64.32 +CTUN, 741, 0.26, 0.39, 0.000000, 0, 0, 6, 741, 0 +ATT, 0.00, -0.17, -4.76, -0.92, 0.00, 58.13, 64.32 +CTUN, 741, 0.27, 0.52, 0.000000, 0, 0, 9, 741, 0 +ATT, 0.00, -0.11, -6.44, -1.62, 0.00, 58.08, 64.32 +CTUN, 740, 0.26, 0.55, 0.000000, 0, 0, 7, 743, 0 +ATT, 0.00, 0.99, -6.53, -3.24, 0.00, 58.37, 64.32 +CTUN, 740, 0.27, 0.56, 0.000000, 0, 1, 7, 741, 0 +ATT, 0.00, 1.56, -6.81, -4.76, 0.00, 58.98, 64.32 +DU32, 7, 166140 +CURR, 740, 299722, 1051, 2061, 5028, 223.470660 +CTUN, 740, 0.27, 0.37, 0.000000, 0, 2, 9, 740, 0 +ATT, -0.37, 1.34, -7.18, -5.67, 0.00, 59.78, 64.32 +CTUN, 738, 0.27, 0.60, 0.000000, 0, 3, 8, 744, 0 +ATT, -0.56, 0.51, -6.62, -5.35, 0.00, 60.62, 64.32 +CTUN, 739, 0.27, 0.55, 0.000000, 0, 2, 8, 741, 0 +ATT, -0.75, -0.13, -5.69, -4.40, 0.00, 61.29, 64.32 +CTUN, 739, 0.28, 0.65, 0.000000, 0, 1, 8, 740, 0 +ATT, -3.22, -0.34, -3.17, -3.42, 0.00, 61.81, 64.32 +CTUN, 738, 0.28, 0.59, 0.000000, 0, 0, 4, 738, 0 +ATT, -5.87, -1.24, -2.70, -2.12, 0.00, 62.05, 64.32 +CTUN, 739, 0.28, 0.48, 0.000000, 0, 0, 3, 739, 0 +ATT, -6.63, -2.61, -2.70, -0.48, 0.00, 62.00, 64.32 +CTUN, 738, 0.28, 0.51, 0.000000, 0, 1, 5, 739, 0 +ATT, -6.72, -5.26, -3.08, 1.07, 0.00, 61.78, 64.32 +CTUN, 738, 0.28, 0.48, 0.000000, 0, 3, 3, 742, 0 +PM, 0, 0, 0, 0, 1000, 10468, 0, 0 +ATT, -6.91, -6.71, -4.10, 1.04, 0.00, 61.51, 64.32 +CTUN, 738, 0.28, 0.56, 0.000000, 0, 4, 1, 742, 0 +ATT, -6.72, -6.04, -4.29, 0.28, 0.00, 61.29, 64.32 +CTUN, 737, 0.28, 0.60, 0.000000, 0, 3, 1, 741, 0 +ATT, -3.22, -5.48, -3.17, -0.73, 0.00, 61.08, 64.32 +DU32, 7, 166140 +CURR, 737, 307130, 1054, 2037, 5028, 229.168010 +CTUN, 738, 0.28, 0.44, 0.000000, 0, 2, 0, 740, 0 +ATT, 0.00, -4.92, -2.52, -1.50, 0.00, 61.16, 64.32 +CTUN, 738, 0.28, 0.49, 0.000000, 0, 1, 0, 738, 0 +ATT, 0.00, -3.01, -2.52, -1.47, 0.00, 61.41, 64.32 +CTUN, 737, 0.28, 0.45, 0.000000, 0, 0, -1, 738, 0 +ATT, 0.00, -1.03, -2.42, -1.02, 0.00, 61.77, 64.32 +CTUN, 737, 0.28, 0.37, 0.000000, 0, 0, 0, 737, 0 +ATT, 0.00, 0.38, -2.24, -0.66, 0.00, 62.25, 64.32 +CTUN, 738, 0.26, 0.44, 0.000000, 0, 0, 0, 737, 0 +ATT, 0.00, 0.00, -2.33, -0.08, 0.00, 62.85, 64.32 +CTUN, 737, 0.26, 0.57, 0.000000, 0, 0, -1, 738, 0 +ATT, 0.00, -0.40, -2.24, 0.40, 0.00, 63.53, 64.32 +CTUN, 738, 0.25, 0.58, 0.000000, 0, 0, -1, 738, 0 +ATT, 0.09, -0.07, -2.52, 0.19, 0.00, 64.25, 64.32 +CTUN, 738, 0.25, 0.55, 0.000000, 0, 0, 1, 738, 0 +ATT, 2.15, -0.60, -2.05, -0.31, 0.00, 64.98, 64.32 +CTUN, 737, 0.24, 0.48, 0.000000, 0, 0, 2, 738, 0 +ATT, 3.18, -0.39, -2.24, -0.98, 0.00, 65.72, 64.32 +CTUN, 738, 0.24, 0.42, 0.000000, 0, 0, 2, 738, 0 +ATT, 3.09, 1.19, -2.24, -1.05, 0.00, 66.27, 64.32 +DU32, 7, 166140 +CURR, 738, 314512, 1042, 1993, 5028, 234.735640 +CTUN, 738, 0.23, 0.52, 0.000000, 0, 0, 5, 738, 0 +ATT, 3.18, 2.77, -2.24, -0.29, 0.00, 66.71, 64.32 +CTUN, 738, 0.23, 0.40, 0.000000, 0, 0, 6, 739, 0 +ATT, 3.28, 3.24, -2.24, 0.32, 0.00, 67.07, 64.32 +CTUN, 738, 0.23, 0.51, 0.000000, 0, 0, 6, 738, 0 +ATT, 3.18, 3.15, -2.24, 0.17, 0.00, 67.40, 64.32 +CTUN, 738, 0.23, 0.52, 0.000000, 0, 0, 8, 738, 0 +ATT, 1.78, 2.59, -2.52, -0.48, 0.00, 67.75, 64.32 +CTUN, 739, 0.23, 0.49, 0.000000, 0, 0, 9, 741, 0 +ATT, 0.00, 1.70, -2.61, -0.54, 0.00, 68.12, 64.32 +CTUN, 740, 0.23, 0.49, 0.000000, 0, 0, 11, 741, 0 +ATT, 0.00, 0.61, -3.26, -1.08, 0.00, 68.63, 64.32 +CTUN, 741, 0.23, 0.41, 0.000000, 0, 0, 12, 741, 0 +ATT, 0.00, -1.24, -3.26, -1.80, 0.00, 69.04, 64.32 +CTUN, 742, 0.24, 0.49, 0.000000, 0, 0, 11, 742, 0 +ATT, 0.00, -2.62, -3.17, -2.10, -0.28, 69.20, 64.22 +CTUN, 743, 0.24, 0.51, 0.000000, 0, 1, 11, 744, 0 +ATT, 0.00, -2.41, -3.26, -1.89, -2.26, 69.11, 63.54 +CTUN, 743, 0.26, 0.67, 0.000000, 0, 0, 13, 744, 0 +ATT, 0.00, -1.83, -3.26, -1.46, -3.20, 68.62, 62.19 +DU32, 7, 166140 +CURR, 743, 321912, 1045, 2077, 5051, 240.392430 +CTUN, 744, 0.26, 0.47, 0.000000, 0, 0, 11, 744, 0 +ATT, 0.00, -1.42, -3.26, -1.58, -3.58, 67.64, 60.63 +CTUN, 744, 0.28, 0.58, 0.000000, 0, 0, 9, 744, 0 +ATT, 0.28, -1.39, -3.26, -2.02, -4.15, 66.14, 58.91 +CTUN, 744, 0.28, 0.59, 0.000000, 0, 0, 10, 744, 0 +ATT, 1.03, -1.25, -2.98, -2.40, -4.24, 64.03, 57.01 +CTUN, 742, 0.29, 0.65, 0.000000, 0, 0, 11, 742, 0 +ATT, 1.68, 0.05, -2.70, -2.37, -4.15, 61.49, 55.09 +CTUN, 741, 0.29, 0.66, 0.000000, 0, 0, 11, 741, 0 +ATT, 1.78, 1.62, -2.52, -1.84, -4.15, 58.79, 53.19 +CTUN, 742, 0.31, 0.63, 0.000000, 0, 0, 11, 742, 0 +ATT, 2.90, 2.37, -2.24, -0.75, -4.15, 56.20, 51.28 +CTUN, 741, 0.31, 0.56, 0.000000, 0, 0, 9, 742, 0 +ATT, 2.90, 3.28, -2.52, -0.11, -4.24, 53.64, 49.37 +CTUN, 742, 0.31, 0.55, 0.000000, 0, 1, 10, 742, 0 +ATT, 2.53, 4.27, -2.52, 0.11, -3.77, 51.03, 47.50 +CTUN, 741, 0.31, 0.70, 0.000000, 0, 1, 6, 742, 0 +ATT, 1.78, 4.60, -2.42, 0.00, -3.77, 48.40, 45.75 +CTUN, 742, 0.32, 0.48, 0.000000, 0, 1, 7, 742, 0 +ATT, 1.78, 3.30, -3.54, -0.20, -3.77, 45.95, 44.04 +DU32, 7, 166140 +CURR, 741, 329336, 1049, 2063, 5051, 246.147740 +CTUN, 741, 0.32, 0.56, 0.000000, 0, 0, 7, 741, 0 +ATT, 0.00, 1.94, -4.76, -1.03, -3.39, 43.98, 42.38 +CTUN, 742, 0.34, 0.58, 0.000000, 0, 0, 6, 741, 0 +ATT, 0.00, 0.91, -6.25, -2.11, -2.26, 42.43, 40.97 +CTUN, 742, 0.34, 0.64, 0.000000, 0, 0, 4, 741, 0 +ATT, 0.00, 0.18, -6.90, -3.22, -1.98, 41.23, 40.03 +CTUN, 743, 0.36, 0.68, 0.000000, 0, 1, 5, 743, 0 +ATT, 0.00, -0.08, -7.93, -4.36, -1.79, 40.28, 39.14 +CTUN, 741, 0.35, 0.68, 0.000000, 0, 2, 5, 744, 0 +ATT, 0.00, -0.10, -8.12, -5.56, -1.79, 39.33, 38.27 +CTUN, 743, 0.36, 0.62, 0.000000, 0, 3, 2, 746, 0 +ATT, 0.00, -0.78, -3.54, -6.41, -1.60, 38.26, 37.44 +CTUN, 742, 0.36, 0.56, 0.000000, 0, 3, 2, 745, 0 +ATT, 0.00, -1.19, -2.24, -5.50, -1.41, 37.05, 36.66 +CTUN, 742, 0.36, 0.62, 0.000000, 0, 2, 2, 746, 0 +ATT, 0.00, -1.03, -2.24, -2.87, -0.84, 35.91, 36.12 +CTUN, 741, 0.36, 0.77, 0.000000, 0, 0, 0, 741, 0 +ATT, 0.00, -0.98, -2.24, -0.45, -0.18, 34.80, 35.91 +CTUN, 742, 0.36, 0.79, 0.000000, 0, 0, -2, 742, 0 +ATT, 0.00, -1.50, -2.24, 0.79, 0.00, 34.00, 35.83 +DU32, 7, 166140 +CURR, 742, 336762, 1047, 2018, 5028, 251.847320 +CTUN, 741, 0.36, 0.66, 0.000000, 0, 0, -2, 741, 0 +ATT, 0.00, -1.35, -2.61, 1.43, 0.00, 33.59, 35.83 +CTUN, 743, 0.36, 0.77, 0.000000, 0, 0, -4, 745, 0 +ATT, 0.00, -1.02, -4.20, 1.48, 0.00, 33.68, 35.83 +CTUN, 743, 0.35, 0.73, 0.000000, 0, 0, -8, 743, 0 +ATT, 0.00, -1.49, -4.76, 1.05, 0.00, 34.14, 35.83 +CTUN, 742, 0.35, 0.60, 0.000000, 0, 0, -10, 742, 0 +ATT, 0.00, -1.78, -5.32, 0.26, 0.00, 34.76, 35.83 +CTUN, 741, 0.32, 0.60, 0.000000, 0, 0, -10, 742, 0 +ATT, 0.00, -1.66, -6.72, -1.13, 0.00, 35.55, 35.83 +CTUN, 741, 0.32, 0.60, 0.000000, 0, 0, -11, 741, 0 +ATT, 0.00, -1.00, -10.73, -2.41, 0.00, 36.34, 35.83 +CTUN, 742, 0.30, 0.62, 0.000000, 0, 0, -11, 741, 0 +ATT, 0.00, 0.09, -10.64, -3.36, 0.00, 37.15, 35.83 +CTUN, 746, 0.30, 0.56, 0.000000, 0, 1, -10, 743, 0 +ATT, 0.00, 0.17, -9.05, -4.95, 0.00, 37.81, 35.83 +CTUN, 741, 0.27, 0.66, 0.000000, 0, 2, -10, 744, 0 +ATT, 0.00, 0.38, -7.84, -5.92, 0.00, 38.21, 35.83 +CTUN, 741, 0.27, 0.50, 0.000000, 0, 3, -12, 744, 0 +ATT, 0.00, 0.59, -8.12, -4.95, 0.00, 38.46, 35.83 +DU32, 7, 166140 +CURR, 742, 344187, 1049, 2063, 5051, 257.498930 +CTUN, 742, 0.24, 0.49, 0.000000, 0, 1, -8, 742, 0 +ATT, 0.00, 0.02, -8.02, -3.43, 0.00, 38.75, 35.83 +CTUN, 741, 0.24, 0.46, 0.000000, 0, 0, -3, 742, 0 +ATT, 0.00, -0.19, -7.84, -2.53, 0.00, 39.02, 35.83 +CTUN, 741, 0.23, 0.48, 0.000000, 0, 0, -3, 742, 0 +ATT, 0.00, 0.40, -7.74, -2.41, 0.00, 39.29, 35.83 +CTUN, 743, 0.23, 0.56, 0.000000, 0, 0, -4, 743, 0 +ATT, 0.00, 0.02, -7.84, -2.32, 0.00, 39.58, 35.83 +CTUN, 741, 0.22, 0.53, 0.000000, 0, 0, -2, 741, 0 +ATT, 0.00, -0.53, -7.37, -2.47, 0.00, 39.73, 35.83 +CTUN, 741, 0.22, 0.39, 0.000000, 0, 0, 1, 742, 0 +ATT, 0.00, 0.09, -6.81, -3.12, 0.00, 39.74, 35.83 +CTUN, 743, 0.21, 0.50, 0.000000, 0, 1, 4, 744, 0 +ATT, -0.56, 0.98, -4.57, -3.49, 0.00, 39.45, 35.83 +CTUN, 743, 0.21, 0.36, 0.000000, 0, 1, 9, 743, 0 +ATT, 0.00, -0.11, -2.52, -3.22, 0.00, 38.88, 35.83 +CTUN, 743, 0.21, 0.43, 0.000000, 0, 0, 12, 743, 0 +ATT, 0.00, -1.34, -2.42, -1.61, 0.00, 37.97, 35.83 +CTUN, 742, 0.21, 0.46, 0.000000, 0, 0, 9, 743, 0 +ATT, 0.00, -0.13, -2.05, 0.18, 0.00, 36.93, 35.83 +DU32, 7, 166140 +CURR, 743, 351610, 1041, 2014, 5028, 263.169430 +CTUN, 743, 0.21, 0.65, 0.000000, 0, 0, 10, 743, 0 +ATT, 0.00, 0.84, 0.00, 1.07, 0.00, 35.96, 35.83 +CTUN, 743, 0.24, 0.56, 0.000000, 0, 0, 12, 743, 0 +ATT, 0.00, 0.76, 0.00, 1.78, 0.00, 35.15, 35.83 +CTUN, 743, 0.24, 0.59, 0.000000, 0, 0, 14, 743, 0 +ATT, 0.00, 0.39, 0.00, 2.62, 0.00, 34.47, 35.83 +CTUN, 743, 0.26, 0.65, 0.000000, 0, 0, 12, 743, 0 +ATT, 0.00, 0.60, 0.00, 2.20, 0.00, 34.13, 35.83 +CTUN, 743, 0.26, 0.61, 0.000000, 0, 0, 12, 742, 0 +ATT, 0.00, 0.45, -2.52, 1.29, 0.00, 33.95, 35.83 +CTUN, 743, 0.28, 0.54, 0.000000, 0, 0, 11, 743, 0 +ATT, -0.18, 0.10, -2.70, 0.30, 0.00, 33.92, 35.83 +CTUN, 743, 0.28, 0.56, 0.000000, 0, 0, 10, 743, 0 +ATT, -0.66, -0.34, -2.61, -0.38, 0.00, 34.07, 35.83 +CTUN, 743, 0.30, 0.65, 0.000000, 0, 0, 7, 742, 0 +ATT, -0.56, -0.51, -2.70, -0.48, 0.00, 34.21, 35.83 +CTUN, 742, 0.30, 0.61, 0.000000, 0, 0, 4, 742, 0 +ATT, -0.75, -0.36, -2.70, -0.43, 0.00, 34.35, 35.83 +CTUN, 743, 0.32, 0.64, 0.000000, 0, 0, 2, 743, 0 +ATT, -0.94, 0.19, -2.70, 0.20, 0.00, 34.36, 35.83 +DU32, 7, 166140 +CURR, 742, 359035, 1037, 2016, 5051, 268.811770 +CTUN, 743, 0.32, 0.75, 0.000000, 0, 0, -2, 743, 0 +ATT, -1.23, -0.15, -2.89, 0.58, 0.00, 34.45, 35.83 +CTUN, 742, 0.33, 0.81, 0.000000, 0, 0, -6, 743, 0 +ATT, -2.36, -0.69, -2.33, -0.06, 0.00, 34.84, 35.83 +CTUN, 742, 0.32, 0.71, 0.000000, 0, 0, -6, 742, 0 +ATT, -2.65, -0.59, -4.38, -0.99, 0.00, 35.45, 35.83 +CTUN, 742, 0.32, 0.59, 0.000000, 0, 0, -6, 742, 0 +ATT, -3.03, -1.52, -4.76, -1.97, 0.00, 36.19, 35.83 +CTUN, 742, 0.32, 0.73, 0.000000, 0, 0, -7, 741, 0 +ATT, -3.88, -2.44, -3.82, -2.99, 0.00, 36.84, 35.83 +CTUN, 741, 0.32, 0.84, 0.000000, 0, 1, -10, 743, 0 +ATT, -4.16, -3.09, -4.20, -3.47, 0.00, 37.19, 35.83 +CTUN, 742, 0.31, 0.73, 0.000000, 0, 2, -8, 744, 0 +ATT, -4.45, -4.32, -4.38, -3.29, 0.00, 37.49, 35.83 +CTUN, 742, 0.31, 0.45, 0.000000, 0, 2, -8, 744, 0 +ATT, -3.78, -4.83, -3.73, -3.45, 0.00, 37.93, 35.83 +CTUN, 741, 0.29, 0.53, 0.000000, 0, 3, -5, 745, 0 +ATT, -0.85, -3.86, -2.61, -3.09, 0.00, 38.31, 35.83 +CTUN, 743, 0.29, 0.62, 0.000000, 0, 1, -5, 744, 0 +ATT, 0.00, -2.70, -2.89, -2.22, 0.00, 38.69, 35.83 +DU32, 7, 166140 +CURR, 743, 366458, 1038, 2048, 5028, 274.440160 +CTUN, 743, 0.27, 0.65, 0.000000, 0, 0, -2, 743, 0 +ATT, 0.00, -1.92, -2.61, -1.50, 0.00, 39.11, 35.83 +CTUN, 742, 0.27, 0.62, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -1.11, -2.70, -1.23, 0.00, 39.44, 35.83 +CTUN, 743, 0.26, 0.72, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -0.33, -2.80, -1.17, 0.00, 39.75, 35.83 +CTUN, 743, 0.26, 0.40, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -0.43, -2.61, -0.69, 0.00, 40.00, 35.83 +CTUN, 743, 0.26, 0.64, 0.000000, 0, 0, 1, 743, 0 +ATT, 0.00, -1.02, -2.70, -0.02, 0.00, 40.17, 35.83 +CTUN, 743, 0.26, 0.47, 0.000000, 0, 0, 1, 743, 0 +ATT, 0.00, -0.94, -2.70, 0.51, 0.00, 40.11, 35.83 +CTUN, 743, 0.26, 0.74, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -0.49, -2.70, 0.40, 0.00, 39.90, 35.83 +CTUN, 743, 0.27, 0.45, 0.000000, 0, 0, 0, 742, 0 +ATT, 0.00, -0.71, -2.61, -0.25, 0.00, 39.60, 35.83 +CTUN, 743, 0.27, 0.58, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -0.28, -2.70, -0.81, 0.00, 39.17, 35.83 +CTUN, 743, 0.27, 0.54, 0.000000, 0, 0, 0, 742, 0 +ATT, 0.00, -0.21, -2.70, -0.84, 0.00, 38.52, 35.83 +DU32, 7, 166140 +CURR, 742, 373887, 1041, 2050, 5051, 280.111720 +CTUN, 742, 0.27, 0.60, 0.000000, 0, 0, 2, 743, 0 +ATT, 0.00, -0.99, -2.61, -0.56, 0.00, 37.69, 35.83 +CTUN, 743, 0.28, 0.47, 0.000000, 0, 0, 1, 742, 0 +ATT, 0.00, -1.60, -2.70, -0.44, 0.00, 36.88, 35.83 +CTUN, 743, 0.28, 0.60, 0.000000, 0, 0, 1, 743, 0 +ATT, 0.09, -1.06, -2.61, -0.25, 0.00, 35.99, 35.83 +CTUN, 743, 0.28, 0.46, 0.000000, 0, 0, 1, 743, 0 +ATT, 0.46, -0.32, -2.70, 0.08, 0.00, 34.87, 35.83 +CTUN, 744, 0.28, 0.53, 0.000000, 0, 0, 0, 744, 0 +ATT, 0.46, 0.07, -2.70, -0.23, 0.00, 33.60, 35.83 +CTUN, 743, 0.28, 0.66, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.84, 0.30, -2.70, -0.80, 0.00, 32.29, 35.83 +CTUN, 742, 0.28, 0.48, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.93, 1.26, -3.08, -0.19, 0.00, 31.07, 35.83 +CTUN, 743, 0.29, 0.55, 0.000000, 0, 0, 1, 742, 0 +PM, 0, 0, 0, 0, 1000, 10484, 0, 0 +ATT, 1.03, 2.00, -3.45, 0.27, 0.00, 30.13, 35.83 +CTUN, 744, 0.28, 0.51, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.84, 2.57, -4.38, 0.01, 0.00, 29.45, 35.83 +CTUN, 742, 0.29, 0.53, 0.000000, 0, 0, 0, 742, 0 +ATT, 0.84, 2.34, -4.29, -1.14, 0.00, 29.04, 35.83 +DU32, 7, 166140 +CURR, 741, 381316, 1039, 2060, 5051, 285.776730 +CTUN, 743, 0.28, 0.60, 0.000000, 0, 0, 1, 742, 0 +ATT, 0.84, 1.64, -4.48, -2.11, 0.00, 28.93, 35.83 +CTUN, 742, 0.28, 0.55, 0.000000, 0, 0, 2, 743, 0 +ATT, 0.56, 1.03, -4.57, -2.73, 0.00, 29.18, 35.83 +CTUN, 742, 0.28, 0.50, 0.000000, 0, 0, 4, 741, 0 +ATT, 0.46, 0.92, -4.38, -2.65, 0.00, 29.80, 35.83 +CTUN, 742, 0.29, 0.57, 0.000000, 0, 0, 1, 742, 0 +ATT, 0.37, 0.75, -4.38, -2.60, 0.00, 30.60, 35.83 +CTUN, 741, 0.29, 0.63, 0.000000, 0, 0, 0, 742, 0 +ATT, 0.46, 0.17, -4.38, -2.41, 0.00, 31.55, 35.83 +CTUN, 742, 0.30, 0.53, 0.000000, 0, 0, -1, 741, 0 +ATT, 0.46, -0.61, -4.38, -1.91, 0.00, 32.58, 35.83 +CTUN, 742, 0.29, 0.60, 0.000000, 0, 0, -3, 741, 0 +ATT, 0.46, -0.94, -4.38, -1.23, 0.00, 33.76, 35.83 +CTUN, 742, 0.29, 0.50, 0.000000, 0, 0, -9, 743, 0 +ATT, 0.46, -1.41, -4.38, -0.79, 0.00, 35.05, 35.83 +CTUN, 743, 0.29, 0.56, 0.000000, 0, 0, -8, 743, 0 +ATT, 0.46, -1.60, -4.38, -1.11, 0.00, 36.46, 35.83 +CTUN, 743, 0.29, 0.61, 0.000000, 0, 0, -8, 743, 0 +ATT, 0.46, -1.69, -4.38, -1.78, 0.00, 37.86, 35.83 +DU32, 7, 166140 +CURR, 742, 388741, 1019, 2014, 5028, 291.425510 +CTUN, 742, 0.28, 0.57, 0.000000, 0, 0, -8, 742, 0 +ATT, 0.46, -1.17, -4.38, -1.80, 0.00, 39.20, 35.83 +CTUN, 743, 0.28, 0.56, 0.000000, 0, 0, -6, 742, 0 +ATT, 0.46, -0.82, -4.29, -2.09, 0.00, 40.59, 35.83 +CTUN, 743, 0.26, 0.45, 0.000000, 0, 0, -9, 742, 0 +ATT, 0.46, -0.15, -4.38, -2.20, 0.00, 41.81, 35.83 +CTUN, 743, 0.26, 0.56, 0.000000, 0, 0, -4, 742, 0 +ATT, 0.37, 0.90, -4.38, -1.39, 0.00, 42.55, 35.83 +CTUN, 743, 0.24, 0.44, 0.000000, 0, 0, -5, 743, 0 +ATT, 0.65, 0.44, -4.38, -0.99, 0.00, 43.12, 35.83 +CTUN, 743, 0.24, 0.47, 0.000000, 0, 0, -2, 743, 0 +ATT, 0.84, -0.49, -3.82, -0.85, 0.00, 43.50, 35.83 +CTUN, 741, 0.24, 0.51, 0.000000, 0, 0, -2, 743, 0 +ATT, 1.40, -1.19, -3.45, -1.27, 0.00, 43.73, 35.83 +CTUN, 742, 0.24, 0.37, 0.000000, 0, 0, -2, 742, 0 +ATT, 1.59, -1.38, -4.01, -1.74, 0.00, 43.92, 35.83 +CTUN, 741, 0.24, 0.58, 0.000000, 0, 0, -2, 741, 0 +ATT, 1.59, -0.40, -4.38, -1.49, 0.00, 44.13, 35.83 +CTUN, 742, 0.24, 0.46, 0.000000, 0, 0, -4, 741, 0 +ATT, 1.40, -0.11, -4.48, -1.75, 0.00, 44.37, 35.83 +DU32, 7, 166140 +CURR, 741, 396164, 1039, 2042, 5028, 297.111020 +CTUN, 741, 0.23, 0.60, 0.000000, 0, 0, -4, 741, 0 +ATT, 1.40, -0.15, -4.85, -2.08, 0.00, 44.51, 35.83 +CTUN, 742, 0.23, 0.49, 0.000000, 0, 0, -2, 741, 0 +ATT, 1.40, -0.23, -4.85, -1.99, 0.00, 44.51, 35.83 +CTUN, 742, 0.23, 0.43, 0.000000, 0, 0, -2, 743, 0 +ATT, 2.25, -0.76, -4.85, -2.24, 0.00, 44.40, 35.83 +CTUN, 742, 0.23, 0.51, 0.000000, 0, 0, -1, 742, 0 +ATT, 2.62, -0.11, -4.85, -2.46, 0.00, 44.08, 35.83 +CTUN, 741, 0.22, 0.49, 0.000000, 0, 0, 0, 741, 0 +ATT, 4.50, 0.28, -4.76, -3.02, 0.00, 43.71, 35.83 +CTUN, 742, 0.23, 0.43, 0.000000, 0, 0, 0, 741, 0 +ATT, 6.37, 1.26, -4.76, -3.29, 0.00, 43.33, 35.83 +CTUN, 741, 0.22, 0.41, 0.000000, 0, 1, 0, 742, 0 +ATT, 7.68, 3.02, -4.85, -3.15, 0.00, 42.97, 35.83 +CTUN, 742, 0.23, 0.47, 0.000000, 0, 1, 0, 742, 0 +ATT, 9.18, 4.61, -4.10, -1.98, 0.00, 42.88, 35.83 +CTUN, 741, 0.22, 0.57, 0.000000, 0, 2, 0, 743, 0 +ATT, 9.09, 6.54, -2.14, -1.11, 0.00, 42.93, 35.83 +CTUN, 742, 0.22, 0.67, 0.000000, 0, 5, -2, 747, 0 +ATT, 7.59, 8.02, -2.24, -0.21, 0.00, 42.96, 35.83 +DU32, 7, 166140 +CURR, 742, 403587, 1040, 2048, 5051, 302.763280 +CTUN, 742, 0.22, 0.53, 0.000000, 0, 6, -4, 748, 0 +ATT, 1.96, 7.72, -2.24, 0.06, 0.00, 42.84, 35.83 +CTUN, 742, 0.22, 0.49, 0.000000, 0, 4, -7, 746, 0 +ATT, 0.00, 5.08, -4.76, -0.45, 0.00, 42.61, 35.83 +CTUN, 743, 0.22, 0.67, 0.000000, 0, 0, -7, 743, 0 +ATT, 0.00, 1.14, -6.06, -1.88, 0.00, 42.32, 35.83 +CTUN, 743, 0.22, 0.56, 0.000000, 0, 0, -7, 743, 0 +ATT, 0.00, -0.47, -7.74, -3.50, 0.00, 42.05, 35.83 +CTUN, 743, 0.22, 0.57, 0.000000, 0, 1, -4, 744, 0 +ATT, 0.00, 0.30, -8.21, -4.01, 0.00, 41.68, 35.83 +CTUN, 743, 0.22, 0.46, 0.000000, 0, 1, -3, 744, 0 +ATT, 0.00, 0.29, -8.21, -4.35, 0.00, 41.16, 35.83 +CTUN, 743, 0.22, 0.56, 0.000000, 0, 1, -2, 744, 0 +ATT, 0.00, -0.07, -7.56, -4.79, 0.00, 40.58, 35.83 +CTUN, 742, 0.22, 0.48, 0.000000, 0, 2, 0, 744, 0 +ATT, -0.37, -0.19, -6.62, -4.63, 0.00, 39.99, 35.83 +CTUN, 741, 0.21, 0.50, 0.000000, 0, 1, 1, 744, 0 +ATT, -1.32, -0.43, -5.50, -4.16, 0.00, 39.45, 35.83 +CTUN, 743, 0.21, 0.59, 0.000000, 0, 1, 3, 742, 0 +ATT, -1.98, -0.59, -4.76, -2.88, 0.00, 38.92, 35.83 +DU32, 7, 166140 +CURR, 742, 411032, 1044, 2028, 5051, 308.419560 +CTUN, 743, 0.21, 0.46, 0.000000, 0, 0, 5, 742, 0 +ATT, -2.55, -0.94, -4.57, -1.57, 0.00, 38.45, 35.83 +CTUN, 743, 0.22, 0.65, 0.000000, 0, 0, 8, 743, 0 +ATT, -2.84, -1.52, -4.57, -0.57, 0.00, 37.91, 35.83 +CTUN, 743, 0.22, 0.52, 0.000000, 0, 0, 5, 742, 0 +ATT, -2.84, -1.78, -4.57, -0.74, 0.00, 37.42, 35.83 +CTUN, 742, 0.23, 0.62, 0.000000, 0, 0, 7, 743, 0 +ATT, -2.84, -2.47, -4.57, -1.43, 0.00, 36.87, 35.83 +CTUN, 742, 0.23, 0.48, 0.000000, 0, 0, 9, 742, 0 +ATT, -2.93, -3.10, -4.66, -1.45, 0.00, 36.33, 35.83 +CTUN, 743, 0.24, 0.50, 0.000000, 0, 1, 10, 743, 0 +ATT, -2.08, -2.94, -4.38, -1.07, 0.00, 35.93, 35.83 +CTUN, 743, 0.24, 0.67, 0.000000, 0, 0, 10, 743, 0 +ATT, -0.75, -2.24, -4.38, -0.58, 0.00, 35.65, 35.83 +CTUN, 743, 0.27, 0.73, 0.000000, 0, 0, 10, 743, 0 +ATT, -0.75, -1.07, -4.38, -0.79, 0.00, 35.61, 35.83 +CTUN, 742, 0.27, 0.70, 0.000000, 0, 0, 8, 742, 0 +ATT, 0.00, -0.75, -3.73, -1.75, 0.00, 35.72, 35.83 +CTUN, 742, 0.28, 0.71, 0.000000, 0, 0, 5, 743, 0 +DU32, 7, 166140 +CURR, 743, 418460, 1022, 2010, 5051, 314.043850 +ATT, 0.00, -0.27, -2.80, -2.32, 0.00, 35.88, 35.83 +CTUN, 742, 0.28, 0.78, 0.000000, 0, 0, 7, 743, 0 +ATT, -0.85, 0.71, -2.70, -2.14, 0.00, 36.05, 35.83 +CTUN, 742, 0.30, 0.56, 0.000000, 0, 0, 7, 742, 0 +ATT, -0.66, 1.22, -2.42, -1.83, 0.00, 36.02, 35.83 +CTUN, 742, 0.30, 0.88, 0.000000, 0, 0, 4, 742, 0 +ATT, -1.80, 1.40, -1.77, -1.54, 0.00, 35.87, 35.83 +CTUN, 742, 0.31, 0.63, 0.000000, 0, 0, 1, 742, 0 +ATT, -3.88, 1.42, 0.00, -0.94, 0.00, 35.63, 35.83 +CTUN, 741, 0.31, 0.63, 0.000000, 0, 0, 0, 741, 0 +ATT, -5.68, 0.30, 0.00, -0.03, 0.00, 35.41, 35.83 +CTUN, 741, 0.31, 0.76, 0.000000, 0, 0, -4, 742, 0 +ATT, -6.06, -1.66, 0.00, 0.84, 0.00, 35.25, 35.83 +CTUN, 743, 0.31, 0.67, 0.000000, 0, 0, -7, 743, 0 +ATT, -6.63, -3.96, 0.00, 1.16, 0.00, 35.32, 35.83 +CTUN, 741, 0.31, 0.60, 0.000000, 0, 2, -9, 743, 0 +ATT, -6.63, -4.62, 0.00, 1.26, 0.00, 35.53, 35.83 +CTUN, 743, 0.30, 0.68, 0.000000, 0, 2, -9, 745, 0 +ATT, -6.25, -4.62, -0.56, 1.29, 0.00, 35.84, 35.83 +CTUN, 742, 0.30, 0.85, 0.000000, 0, 2, -10, 744, 0 +DU32, 7, 166140 +CURR, 743, 425886, 1046, 2031, 5028, 319.663240 +ATT, -5.87, -4.33, -1.02, 1.49, 0.00, 36.20, 35.83 +CTUN, 743, 0.29, 0.57, 0.000000, 0, 1, -10, 743, 0 +ATT, -5.68, -4.13, -1.02, 1.23, 0.00, 36.59, 35.83 +CTUN, 743, 0.29, 0.60, 0.000000, 0, 1, -8, 744, 0 +ATT, -5.30, -4.37, -1.12, 0.90, 0.00, 36.85, 35.83 +CTUN, 743, 0.26, 0.45, 0.000000, 0, 1, -10, 743, 0 +ATT, -3.88, -4.34, -2.05, 0.69, 0.00, 36.97, 35.83 +CTUN, 742, 0.26, 0.55, 0.000000, 0, 1, -10, 743, 0 +ATT, -2.27, -3.98, -2.24, -0.03, 0.00, 37.15, 35.83 +CTUN, 742, 0.24, 0.57, 0.000000, 0, 1, -8, 743, 0 +ATT, -0.66, -3.67, -2.52, -0.58, 0.00, 37.38, 35.83 +CTUN, 743, 0.24, 0.54, 0.000000, 0, 1, -6, 744, 0 +ATT, 0.00, -2.35, -4.10, -0.64, 0.00, 37.72, 35.83 +CTUN, 743, 0.22, 0.72, 0.000000, 0, 0, -2, 743, 0 +ATT, 0.00, -0.32, -3.92, -0.92, 0.00, 38.01, 35.83 +CTUN, 742, 0.22, 0.55, 0.000000, 0, 0, 1, 743, 0 +ATT, 0.00, 0.90, -3.26, -1.15, 0.00, 38.20, 35.83 +CTUN, 743, 0.20, 0.61, 0.000000, 0, 0, 7, 743, 0 +ATT, 0.09, 0.81, -2.52, -0.98, 0.00, 38.23, 35.83 +CTUN, 743, 0.20, 0.49, 0.000000, 0, 0, 8, 743, 0 +DU32, 7, 166140 +CURR, 742, 433320, 1046, 1996, 5051, 325.250460 +ATT, 0.00, 0.50, -2.52, -1.18, 0.00, 38.26, 35.83 +CTUN, 742, 0.20, 0.58, 0.000000, 0, 0, 10, 742, 0 +ATT, 0.00, -0.06, -2.52, -1.35, 0.00, 38.37, 35.83 +CTUN, 743, 0.20, 0.47, 0.000000, 0, 0, 11, 744, 0 +ATT, 0.18, -0.13, -2.52, -1.24, 0.00, 38.43, 35.83 +CTUN, 743, 0.20, 0.47, 0.000000, 0, 0, 14, 742, 0 +ATT, 1.12, 0.59, -2.52, -0.94, 0.00, 38.32, 35.83 +CTUN, 742, 0.20, 0.48, 0.000000, 0, 0, 16, 742, 0 +ATT, 1.40, 0.54, -2.42, -0.44, 0.00, 38.04, 35.83 +CTUN, 743, 0.20, 0.64, 0.000000, 0, 0, 19, 743, 0 +ATT, 1.59, 0.49, -2.42, -0.34, 0.00, 37.64, 35.83 +CTUN, 743, 0.20, 0.57, 0.000000, 0, 0, 21, 743, 0 +ATT, 2.43, 1.22, -2.42, -0.39, 0.00, 37.13, 35.83 +CTUN, 742, 0.20, 0.69, 0.000000, 0, 0, 19, 743, 0 +ATT, 2.71, 1.81, -2.52, -0.68, 0.00, 36.66, 35.83 +CTUN, 741, 0.23, 0.57, 0.000000, 0, 0, 21, 741, 0 +ATT, 3.00, 2.69, -2.52, -1.08, 0.00, 36.30, 35.83 +CTUN, 742, 0.23, 0.62, 0.000000, 0, 0, 20, 742, 0 +ATT, 2.62, 3.00, -2.52, -1.38, 0.00, 36.09, 35.83 +CTUN, 743, 0.25, 0.74, 0.000000, 0, 0, 16, 743, 0 +DU32, 7, 166140 +CURR, 741, 440747, 1042, 2029, 5051, 330.838960 +ATT, 1.59, 2.40, -2.42, -1.66, 0.00, 36.13, 35.83 +CTUN, 743, 0.25, 0.61, 0.000000, 0, 0, 14, 743, 0 +ATT, 0.00, 2.06, -2.42, -1.51, 0.00, 36.19, 35.83 +CTUN, 741, 0.27, 0.66, 0.000000, 0, 0, 10, 743, 0 +ATT, 0.00, 1.97, -2.52, -1.11, 0.00, 36.16, 35.83 +CTUN, 742, 0.27, 0.65, 0.000000, 0, 0, 6, 742, 0 +ATT, 0.00, 1.09, -2.52, -1.15, 0.00, 36.13, 35.83 +CTUN, 743, 0.29, 0.74, 0.000000, 0, 0, 4, 743, 0 +ATT, 0.00, 0.62, -2.52, -1.32, 0.00, 36.07, 35.83 +CTUN, 743, 0.28, 0.63, 0.000000, 0, 0, 2, 742, 0 +ATT, 0.00, -0.04, -2.42, -1.22, 0.00, 35.97, 35.83 +CTUN, 743, 0.28, 0.68, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -0.53, -2.52, -0.73, 0.00, 35.90, 35.83 +CTUN, 742, 0.28, 0.53, 0.000000, 0, 0, 0, 742, 0 +ATT, 0.00, -0.59, -2.42, -0.40, 0.00, 35.77, 35.83 +CTUN, 743, 0.28, 0.74, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, -0.96, -2.42, -0.43, 0.00, 35.72, 35.83 +CTUN, 742, 0.28, 0.68, 0.000000, 0, 0, -2, 743, 0 +ATT, 0.00, -0.89, -2.52, -0.59, 0.00, 35.71, 35.83 +CTUN, 742, 0.28, 0.55, 0.000000, 0, 0, -2, 743, 0 +DU32, 7, 166140 +CURR, 743, 448172, 1037, 1999, 5051, 336.392610 +ATT, 0.00, -0.70, -2.42, -0.32, 0.00, 35.67, 35.83 +CTUN, 743, 0.26, 0.65, 0.000000, 0, 0, -4, 743, 0 +ATT, 0.00, -1.37, -2.52, -0.14, 0.00, 35.51, 35.83 +CTUN, 743, 0.26, 0.60, 0.000000, 0, 0, -7, 742, 0 +ATT, 0.00, -1.74, -2.52, -0.39, 0.00, 35.42, 35.83 +CTUN, 743, 0.25, 0.63, 0.000000, 0, 0, -6, 743, 0 +ATT, 0.00, -1.66, -2.52, -0.70, 0.00, 35.32, 35.83 +CTUN, 743, 0.25, 0.62, 0.000000, 0, 0, -6, 743, 0 +ATT, 0.00, -1.71, -2.52, -0.77, 0.00, 35.22, 35.83 +CTUN, 742, 0.23, 0.46, 0.000000, 0, 0, -3, 742, 0 +ATT, 0.00, -1.67, -2.52, -0.43, 0.00, 35.00, 35.83 +CTUN, 742, 0.23, 0.56, 0.000000, 0, 0, -4, 742, 0 +ATT, 0.00, -1.86, -2.42, -0.38, 0.00, 34.69, 35.83 +CTUN, 743, 0.22, 0.69, 0.000000, 0, 0, -2, 743, 0 +ATT, 0.00, -1.83, -2.42, -0.69, 0.00, 34.42, 35.83 +CTUN, 743, 0.22, 0.52, 0.000000, 0, 0, 2, 743, 0 +PM, 0, 0, 0, 0, 1000, 10484, 0, 0 +ATT, 0.00, -1.57, -2.52, -1.09, 0.00, 34.18, 35.83 +CTUN, 742, 0.20, 0.73, 0.000000, 0, 0, 3, 742, 0 +ATT, 0.00, -0.88, -2.52, -1.19, 0.00, 33.99, 35.83 +CTUN, 743, 0.20, 0.52, 0.000000, 0, 0, 7, 742, 0 +DU32, 7, 166140 +CURR, 743, 455601, 1032, 2004, 5051, 341.938870 +ATT, 0.00, 0.01, -2.52, -0.81, 0.00, 33.89, 35.83 +CTUN, 742, 0.20, 0.65, 0.000000, 0, 0, 13, 743, 0 +ATT, 0.00, 0.20, -2.52, 0.01, 0.00, 33.97, 35.83 +CTUN, 742, 0.20, 0.58, 0.000000, 0, 0, 13, 742, 0 +ATT, 0.00, 0.14, -2.52, 0.39, 0.00, 34.06, 35.83 +CTUN, 743, 0.20, 0.60, 0.000000, 0, 0, 12, 743, 0 +ATT, 0.00, 0.73, -2.52, 0.58, 0.00, 34.10, 35.83 +CTUN, 743, 0.20, 0.64, 0.000000, 0, 0, 16, 744, 0 +ATT, 0.00, 0.95, -2.52, 0.34, 0.00, 34.31, 35.83 +CTUN, 743, 0.20, 0.71, 0.000000, 0, 0, 19, 743, 0 +ATT, 0.00, 0.55, -2.52, -0.83, 0.00, 34.42, 35.83 +CTUN, 743, 0.22, 0.62, 0.000000, 0, 0, 17, 743, 0 +ATT, 0.00, 0.67, -2.42, -2.16, 0.00, 34.17, 35.83 +CTUN, 743, 0.22, 0.63, 0.000000, 0, 0, 16, 743, 0 +ATT, 0.00, 0.51, -2.42, -2.06, 0.00, 33.78, 35.83 +CTUN, 743, 0.24, 0.64, 0.000000, 0, 0, 17, 742, 0 +ATT, 0.00, -0.35, -2.52, -1.04, 0.00, 33.26, 35.83 +CTUN, 744, 0.24, 0.61, 0.000000, 0, 0, 13, 743, 0 +ATT, 0.00, 0.47, -2.42, 0.03, 0.00, 32.51, 35.83 +CTUN, 743, 0.27, 0.70, 0.000000, 0, 0, 10, 743, 0 +DU32, 7, 166140 +CURR, 743, 463030, 1023, 2000, 5051, 347.506040 +ATT, 0.00, 2.40, -2.42, 0.69, 0.00, 31.97, 35.83 +CTUN, 743, 0.27, 0.70, 0.000000, 0, 0, 5, 743, 0 +ATT, 0.00, 2.36, -4.01, 1.23, 0.00, 31.63, 35.83 +CTUN, 742, 0.28, 0.66, 0.000000, 0, 0, 2, 742, 0 +ATT, 0.00, 1.76, -6.34, 1.06, 0.00, 31.52, 35.83 +CTUN, 743, 0.28, 0.76, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, 1.20, -8.02, -0.41, 0.00, 31.68, 35.83 +CTUN, 743, 0.28, 0.72, 0.000000, 0, 0, -5, 743, 0 +ATT, 0.00, 0.84, -10.82, -3.05, 0.00, 31.85, 35.83 +CTUN, 743, 0.27, 0.73, 0.000000, 0, 1, -7, 744, 0 +ATT, 0.00, 0.65, -10.92, -5.85, 0.00, 32.12, 35.83 +CTUN, 743, 0.27, 0.70, 0.000000, 0, 3, -8, 745, 0 +ATT, 0.00, 0.82, -10.92, -7.78, 0.00, 32.38, 35.83 +CTUN, 743, 0.26, 0.64, 0.000000, 0, 6, -12, 749, 0 +ATT, 0.00, 0.42, -10.92, -8.08, 0.00, 32.76, 35.83 +CTUN, 743, 0.26, 0.57, 0.000000, 0, 5, -10, 748, 0 +ATT, 0.00, 0.25, -10.64, -6.52, 0.00, 33.19, 35.83 +CTUN, 743, 0.24, 0.65, 0.000000, 0, 3, -12, 746, 0 +ATT, 0.00, 0.49, -8.30, -4.93, 0.00, 33.64, 35.83 +CTUN, 743, 0.24, 0.45, 0.000000, 0, 2, -9, 744, 0 +DU32, 7, 166140 +CURR, 743, 470477, 1037, 2004, 5028, 353.057680 +ATT, 0.00, -0.35, -7.84, -3.71, 0.00, 34.08, 35.83 +CTUN, 743, 0.21, 0.29, 0.000000, 0, 1, -8, 744, 0 +ATT, 0.00, -0.65, -8.02, -2.69, 0.00, 34.62, 35.83 +CTUN, 743, 0.21, 0.50, 0.000000, 0, 0, -6, 743, 0 +ATT, 0.00, 0.30, -8.12, -2.10, 0.00, 35.21, 35.83 +CTUN, 742, 0.20, 0.60, 0.000000, 0, 0, -4, 742, 0 +ATT, 0.00, 0.56, -8.12, -2.70, 0.00, 35.73, 35.83 +CTUN, 743, 0.20, 0.58, 0.000000, 0, 0, -2, 742, 0 +ATT, 0.00, -0.40, -7.00, -4.03, 0.00, 36.26, 35.83 +CTUN, 742, 0.20, 0.51, 0.000000, 0, 1, 1, 743, 0 +ATT, 0.00, -1.38, -6.16, -4.70, 0.00, 36.75, 35.83 +CTUN, 743, 0.20, 0.65, 0.000000, 0, 2, 5, 745, 0 +ATT, 0.46, -1.50, -4.66, -3.93, 0.00, 37.07, 35.83 +CTUN, 743, 0.20, 0.46, 0.000000, 0, 1, 10, 744, 0 +ATT, 0.84, -1.05, -2.89, -1.73, 0.00, 37.35, 35.83 +CTUN, 743, 0.20, 0.23, 0.000000, 0, 0, 14, 743, 0 +ATT, 3.46, -0.68, -2.24, 0.80, 0.00, 37.45, 35.83 +CTUN, 742, 0.20, 0.69, 0.000000, 0, 0, 15, 742, 0 +ATT, 6.09, 0.76, -2.24, 2.09, 0.00, 37.50, 35.83 +CTUN, 743, 0.20, 0.68, 0.000000, 0, 0, 16, 743, 0 +DU32, 7, 166140 +CURR, 743, 477908, 1049, 2003, 5028, 358.618740 +ATT, 7.03, 2.86, -2.24, 1.69, 0.00, 37.42, 35.83 +CTUN, 742, 0.20, 0.61, 0.000000, 0, 1, 12, 743, 0 +ATT, 7.31, 5.20, -2.24, 1.26, 0.00, 37.41, 35.83 +CTUN, 742, 0.20, 0.63, 0.000000, 0, 3, 12, 745, 0 +ATT, 7.87, 6.98, -2.24, 1.43, 0.00, 37.65, 35.83 +CTUN, 744, 0.20, 0.61, 0.000000, 0, 5, 10, 748, 0 +ATT, 7.59, 8.03, -2.24, 1.36, 0.00, 38.07, 35.83 +CTUN, 742, 0.22, 0.66, 0.000000, 0, 6, 6, 748, 0 +ATT, 6.28, 7.70, -2.24, 1.36, 0.00, 38.51, 35.83 +CTUN, 743, 0.22, 0.62, 0.000000, 0, 5, 3, 750, 0 +ATT, 0.84, 6.81, -3.54, 1.23, 0.00, 38.83, 35.83 +CTUN, 743, 0.23, 0.66, 0.000000, 0, 4, 0, 748, 0 +ATT, 0.00, 4.64, -4.57, 0.42, 0.00, 38.89, 35.83 +CTUN, 743, 0.23, 0.65, 0.000000, 0, 1, -2, 743, 0 +ATT, 0.00, 1.15, -6.34, -1.43, 0.00, 38.85, 35.83 +CTUN, 742, 0.23, 0.50, 0.000000, 0, 0, -2, 742, 0 +ATT, 0.00, -1.04, -7.00, -2.87, 0.00, 38.70, 35.83 +CTUN, 743, 0.23, 0.59, 0.000000, 0, 1, -2, 744, 0 +ATT, 0.00, -1.49, -7.46, -3.31, 0.00, 38.47, 35.83 +CTUN, 743, 0.24, 0.70, 0.000000, 0, 1, -4, 743, 0 +DU32, 7, 166140 +CURR, 742, 485362, 1036, 1998, 5028, 364.193660 +ATT, 0.00, -1.28, -6.81, -3.20, 0.00, 38.06, 35.83 +CTUN, 743, 0.23, 0.65, 0.000000, 0, 0, -2, 743, 0 +ATT, 0.00, -0.39, -6.81, -2.47, 0.00, 37.54, 35.83 +CTUN, 743, 0.23, 0.52, 0.000000, 0, 0, -3, 743, 0 +ATT, 0.00, 0.07, -6.53, -1.75, 0.00, 37.14, 35.83 +CTUN, 743, 0.23, 0.59, 0.000000, 0, 0, -1, 743, 0 +ATT, 0.00, 0.40, -6.06, -1.31, 0.00, 36.84, 35.83 +CTUN, 743, 0.23, 0.65, 0.000000, 0, 0, 0, 743, 0 +ATT, -0.75, -0.06, -5.88, -1.38, 0.00, 36.58, 35.83 +CTUN, 743, 0.22, 0.47, 0.000000, 0, 0, 1, 743, 0 +ATT, -3.31, -0.30, -5.60, -0.96, 0.00, 36.37, 35.83 +CTUN, 743, 0.22, 0.52, 0.000000, 0, 0, 3, 743, 0 +ATT, -3.78, -0.66, -5.50, -0.42, 0.00, 36.12, 35.83 +CTUN, 743, 0.21, 0.42, 0.000000, 0, 0, 3, 742, 0 +ATT, -3.88, -1.80, -5.60, -0.87, 0.00, 35.83, 35.83 +CTUN, 742, 0.22, 0.63, 0.000000, 0, 0, 4, 742, 0 +ATT, -4.07, -2.73, -4.01, -2.03, 0.00, 35.50, 35.83 +CTUN, 743, 0.21, 0.63, 0.000000, 0, 1, 4, 744, 0 +ATT, -4.83, -2.96, -4.76, -2.16, 0.00, 35.03, 35.83 +CTUN, 742, 0.21, 0.60, 0.000000, 0, 1, 6, 744, 0 +DU32, 7, 166140 +CURR, 743, 492792, 1031, 2009, 5028, 369.755000 +ATT, -4.83, -3.24, -4.76, -1.64, 0.00, 34.46, 35.83 +CTUN, 743, 0.21, 0.55, 0.000000, 0, 1, 7, 744, 0 +ATT, -0.28, -3.91, -4.85, -1.37, 0.00, 34.00, 35.83 +CTUN, 742, 0.22, 0.69, 0.000000, 0, 1, 9, 744, 0 +ATT, 0.00, -3.09, -2.98, -1.60, 0.00, 33.57, 35.83 +CTUN, 742, 0.22, 0.49, 0.000000, 0, 0, 9, 742, 0 +ATT, 0.00, -0.84, -2.80, -1.78, 0.00, 33.13, 35.83 +CTUN, 743, 0.22, 0.72, 0.000000, 0, 0, 10, 743, 0 +ATT, 0.00, 1.25, -2.33, -1.51, 0.00, 32.64, 35.83 +CTUN, 743, 0.22, 0.72, 0.000000, 0, 0, 12, 743, 0 +ATT, 0.00, 1.65, -2.42, -0.93, 0.00, 32.26, 35.83 +CTUN, 743, 0.22, 0.66, 0.000000, 0, 0, 12, 743, 0 +ATT, 0.00, 0.52, -2.42, -0.45, 0.00, 31.91, 35.83 +CTUN, 743, 0.22, 0.69, 0.000000, 0, 0, 13, 743, 0 +ATT, 0.00, -0.04, -2.52, -0.28, 0.00, 31.59, 35.83 +CTUN, 743, 0.24, 0.58, 0.000000, 0, 0, 14, 742, 0 +ATT, 0.00, 0.14, -2.52, -0.39, 0.00, 31.51, 35.83 +CTUN, 743, 0.24, 0.70, 0.000000, 0, 0, 11, 743, 0 +ATT, 0.00, 0.68, -2.52, -0.47, 0.00, 31.78, 35.83 +CTUN, 742, 0.26, 0.62, 0.000000, 0, 0, 9, 743, 0 +DU32, 7, 166140 +CURR, 744, 500222, 1041, 2010, 5051, 375.335140 +ATT, 0.00, 0.95, -2.52, -0.59, 0.00, 32.16, 35.83 +CTUN, 743, 0.26, 0.63, 0.000000, 0, 0, 8, 743, 0 +ATT, 0.00, 0.01, -2.42, -0.70, 0.00, 32.62, 35.83 +CTUN, 742, 0.27, 0.83, 0.000000, 0, 0, 4, 743, 0 +ATT, 0.00, -0.24, -2.52, -0.74, 0.00, 33.04, 35.83 +CTUN, 743, 0.27, 0.84, 0.000000, 0, 0, 2, 742, 0 +ATT, 0.00, 0.40, -2.52, -0.20, 0.00, 33.58, 35.83 +CTUN, 743, 0.27, 0.79, 0.000000, 0, 0, 3, 743, 0 +ATT, 0.00, 0.77, -2.42, 0.20, 0.00, 34.13, 35.83 +CTUN, 743, 0.27, 0.81, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, 1.22, -2.52, 0.50, 0.00, 34.66, 35.83 +CTUN, 743, 0.27, 0.62, 0.000000, 0, 0, -1, 743, 0 +ATT, 0.00, 1.17, -2.42, 0.53, 0.00, 35.02, 35.83 +CTUN, 742, 0.26, 0.66, 0.000000, 0, 0, -1, 742, 0 +ATT, 0.00, 0.84, -2.52, 0.40, 0.00, 35.18, 35.83 +CTUN, 743, 0.26, 0.68, 0.000000, 0, 0, 0, 743, 0 +ATT, 0.00, 1.08, -2.52, 0.26, 0.00, 35.31, 35.83 +CTUN, 743, 0.25, 0.73, 0.000000, 0, 0, 3, 743, 0 +MODE, ALT_HOLD, 742 +ATT, 0.00, 0.77, -2.52, 0.35, 0.00, 35.48, 35.83 +CTUN, 743, 0.25, 0.70, 0.775600, 0, 0, 1, 743, 89 +ATT, 0.00, 0.06, -2.42, 0.40, 0.00, 35.67, 35.83 +DU32, 7, 166132 +CURR, 743, 507650, 1036, 2029, 5028, 380.935730 +CTUN, 743, 0.23, 0.79, 0.874400, 0, 0, 4, 764, 89 +ATT, 0.00, -0.15, -2.52, 0.36, 0.00, 35.95, 35.83 +CTUN, 743, 0.24, 0.73, 0.965400, 0, 0, 7, 807, 89 +ATT, 0.00, -0.31, -2.52, 0.24, 0.00, 36.33, 35.83 +CTUN, 743, 0.24, 0.66, 1.064200, 0, 0, 16, 816, 89 +ATT, 0.00, -0.81, -2.42, 0.35, 0.00, 36.73, 35.83 +CTUN, 743, 0.24, 0.64, 1.145400, 0, 0, 24, 826, 89 +ATT, 0.00, -0.67, -2.42, 0.55, 0.00, 37.15, 35.83 +CTUN, 742, 0.24, 0.64, 1.264400, 0, 0, 37, 830, 89 +ATT, 0.00, -0.31, -2.52, 0.81, 0.00, 37.37, 35.83 +CTUN, 743, 0.27, 0.65, 1.365000, 0, 0, 45, 835, 89 +ATT, 0.00, -0.22, -2.52, 1.04, 0.00, 37.36, 35.83 +CTUN, 743, 0.27, 0.79, 1.463800, 0, 0, 52, 841, 89 +ATT, 0.00, 0.11, -2.52, 0.92, 0.00, 37.12, 35.83 +CTUN, 743, 0.33, 0.80, 1.584800, 0, 0, 59, 839, 88 +ATT, 0.00, 0.57, -2.52, 0.79, 0.00, 36.54, 35.83 +CTUN, 743, 0.33, 0.97, 1.673800, 0, 0, 66, 820, 89 +ATT, 0.00, 0.41, -2.52, 1.04, 0.00, 35.52, 35.83 +CTUN, 743, 0.42, 0.93, 1.804800, 0, 0, 74, 838, 88 +MODE, STABILIZE, 742 +ATT, 0.00, 0.24, -2.52, 0.86, 0.00, 34.22, 35.83 +DU32, 7, 166140 +CURR, 744, 515857, 1018, 2397, 5028, 387.614870 +CTUN, 743, 0.42, 1.08, 0.000000, 0, 0, 77, 743, 0 +ATT, 0.00, 0.31, -2.52, 0.11, 0.00, 32.88, 35.83 +CTUN, 743, 0.55, 1.22, 0.000000, 0, 0, 72, 743, 0 +ATT, 0.00, 0.35, -2.42, -0.97, 0.00, 31.49, 35.83 +CTUN, 744, 0.55, 1.19, 0.000000, 0, 0, 67, 744, 0 +ATT, 0.00, 0.72, -3.73, -1.54, 0.00, 30.13, 35.83 +CTUN, 743, 0.68, 1.22, 0.000000, 0, 0, 60, 743, 0 +ATT, 0.00, 1.53, -6.34, -1.77, 0.00, 28.90, 35.83 +CTUN, 743, 0.68, 1.25, 0.000000, 0, 0, 52, 743, 0 +ATT, 0.00, 1.50, -8.40, -2.65, 0.00, 27.97, 35.83 +CTUN, 742, 0.80, 1.26, 0.000000, 0, 1, 48, 743, 0 +ATT, 0.00, 1.19, -11.01, -4.79, 0.00, 27.41, 35.83 +CTUN, 743, 0.80, 1.26, 0.000000, 0, 3, 40, 745, 0 +ATT, 0.00, 1.18, -12.23, -7.72, 0.00, 27.10, 35.83 +CTUN, 743, 0.90, 1.35, 0.000000, 0, 7, 34, 750, 0 +ATT, 0.00, 1.43, -12.60, -9.93, 0.00, 26.94, 35.83 +CTUN, 743, 0.90, 1.40, 0.000000, 0, 10, 28, 753, 0 +ATT, 0.00, 1.99, -12.60, -10.90, 0.00, 27.06, 35.83 +CTUN, 744, 0.97, 1.37, 0.000000, 0, 11, 24, 755, 0 +ATT, 1.03, 2.45, -10.64, -10.94, 0.00, 27.51, 35.83 +DU32, 7, 166140 +CURR, 743, 523318, 1028, 2078, 5051, 393.222560 +CTUN, 742, 0.97, 1.55, 0.000000, 0, 11, 20, 754, 0 +ATT, 2.81, 2.17, -4.01, -10.22, 0.00, 28.13, 35.83 +CTUN, 743, 1.02, 1.55, 0.000000, 0, 9, 17, 752, 0 +ATT, 2.71, 3.04, -1.58, -7.71, 0.00, 28.92, 35.83 +CTUN, 743, 1.02, 1.52, 0.000000, 0, 4, 15, 747, 0 +ATT, 0.46, 4.00, -0.37, -3.41, 0.00, 30.00, 35.83 +CTUN, 744, 1.06, 1.58, 0.000000, 0, 2, 8, 746, 0 +ATT, 0.00, 2.70, 0.00, 0.50, 0.00, 31.21, 35.83 +CTUN, 744, 1.06, 1.57, 0.000000, 0, 0, 6, 744, 0 +ATT, 0.09, 0.85, 0.00, 2.67, 0.00, 32.42, 35.83 +CTUN, 744, 1.08, 1.67, 0.000000, 0, 0, 3, 744, 0 +ATT, 0.00, 0.80, 0.00, 3.78, 0.00, 33.67, 35.83 +CTUN, 743, 1.08, 1.76, 0.000000, 0, 1, -2, 744, 0 +ATT, 0.28, 0.87, 0.00, 3.83, 0.00, 34.97, 35.83 +CTUN, 744, 1.08, 1.65, 0.000000, 0, 1, -7, 745, 0 +PM, 0, 0, 0, 0, 1000, 10476, 0, 0 +ATT, 1.59, 0.51, 0.00, 3.24, 0.00, 36.18, 35.83 +CTUN, 743, 1.08, 1.57, 0.000000, 0, 0, -11, 743, 0 +ATT, 0.84, 1.04, 0.00, 3.16, 0.00, 37.08, 35.83 +CTUN, 745, 1.08, 1.50, 0.000000, 0, 1, -17, 745, 0 +ATT, 0.84, 1.54, 0.00, 3.33, 0.00, 37.82, 35.83 +DU32, 7, 166140 +CURR, 743, 530782, 1031, 1989, 5028, 398.800230 +CTUN, 744, 1.07, 1.73, 0.000000, 0, 1, -22, 745, 0 +ATT, 0.46, 0.51, 0.00, 3.21, 0.00, 38.43, 35.83 +CTUN, 745, 1.07, 1.67, 0.000000, 0, 0, -26, 745, 0 +ATT, 0.65, -0.87, 0.00, 3.04, 0.00, 38.94, 35.83 +CTUN, 744, 1.02, 1.58, 0.000000, 0, 0, -31, 744, 0 +ATT, 0.65, -1.04, 0.00, 2.58, 0.00, 39.41, 35.83 +CTUN, 744, 1.02, 1.48, 0.000000, 0, 0, -32, 744, 0 +ATT, 0.84, -0.99, -0.37, 2.12, 0.00, 39.92, 35.83 +CTUN, 743, 0.96, 1.57, 0.000000, 0, 0, -36, 744, 0 +ATT, 0.46, -0.20, -1.21, 1.70, 0.00, 40.55, 35.83 +CTUN, 744, 0.96, 1.38, 0.000000, 0, 0, -41, 744, 0 +ATT, 0.09, 0.87, -1.30, 1.11, 0.00, 41.11, 35.83 +CTUN, 743, 0.90, 1.37, 0.000000, 0, 0, -44, 743, 0 +ATT, 0.00, 1.35, -2.05, 0.32, 0.00, 41.36, 35.83 +CTUN, 743, 0.90, 1.53, 0.000000, 0, 0, -45, 743, 0 +ATT, 0.00, 0.88, -2.05, -0.24, 0.00, 41.22, 35.83 +CTUN, 744, 0.80, 1.52, 0.000000, 0, 0, -49, 743, 0 +ATT, 0.00, 0.80, -2.52, -0.57, 0.00, 40.78, 35.83 +CTUN, 743, 0.80, 1.31, 0.000000, 0, 0, -50, 743, 0 +ATT, 0.00, 0.83, -6.81, -0.53, 0.00, 39.98, 35.83 +DU32, 7, 166140 +CURR, 742, 538215, 1041, 2013, 5051, 404.352230 +CTUN, 741, 0.70, 1.31, 0.000000, 0, 0, -55, 742, 0 +ATT, 0.00, 0.52, -8.30, -0.99, 0.00, 38.94, 35.83 +CTUN, 743, 0.70, 1.30, 0.000000, 0, 0, -61, 743, 0 +ATT, 0.00, 0.42, -10.82, -2.29, 0.00, 37.92, 35.83 +CTUN, 742, 0.59, 1.22, 0.000000, 0, 0, -66, 742, 0 +ATT, 0.28, 0.58, -11.76, -4.05, 0.00, 37.03, 35.83 +CTUN, 742, 0.59, 1.11, 0.000000, 0, 2, -70, 744, 0 +ATT, 0.46, 0.62, -11.76, -5.21, 0.00, 36.44, 35.83 +CTUN, 741, 0.46, 1.14, 0.000000, 0, 2, -69, 743, 0 +ATT, 1.78, 1.05, -10.92, -4.92, 0.00, 36.09, 35.83 +CTUN, 741, 0.46, 0.93, 0.000000, 0, 2, -70, 745, 0 +ATT, 2.90, 1.49, -9.14, -4.48, 0.00, 35.65, 35.83 +CTUN, 741, 0.32, 0.67, 0.000000, 0, 2, -68, 743, 0 +ATT, 2.81, 1.15, -7.84, -5.19, 0.00, 35.32, 35.83 +CTUN, 741, 0.32, 0.45, 0.000000, 0, 2, -58, 744, 0 +ATT, 2.43, 0.87, -6.62, -4.87, 0.00, 35.24, 35.83 +CTUN, 741, 0.20, -1.47, 0.000000, 0, 1, -43, 742, 0 +ATT, 1.59, 0.45, -6.53, -3.49, 0.00, 35.46, 35.83 +CTUN, 741, 0.27, -3.39, 0.000000, 0, 0, -24, 742, 0 +ATT, 1.40, -0.83, -6.81, 1.20, 0.00, 35.96, 35.83 +DU32, 7, 166140 +CURR, 742, 545643, 1031, 1993, 5051, 409.884770 +CTUN, 742, 0.21, -5.11, 0.000000, 0, 0, 15, 742, 0 +ATT, 0.84, 1.67, -6.25, 2.58, 0.00, 36.24, 35.83 +CTUN, 742, 0.21, -4.21, 0.000000, 0, 0, 27, 743, 0 +ATT, 0.65, 0.76, -5.32, -0.02, 0.00, 36.75, 35.83 +CTUN, 742, 0.21, -2.88, 0.000000, 0, 0, 34, 742, 0 +ATT, 0.37, 0.11, -5.22, -1.34, 0.00, 37.28, 35.83 +CTUN, 743, 0.21, -1.12, 0.000000, 0, 0, 37, 743, 0 +ATT, 0.00, 0.25, -5.88, -1.76, 0.00, 37.53, 35.83 +CTUN, 750, 0.20, -0.11, 0.000000, 0, 0, 38, 750, 0 +ATT, 0.00, 0.37, -4.76, -1.75, 0.00, 37.75, 35.83 +CTUN, 750, 0.21, 0.67, 0.000000, 0, 0, 38, 750, 0 +ATT, 0.00, -0.35, -2.52, -1.64, 0.00, 37.83, 35.83 +CTUN, 750, 0.21, 0.75, 0.000000, 0, 0, 36, 750, 0 +ATT, 0.00, -0.30, -2.52, -1.31, 0.00, 37.66, 35.83 +CTUN, 750, 0.23, 0.80, 0.000000, 0, 0, 33, 750, 0 +ATT, 0.93, 0.07, -2.61, -0.59, 0.00, 37.43, 35.83 +CTUN, 751, 0.23, 0.92, 0.000000, 0, 0, 30, 750, 0 +ATT, 2.81, 0.18, -2.24, -0.07, 0.00, 37.09, 35.83 +CTUN, 751, 0.32, 0.86, 0.000000, 0, 0, 27, 751, 0 +ATT, 3.09, 1.21, -2.24, 0.03, 0.00, 36.63, 35.83 +DU32, 7, 166140 +CURR, 750, 553114, 1036, 2033, 5051, 415.498600 +CTUN, 751, 0.32, 0.98, 0.000000, 0, 0, 22, 751, 0 +ATT, 5.62, 2.42, -2.24, 0.05, 0.00, 36.08, 35.83 +CTUN, 750, 0.40, 0.98, 0.000000, 0, 0, 16, 750, 0 +ATT, 6.93, 3.44, -2.24, 0.27, 0.00, 35.59, 35.83 +CTUN, 750, 0.40, 1.01, 0.000000, 0, 1, 12, 751, 0 +ATT, 6.93, 4.91, -2.14, 0.50, 0.00, 35.11, 35.83 +CTUN, 750, 0.47, 1.07, 0.000000, 0, 2, 12, 752, 0 +ATT, 5.71, 5.79, -2.24, 0.92, 0.00, 34.72, 35.83 +CTUN, 751, 0.47, 1.17, 0.000000, 0, 3, 10, 754, 0 +ATT, 1.03, 5.48, -2.42, 1.27, 0.00, 34.36, 35.83 +CTUN, 750, 0.50, 1.15, 0.000000, 0, 2, 4, 752, 0 +ATT, 0.00, 3.24, -2.24, 1.16, 0.00, 33.97, 35.83 +CTUN, 752, 0.50, 1.12, 0.000000, 0, 0, 2, 752, 0 +ATT, 0.00, -0.04, -3.92, 0.60, 0.00, 33.49, 35.83 +CTUN, 751, 0.52, 1.20, 0.000000, 0, 0, 0, 750, 0 +ATT, 0.00, -1.21, -5.04, 0.06, 0.00, 32.87, 35.83 +CTUN, 750, 0.52, 1.15, 0.000000, 0, 0, -4, 750, 0 +ATT, -0.75, -0.49, -6.90, -0.57, 0.00, 31.95, 35.83 +CTUN, 751, 0.53, 0.89, 0.000000, 0, 0, -6, 751, 0 +ATT, -3.97, -0.23, -7.09, -1.65, 0.00, 30.92, 35.83 +DU32, 7, 166140 +CURR, 750, 560627, 1029, 2038, 5028, 421.153990 +CTUN, 751, 0.52, 1.16, 0.000000, 0, 0, -9, 751, 0 +ATT, -6.06, -1.70, -5.88, -2.74, 0.00, 30.09, 35.83 +CTUN, 751, 0.52, 1.11, 0.000000, 0, 1, -12, 751, 0 +ATT, -5.96, -3.51, -5.88, -3.22, 0.00, 29.35, 35.83 +CTUN, 750, 0.51, 0.96, 0.000000, 0, 2, -14, 752, 0 +ATT, -5.49, -4.79, -5.41, -3.37, 0.00, 28.63, 35.83 +CTUN, 751, 0.51, 1.03, 0.000000, 0, 3, -17, 753, 0 +ATT, -3.50, -5.20, -5.60, -3.29, 0.00, 27.99, 35.83 +CTUN, 750, 0.49, 0.88, 0.000000, 0, 3, -21, 753, 0 +ATT, -0.66, -4.72, -5.69, -3.02, 0.00, 27.42, 35.83 +CTUN, 750, 0.49, 1.01, 0.000000, 0, 2, -22, 752, 0 +ATT, 0.00, -2.60, -6.06, -2.83, 0.00, 27.00, 35.83 +CTUN, 754, 0.44, 0.87, 0.000000, 0, 0, -26, 752, 0 +ATT, 0.00, -0.23, -6.53, -2.68, 0.00, 26.81, 35.83 +CTUN, 769, 0.44, 0.94, 0.000000, 0, 0, -28, 769, 0 +ATT, 0.00, 0.73, -6.53, -2.56, 0.00, 26.92, 35.83 +CTUN, 780, 0.38, 0.91, 0.000000, 0, 0, -25, 780, 0 +ATT, 0.00, 0.88, -6.53, -2.54, 0.19, 27.20, 35.83 +CTUN, 779, 0.38, 0.81, 0.000000, 0, 0, -26, 779, 0 +ATT, 0.00, 1.12, -5.69, -3.00, 1.63, 27.65, 36.17 +DU32, 7, 166140 +CURR, 780, 568214, 1018, 2205, 5051, 426.923520 +CTUN, 783, 0.31, 0.79, 0.000000, 0, 1, -20, 782, 0 +ATT, 0.00, 0.94, -4.85, -2.81, 2.59, 28.49, 37.15 +CTUN, 785, 0.31, 0.80, 0.000000, 0, 0, -13, 785, 0 +ATT, 0.00, 0.34, -3.73, -1.89, 3.36, 29.94, 38.44 +CTUN, 785, 0.26, 0.84, 0.000000, 0, 0, -5, 787, 0 +ATT, 0.00, -0.10, -2.24, -0.56, 3.75, 31.87, 40.02 +CTUN, 784, 0.26, 0.81, 0.000000, 0, 0, 2, 784, 0 +ATT, 0.00, 0.02, -2.24, 1.23, 4.23, 34.33, 41.82 +CTUN, 784, 0.22, 0.75, 0.000000, 0, 0, 8, 784, 0 +ATT, 0.00, -0.06, -2.24, 2.34, 4.23, 37.29, 43.70 +CTUN, 783, 0.22, 0.65, 0.000000, 0, 0, 14, 783, 0 +ATT, 0.00, 0.25, -2.42, 1.83, 4.13, 40.50, 45.49 +CTUN, 782, 0.22, 0.69, 0.000000, 0, 0, 17, 782, 0 +ATT, 0.00, 0.09, -3.26, 1.02, 0.38, 43.77, 46.50 +CTUN, 778, 0.23, 0.71, 0.000000, 0, 0, 17, 782, 0 +ATT, 0.00, -0.09, -4.76, 0.82, 0.00, 46.74, 46.50 +CTUN, 766, 0.23, 0.66, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.00, -0.08, -6.81, 0.81, 0.00, 48.76, 46.50 +CTUN, 758, 0.25, 0.73, 0.000000, 0, 0, 24, 758, 0 +ATT, 0.00, -0.22, -7.37, -0.37, 0.00, 49.97, 46.50 +DU32, 7, 166140 +CURR, 758, 576011, 1026, 2088, 5051, 433.009460 +CTUN, 758, 0.25, 0.87, 0.000000, 0, 0, 21, 758, 0 +ATT, 0.00, -0.42, -8.12, -3.05, 0.00, 50.54, 46.50 +CTUN, 759, 0.29, 0.89, 0.000000, 0, 1, 19, 760, 0 +ATT, 0.00, -0.39, -8.21, -4.99, 0.00, 50.49, 46.50 +CTUN, 759, 0.29, 0.90, 0.000000, 0, 2, 16, 761, 0 +ATT, 0.00, -0.70, -8.02, -5.74, 0.00, 50.07, 46.50 +CTUN, 759, 0.32, 0.96, 0.000000, 0, 3, 14, 762, 0 +ATT, 0.00, -0.69, -7.74, -5.56, 0.00, 49.27, 46.50 +CTUN, 757, 0.32, 1.00, 0.000000, 0, 2, 10, 758, 0 +ATT, 0.84, -0.24, -6.06, -5.08, 0.00, 48.27, 46.50 +CTUN, 756, 0.35, 1.02, 0.000000, 0, 2, 9, 758, 0 +ATT, 1.78, 0.26, -4.38, -4.20, 0.00, 47.27, 46.50 +CTUN, 756, 0.35, 1.01, 0.000000, 0, 1, 7, 757, 0 +ATT, 2.43, 0.96, -2.24, -3.19, 0.00, 46.37, 46.50 +CTUN, 756, 0.37, 0.91, 0.000000, 0, 0, 4, 756, 0 +ATT, 2.62, 1.52, -2.24, -1.92, 0.00, 45.63, 46.50 +CTUN, 756, 0.37, 0.94, 0.000000, 0, 0, 2, 756, 0 +ATT, 2.34, 2.29, -2.24, -1.24, 0.00, 45.12, 46.50 +CTUN, 756, 0.37, 0.89, 0.000000, 0, 0, 0, 756, 0 +ATT, 2.34, 3.25, -2.24, -0.77, 0.00, 44.90, 46.50 +DU32, 7, 166140 +CURR, 755, 583594, 1027, 2070, 5028, 438.766970 +CTUN, 756, 0.37, 0.88, 0.000000, 0, 1, -1, 757, 0 +ATT, 0.84, 3.87, -2.24, -0.27, 0.00, 44.89, 46.50 +CTUN, 756, 0.37, 0.89, 0.000000, 0, 1, -6, 757, 0 +ATT, 0.00, 2.87, -2.33, -0.17, 0.00, 44.87, 46.50 +CTUN, 756, 0.36, 0.86, 0.000000, 0, 0, -8, 756, 0 +ATT, 0.00, 1.34, -2.52, -0.32, 0.00, 44.99, 46.50 +CTUN, 756, 0.36, 0.99, 0.000000, 0, 0, -11, 756, 0 +ATT, 0.00, 0.65, -3.26, -0.38, 0.00, 45.23, 46.50 +CTUN, 756, 0.35, 0.79, 0.000000, 0, 0, -12, 756, 0 +ATT, 0.00, 0.63, -3.26, -0.83, 0.00, 45.62, 46.50 +CTUN, 756, 0.35, 0.95, 0.000000, 0, 0, -15, 756, 0 +ATT, 0.00, 0.95, -3.45, -1.23, 0.00, 46.08, 46.50 +CTUN, 756, 0.32, 0.89, 0.000000, 0, 0, -14, 756, 0 +ATT, 0.00, 1.17, -3.17, -1.19, 0.00, 46.51, 46.50 +CTUN, 756, 0.32, 0.67, 0.000000, 0, 0, -14, 756, 0 +ATT, 0.00, 0.54, -2.24, -1.43, 0.00, 46.95, 46.50 +CTUN, 755, 0.29, 0.73, 0.000000, 0, 0, -13, 755, 0 +ATT, 0.00, 0.21, -2.05, -1.70, 0.00, 47.34, 46.50 +CTUN, 756, 0.29, 0.72, 0.000000, 0, 0, -13, 756, 0 +ATT, 0.00, -0.24, -2.24, -1.64, 0.00, 47.66, 46.50 +DU32, 7, 166140 +CURR, 756, 591155, 1037, 2054, 5051, 444.483760 +CTUN, 756, 0.26, 0.70, 0.000000, 0, 0, -12, 756, 0 +ATT, 0.00, -0.48, -2.24, -1.35, 0.00, 47.83, 46.50 +CTUN, 756, 0.26, 0.62, 0.000000, 0, 0, -5, 756, 0 +ATT, 0.00, -0.65, -2.24, -0.53, 0.00, 47.86, 46.50 +CTUN, 756, 0.24, 0.77, 0.000000, 0, 0, -3, 756, 0 +ATT, 0.00, -0.59, -2.24, -0.44, 0.00, 47.88, 46.50 +CTUN, 756, 0.24, 0.60, 0.000000, 0, 0, 0, 756, 0 +ATT, 0.00, -0.44, -2.24, -0.49, 0.00, 47.81, 46.50 +CTUN, 755, 0.22, 0.63, 0.000000, 0, 0, 4, 756, 0 +ATT, 0.00, -0.12, -2.33, -0.09, 0.00, 47.67, 46.50 +CTUN, 756, 0.22, 0.78, 0.000000, 0, 0, 8, 756, 0 +ATT, 0.00, -0.13, -3.08, 0.20, 0.00, 47.54, 46.50 +CTUN, 757, 0.21, 0.53, 0.000000, 0, 0, 10, 757, 0 +ATT, 0.00, -0.04, -3.73, -0.22, 0.00, 47.44, 46.50 +CTUN, 755, 0.22, 0.28, 0.000000, 0, 0, 10, 756, 0 +ATT, 0.00, 0.00, -4.38, -0.33, 0.00, 47.26, 46.50 +CTUN, 758, 0.22, 0.30, 0.000000, 0, 0, 11, 756, 0 +ATT, 0.00, 0.03, -4.29, -0.61, 0.00, 46.88, 46.50 +CTUN, 757, 0.23, 0.71, 0.000000, 0, 0, 11, 756, 0 +ATT, 0.00, -0.18, -4.57, -1.55, 0.00, 46.40, 46.50 +DU32, 7, 166140 +CURR, 757, 598715, 1025, 2063, 5051, 450.197110 +CTUN, 757, 0.23, 0.78, 0.000000, 0, 0, 12, 756, 0 +ATT, 0.00, -0.14, -4.76, -1.84, 0.00, 45.85, 46.50 +CTUN, 756, 0.25, 0.78, 0.000000, 0, 0, 10, 756, 0 +ATT, 0.00, -0.23, -3.92, -2.14, 0.00, 45.32, 46.50 +CTUN, 756, 0.25, 0.66, 0.000000, 0, 0, 12, 756, 0 +ATT, 0.00, -0.64, -2.05, -2.77, 0.00, 44.85, 46.50 +CTUN, 756, 0.27, 0.78, 0.000000, 0, 0, 10, 756, 0 +ATT, 0.00, -0.40, -2.24, -2.55, 0.00, 44.48, 46.50 +CTUN, 756, 0.27, 0.86, 0.000000, 0, 0, 13, 756, 0 +ATT, 0.00, -0.28, -2.24, -1.27, 0.00, 44.19, 46.50 +CTUN, 756, 0.28, 0.73, 0.000000, 0, 0, 9, 756, 0 +ATT, 0.00, -0.48, -2.52, -0.43, 0.00, 43.89, 46.50 +CTUN, 762, 0.28, 0.92, 0.000000, 0, 0, 8, 758, 0 +ATT, 0.00, -0.37, -2.52, -0.11, 0.00, 43.68, 46.50 +CTUN, 765, 0.29, 0.92, 0.000000, 0, 0, 8, 765, 0 +PM, 0, 0, 0, 0, 1000, 10492, 0, 0 +ATT, 0.00, -0.81, -2.52, -0.28, 0.00, 43.56, 46.50 +CTUN, 767, 0.29, 0.82, 0.000000, 0, 0, 6, 767, 0 +ATT, 0.00, -1.03, -2.52, -0.69, 0.00, 43.54, 46.50 +CTUN, 768, 0.31, 0.82, 0.000000, 0, 0, 4, 769, 0 +ATT, 0.00, -1.02, -2.42, -0.30, 0.00, 43.52, 46.50 +DU32, 7, 166140 +CURR, 771, 606310, 1025, 2109, 5051, 455.943150 +CTUN, 771, 0.31, 0.75, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, -1.50, -2.42, 0.58, 0.00, 43.41, 46.50 +CTUN, 771, 0.31, 0.77, 0.000000, 0, 0, 7, 770, 0 +ATT, 0.00, -2.21, -2.52, 0.86, 0.00, 43.43, 46.50 +CTUN, 771, 0.31, 0.88, 0.000000, 0, 0, 5, 770, 0 +ATT, 0.46, -2.59, -2.52, 0.38, 0.00, 43.49, 46.50 +CTUN, 771, 0.33, 0.82, 0.000000, 0, 0, 6, 770, 0 +ATT, 1.78, -1.88, -2.42, 0.71, 0.00, 43.37, 46.50 +CTUN, 771, 0.33, 0.80, 0.000000, 0, 0, 4, 771, 0 +ATT, 1.78, -0.49, -2.42, 1.18, 0.00, 43.10, 46.50 +CTUN, 770, 0.34, 0.74, 0.000000, 0, 0, 3, 770, 0 +ATT, 2.34, 0.43, -2.52, 1.32, 0.00, 42.72, 46.50 +CTUN, 771, 0.34, 0.88, 0.000000, 0, 0, 1, 771, 0 +ATT, 2.90, 1.22, -2.52, 1.26, 0.00, 42.26, 46.50 +CTUN, 771, 0.34, 0.90, 0.000000, 0, 0, 0, 771, 0 +ATT, 2.90, 2.80, -2.42, 1.26, 0.00, 41.74, 46.50 +CTUN, 771, 0.34, 0.94, 0.000000, 0, 1, -1, 771, 0 +ATT, 2.90, 4.08, -3.45, 0.94, 0.00, 41.26, 46.50 +CTUN, 770, 0.34, 0.94, 0.000000, 0, 1, -5, 772, 0 +ATT, 1.78, 4.44, -7.56, 0.43, 0.00, 40.83, 46.50 +DU32, 7, 166140 +CURR, 770, 614016, 1023, 2116, 5051, 461.851560 +CTUN, 770, 0.32, 0.95, 0.000000, 0, 1, -6, 772, 0 +ATT, 0.65, 4.16, -10.73, -1.10, 0.00, 40.50, 46.50 +CTUN, 771, 0.32, 0.82, 0.000000, 0, 1, -8, 772, 0 +ATT, 0.46, 3.62, -11.20, -3.47, 0.00, 40.23, 46.50 +CTUN, 771, 0.32, 0.85, 0.000000, 0, 3, -9, 773, 0 +ATT, 0.18, 3.65, -11.01, -5.72, 0.00, 40.10, 46.50 +CTUN, 771, 0.32, 0.91, 0.000000, 0, 5, -11, 776, 0 +ATT, 0.28, 4.08, -10.92, -6.48, 0.00, 40.17, 46.50 +CTUN, 771, 0.29, 0.83, 0.000000, 0, 5, -10, 776, 0 +ATT, 0.28, 3.57, -10.92, -6.45, 0.00, 40.64, 46.50 +CTUN, 771, 0.29, 0.78, 0.000000, 0, 5, -8, 776, 0 +ATT, 0.00, 2.67, -10.54, -6.04, 0.00, 41.36, 46.50 +CTUN, 770, 0.27, 0.94, 0.000000, 0, 3, -3, 774, 0 +ATT, 0.00, 1.55, -9.52, -5.78, 0.00, 42.15, 46.50 +CTUN, 771, 0.27, 0.64, 0.000000, 0, 3, -3, 774, 0 +ATT, 0.00, 0.94, -8.21, -4.80, 0.00, 42.96, 46.50 +CTUN, 770, 0.25, 0.68, 0.000000, 0, 1, 2, 773, 0 +ATT, 0.00, 0.29, -6.44, -2.86, 0.00, 43.89, 46.50 +CTUN, 771, 0.25, 0.70, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 0.35, -4.85, -1.35, 0.00, 44.90, 46.50 +DU32, 7, 166140 +CURR, 771, 621752, 1023, 2130, 5028, 467.780700 +CTUN, 771, 0.25, 0.57, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, 1.01, -4.38, -0.02, 0.00, 45.83, 46.50 +CTUN, 771, 0.25, 0.86, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, 0.63, -3.08, 0.68, 0.00, 46.67, 46.50 +CTUN, 771, 0.25, 0.77, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, 0.54, -2.52, 0.45, 0.00, 47.47, 46.50 +CTUN, 771, 0.25, 0.84, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.00, 0.45, -2.42, 0.32, 0.00, 48.01, 46.50 +CTUN, 770, 0.25, 0.80, 0.000000, 0, 0, 19, 770, 0 +ATT, 0.00, 0.06, -2.52, 0.75, 0.00, 48.27, 46.50 +CTUN, 771, 0.27, 0.87, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.00, -0.39, -2.52, 1.47, 0.00, 48.34, 46.50 +CTUN, 770, 0.27, 0.85, 0.000000, 0, 0, 21, 771, 0 +ATT, 0.00, -0.59, -3.26, 1.93, 0.00, 48.20, 46.50 +CTUN, 771, 0.30, 0.85, 0.000000, 0, 0, 18, 770, 0 +ATT, 0.00, -0.45, -4.57, 1.70, 0.00, 47.85, 46.50 +CTUN, 771, 0.30, 0.95, 0.000000, 0, 0, 16, 770, 0 +ATT, 0.00, -0.76, -6.16, 0.71, 0.00, 47.36, 46.50 +CTUN, 770, 0.32, 0.78, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, -1.12, -6.53, -0.22, 0.00, 46.74, 46.50 +DU32, 7, 166140 +CURR, 771, 629460, 1020, 2119, 5028, 473.708370 +CTUN, 770, 0.32, 0.81, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.00, -0.83, -6.53, -1.30, 0.00, 45.98, 46.50 +CTUN, 770, 0.36, 0.99, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, -0.50, -6.53, -2.08, 0.00, 45.26, 46.50 +CTUN, 770, 0.36, 1.05, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.93, -6.53, -2.19, 0.00, 44.67, 46.50 +CTUN, 770, 0.37, 1.01, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, -1.31, -6.53, -2.03, 0.00, 44.18, 46.50 +CTUN, 771, 0.37, 1.13, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.83, -6.53, -2.19, 0.00, 43.72, 46.50 +CTUN, 770, 0.37, 1.07, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 0.44, -6.53, -2.77, 0.00, 43.34, 46.50 +CTUN, 771, 0.37, 0.96, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.93, -6.53, -3.26, 0.00, 43.08, 46.50 +CTUN, 771, 0.37, 1.15, 0.000000, 0, 1, -1, 772, 0 +ATT, 0.00, 1.28, -6.53, -3.37, 0.00, 42.84, 46.50 +CTUN, 771, 0.37, 0.92, 0.000000, 0, 1, -3, 771, 0 +ATT, 0.00, 0.78, -6.06, -3.30, 0.00, 42.62, 46.50 +CTUN, 771, 0.37, 1.01, 0.000000, 0, 1, -5, 771, 0 +ATT, 0.00, -0.19, -5.04, -3.11, 0.00, 42.45, 46.50 +DU32, 7, 166140 +CURR, 771, 637171, 1028, 2094, 5051, 479.558870 +CTUN, 771, 0.35, 0.94, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -0.38, -4.85, -2.20, 0.00, 42.34, 46.50 +CTUN, 770, 0.35, 1.07, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, -0.34, -4.85, -0.79, 0.00, 42.34, 46.50 +CTUN, 771, 0.33, 1.06, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -0.19, -4.48, -0.79, 0.00, 42.65, 46.50 +CTUN, 771, 0.33, 0.87, 0.000000, 0, 0, -7, 771, 0 +ATT, 0.00, 0.25, -4.38, -1.50, 0.00, 43.15, 46.50 +CTUN, 771, 0.31, 0.88, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, 0.32, -4.48, -1.76, 0.00, 43.81, 46.50 +CTUN, 771, 0.31, 0.84, 0.000000, 0, 0, -4, 770, 0 +ATT, 0.00, 0.18, -4.20, -1.52, 0.00, 44.68, 46.50 +CTUN, 770, 0.29, 0.94, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, 0.18, -3.92, -1.33, 0.00, 45.66, 46.50 +CTUN, 771, 0.29, 0.83, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.20, -3.17, -1.71, 0.00, 46.81, 46.50 +CTUN, 771, 0.27, 0.79, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.19, -3.08, -2.18, 0.00, 47.99, 46.50 +CTUN, 770, 0.27, 0.77, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 0.11, -3.17, -1.48, 0.00, 48.88, 46.50 +DU32, 7, 166140 +CURR, 771, 644880, 1027, 2114, 5051, 485.402770 +CTUN, 771, 0.26, 0.82, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.01, -3.08, -0.24, 0.00, 49.56, 46.50 +CTUN, 771, 0.26, 0.76, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, -0.38, -2.80, 0.57, 0.00, 50.10, 46.50 +CTUN, 771, 0.26, 0.70, 0.000000, 0, 0, 9, 770, 0 +ATT, 0.00, 0.15, -2.61, 1.27, 0.00, 50.43, 46.50 +CTUN, 770, 0.27, 0.78, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, 0.66, -2.52, 1.80, 0.00, 50.67, 46.50 +CTUN, 770, 0.26, 0.87, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, 0.82, -2.61, 1.44, 0.00, 50.88, 46.50 +CTUN, 771, 0.26, 0.84, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, 1.26, -2.61, 0.48, 0.00, 50.94, 46.50 +CTUN, 771, 0.26, 0.81, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, 1.58, -2.70, 0.37, 0.00, 50.89, 46.50 +CTUN, 771, 0.28, 0.82, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, 1.01, -2.70, 1.20, 0.00, 50.88, 46.50 +CTUN, 771, 0.28, 0.86, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, -0.12, -2.80, 1.09, 0.00, 50.88, 46.50 +CTUN, 771, 0.29, 0.74, 0.000000, 0, 0, 9, 770, 0 +ATT, 0.00, -0.04, -2.61, 0.22, 0.00, 50.80, 46.50 +DU32, 7, 166140 +CURR, 770, 652588, 1019, 2116, 5051, 491.281890 +CTUN, 770, 0.29, 0.79, 0.000000, 0, 0, 9, 771, 0 +ATT, -0.37, 0.92, -2.70, -0.24, 0.00, 50.53, 46.50 +CTUN, 770, 0.29, 0.85, 0.000000, 0, 0, 8, 771, 0 +ATT, -2.17, 0.76, -1.49, -0.65, 0.00, 50.17, 46.50 +CTUN, 771, 0.29, 0.81, 0.000000, 0, 0, 9, 770, 0 +ATT, -2.36, -0.81, -2.33, -1.04, 0.00, 49.71, 46.50 +CTUN, 771, 0.30, 0.85, 0.000000, 0, 0, 9, 771, 0 +ATT, -0.94, -2.02, -2.61, -1.15, 0.00, 49.16, 46.50 +CTUN, 771, 0.30, 0.99, 0.000000, 0, 0, 11, 771, 0 +ATT, -0.75, -2.06, -2.70, -1.01, 0.00, 48.44, 46.50 +CTUN, 771, 0.33, 0.92, 0.000000, 0, 0, 7, 770, 0 +ATT, -0.37, -0.78, -2.89, -1.39, 0.00, 47.96, 46.50 +CTUN, 771, 0.33, 0.86, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, -0.24, -2.89, -1.40, 0.00, 47.65, 46.50 +CTUN, 770, 0.33, 0.92, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.25, -3.08, -1.20, 0.00, 47.57, 46.50 +CTUN, 771, 0.33, 0.91, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.00, -3.08, -1.21, 0.00, 47.69, 46.50 +CTUN, 771, 0.34, 0.97, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.27, -2.98, -1.56, 0.00, 47.97, 46.50 +DU32, 7, 166140 +CURR, 770, 660297, 1015, 2097, 5051, 497.135040 +CTUN, 771, 0.34, 1.00, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, 0.44, -3.08, -2.27, 0.00, 48.32, 46.50 +CTUN, 771, 0.34, 0.87, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.00, 0.23, -2.80, -2.64, 0.00, 48.66, 46.50 +CTUN, 771, 0.34, 0.80, 0.000000, 0, 0, -2, 770, 0 +ATT, 0.00, -0.41, -2.61, -2.57, 0.00, 49.05, 46.50 +CTUN, 771, 0.34, 1.06, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, -0.40, -2.52, -1.61, 0.00, 49.32, 46.50 +CTUN, 771, 0.33, 0.86, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 0.45, -1.77, -0.48, 0.00, 49.40, 46.50 +CTUN, 771, 0.33, 0.90, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 0.74, 0.00, 0.11, 0.00, 49.14, 46.50 +CTUN, 771, 0.32, 0.82, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.92, 0.00, 0.99, 0.00, 48.73, 46.50 +CTUN, 771, 0.32, 1.02, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, 1.84, 0.00, 2.28, 0.00, 48.23, 46.50 +CTUN, 771, 0.32, 0.89, 0.000000, 0, 1, 9, 772, 0 +ATT, 0.00, 2.41, 0.00, 3.41, 0.00, 47.62, 46.50 +CTUN, 771, 0.32, 0.97, 0.000000, 0, 1, 5, 772, 0 +ATT, 0.00, 2.19, 0.00, 2.59, 0.00, 47.10, 46.50 +DU32, 7, 166140 +CURR, 771, 668007, 1020, 2123, 5051, 503.020450 +CTUN, 770, 0.32, 1.03, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.00, 1.51, 0.00, 0.63, 0.00, 46.94, 46.50 +CTUN, 771, 0.32, 0.95, 0.000000, 0, 0, 4, 770, 0 +ATT, -2.93, 0.95, 0.00, -0.05, 0.00, 47.37, 46.50 +CTUN, 771, 0.32, 0.89, 0.000000, 0, 0, 6, 771, 0 +ATT, -3.78, -0.94, -0.93, 1.83, 0.00, 47.99, 46.50 +CTUN, 771, 0.32, 1.00, 0.000000, 0, 1, 9, 772, 0 +ATT, -4.45, -4.10, -1.02, 4.62, 0.00, 48.63, 46.50 +CTUN, 771, 0.32, 0.90, 0.000000, 0, 4, 6, 775, 0 +ATT, -5.21, -5.10, -1.02, 4.79, 0.00, 49.40, 46.50 +CTUN, 771, 0.34, 1.09, 0.000000, 0, 4, 3, 774, 0 +ATT, -4.35, -4.14, -0.93, 2.73, 0.00, 50.20, 46.50 +CTUN, 771, 0.34, 0.96, 0.000000, 0, 1, 1, 772, 0 +ATT, -2.55, -3.94, -2.42, -0.01, 0.00, 50.83, 46.50 +CTUN, 771, 0.34, 0.88, 0.000000, 0, 1, -1, 772, 0 +ATT, -2.74, -3.82, -2.61, -2.57, 0.00, 51.33, 46.50 +CTUN, 771, 0.34, 0.91, 0.000000, 0, 2, -1, 773, 0 +ATT, -0.85, -3.13, -2.61, -3.65, 0.00, 51.59, 46.50 +CTUN, 770, 0.34, 0.91, 0.000000, 0, 2, 0, 773, 0 +ATT, 0.00, -2.77, -2.61, -3.44, 0.00, 51.55, 46.50 +DU32, 7, 166140 +CURR, 770, 675728, 1019, 2109, 5051, 508.902500 +CTUN, 770, 0.33, 0.89, 0.000000, 0, 1, 0, 772, 0 +ATT, 0.00, -2.10, -2.89, -2.36, 0.00, 51.46, 46.50 +CTUN, 770, 0.33, 0.77, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -1.32, -2.80, -1.72, 0.00, 51.27, 46.50 +CTUN, 771, 0.31, 0.92, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -1.30, -2.89, -1.42, 0.00, 50.96, 46.50 +CTUN, 770, 0.31, 0.99, 0.000000, 0, 0, -9, 771, 0 +ATT, 0.00, -1.43, -3.08, -1.85, 0.00, 50.73, 46.50 +CTUN, 771, 0.30, 0.90, 0.000000, 0, 0, -9, 771, 0 +ATT, 0.00, -1.38, -3.08, -2.12, 0.00, 50.61, 46.50 +CTUN, 770, 0.30, 0.90, 0.000000, 0, 0, -7, 770, 0 +ATT, 0.00, -0.10, -3.08, -2.63, 0.00, 50.43, 46.50 +CTUN, 771, 0.28, 0.80, 0.000000, 0, 0, -7, 770, 0 +ATT, 0.00, 1.54, -2.80, -2.40, 0.00, 50.44, 46.50 +CTUN, 771, 0.28, 0.76, 0.000000, 0, 0, -5, 770, 0 +PM, 0, 0, 0, 0, 1000, 10476, 0, 0 +ATT, 0.00, 2.17, -2.70, -1.93, 0.00, 50.69, 46.50 +CTUN, 770, 0.26, 0.79, 0.000000, 0, 0, -1, 770, 0 +ATT, 0.00, 0.70, -2.42, -1.55, 0.00, 51.12, 46.50 +CTUN, 771, 0.26, 0.82, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.30, -2.52, -1.61, 0.00, 51.61, 46.50 +DU32, 7, 166140 +CURR, 771, 683435, 1022, 2126, 5051, 514.773070 +CTUN, 771, 0.24, 0.80, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 1.92, -2.05, -1.83, 0.00, 52.19, 46.50 +CTUN, 771, 0.24, 0.73, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 2.58, -1.40, -1.53, 0.00, 52.84, 46.50 +CTUN, 770, 0.24, 0.93, 0.000000, 0, 0, 10, 770, 0 +ATT, 0.00, 1.46, 0.00, -0.38, 0.00, 53.64, 46.50 +CTUN, 771, 0.24, 0.98, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, 0.66, 0.00, 1.03, 0.00, 54.43, 46.50 +CTUN, 771, 0.24, 0.92, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, 1.15, 0.00, 1.86, 0.00, 54.99, 46.50 +CTUN, 771, 0.26, 0.91, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, 3.02, 0.00, 1.63, 0.00, 55.16, 46.50 +CTUN, 770, 0.26, 0.83, 0.000000, 0, 1, 7, 772, 0 +ATT, 0.00, 2.65, 0.00, 0.64, 0.00, 55.06, 46.50 +CTUN, 771, 0.27, 0.88, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.00, 2.17, -0.93, 0.02, 0.00, 54.66, 46.50 +CTUN, 771, 0.27, 0.78, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 1.00, -0.93, 0.06, 0.00, 54.47, 46.50 +CTUN, 771, 0.27, 0.81, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -0.45, 0.00, 0.13, 0.00, 54.25, 46.50 +DU32, 7, 166140 +CURR, 770, 691143, 1023, 2092, 5051, 520.668400 +CTUN, 771, 0.26, 0.93, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.15, 0.00, -0.54, 0.00, 54.06, 46.50 +CTUN, 770, 0.26, 0.87, 0.000000, 0, 0, 1, 770, 0 +ATT, -0.37, 1.32, -0.37, -1.61, 0.00, 53.98, 46.50 +CTUN, 771, 0.26, 0.78, 0.000000, 0, 0, 2, 770, 0 +ATT, -0.37, -0.35, -0.37, -1.59, 0.00, 54.20, 46.50 +CTUN, 770, 0.26, 0.84, 0.000000, 0, 0, 2, 770, 0 +ATT, -1.70, -3.10, 0.00, -1.15, 0.00, 54.50, 46.50 +CTUN, 771, 0.25, 0.80, 0.000000, 0, 1, 6, 772, 0 +ATT, -2.46, -4.37, 0.00, -1.46, 0.00, 54.88, 46.50 +CTUN, 770, 0.26, 0.71, 0.000000, 0, 1, 9, 772, 0 +ATT, -3.12, -3.58, 0.00, -1.30, 0.00, 55.20, 46.50 +CTUN, 771, 0.26, 0.80, 0.000000, 0, 1, 13, 772, 0 +ATT, -3.22, -3.67, 0.00, -0.70, 0.00, 55.42, 46.50 +CTUN, 770, 0.26, 0.93, 0.000000, 0, 1, 16, 772, 0 +ATT, -1.23, -4.55, 0.00, -0.40, 0.00, 55.45, 46.50 +CTUN, 770, 0.26, 0.76, 0.000000, 0, 2, 17, 773, 0 +ATT, -0.75, -3.67, 0.00, 0.28, 0.00, 55.12, 46.50 +CTUN, 771, 0.28, 0.88, 0.000000, 0, 1, 19, 772, 0 +ATT, 0.00, -1.25, 0.00, 1.46, 0.00, 54.30, 46.50 +DU32, 7, 166140 +CURR, 770, 698857, 1013, 2175, 5028, 526.637940 +CTUN, 771, 0.28, 0.73, 0.000000, 0, 0, 24, 771, 0 +ATT, 0.00, -0.40, 0.00, 2.81, 0.00, 52.85, 46.50 +CTUN, 771, 0.30, 1.05, 0.000000, 0, 0, 21, 771, 0 +ATT, 0.00, -0.83, 0.00, 2.37, 0.00, 51.53, 46.50 +CTUN, 771, 0.30, 1.02, 0.000000, 0, 0, 21, 771, 0 +ATT, 0.00, -1.36, 0.00, 1.59, 0.00, 50.65, 46.50 +CTUN, 771, 0.34, 1.07, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.00, -0.07, 0.00, 1.86, 0.00, 50.08, 46.50 +CTUN, 771, 0.34, 1.03, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.00, 0.38, -1.21, 2.70, 0.00, 49.65, 46.50 +CTUN, 771, 0.37, 1.25, 0.000000, 0, 0, 10, 770, 0 +ATT, 0.00, 1.20, -1.40, 1.60, 0.00, 49.57, 46.50 +CTUN, 771, 0.37, 1.05, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 1.34, -2.14, -0.39, 0.00, 49.68, 46.50 +CTUN, 770, 0.37, 1.27, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, -0.94, -2.33, -2.44, 0.00, 50.21, 46.50 +CTUN, 771, 0.37, 1.11, 0.000000, 0, 1, 4, 772, 0 +ATT, 0.00, -2.05, -2.52, -4.00, 0.00, 50.77, 46.50 +CTUN, 771, 0.39, 1.06, 0.000000, 0, 2, 2, 773, 0 +ATT, 0.00, -1.12, -2.52, -4.20, 0.00, 51.15, 46.50 +DU32, 7, 166140 +CURR, 771, 706570, 1024, 2127, 5051, 532.557250 +CTUN, 771, 0.39, 1.16, 0.000000, 0, 1, 1, 772, 0 +ATT, 0.00, -0.10, -2.52, -2.87, 0.00, 51.48, 46.50 +CTUN, 771, 0.39, 1.05, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, -0.16, -2.52, -2.25, 0.00, 51.78, 46.50 +CTUN, 770, 0.39, 0.98, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, -0.99, -2.52, -2.01, 0.00, 52.13, 46.50 +CTUN, 771, 0.39, 0.91, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -1.29, -2.52, -1.16, 0.00, 52.59, 46.50 +CTUN, 771, 0.39, 0.93, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, -0.54, -2.52, -0.35, 0.00, 53.13, 46.50 +CTUN, 771, 0.39, 1.00, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 0.62, -2.52, -0.32, 0.00, 53.58, 46.50 +CTUN, 770, 0.39, 0.97, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.76, -2.42, -0.91, 0.00, 53.82, 46.50 +CTUN, 770, 0.39, 1.05, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.68, -2.52, -1.47, 0.00, 54.05, 46.50 +CTUN, 771, 0.39, 0.91, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, 0.58, -2.42, -1.98, 0.00, 54.11, 46.50 +CTUN, 771, 0.39, 1.13, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, 0.16, -2.52, -2.04, 0.00, 53.86, 46.50 +DU32, 7, 166140 +CURR, 771, 714279, 1012, 2156, 5051, 538.535710 +CTUN, 771, 0.37, 1.02, 0.000000, 0, 0, -4, 774, 0 +ATT, 0.00, -0.13, -2.42, -1.73, 0.00, 53.39, 46.50 +CTUN, 771, 0.37, 1.05, 0.000000, 0, 0, -8, 770, 0 +ATT, 0.00, -0.06, -2.42, -2.10, 0.00, 52.89, 46.50 +CTUN, 770, 0.36, 0.92, 0.000000, 0, 0, -9, 770, 0 +ATT, 0.00, -0.49, -2.05, -2.58, 0.00, 52.28, 46.50 +CTUN, 771, 0.36, 0.92, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, -1.11, -0.74, -2.34, 0.00, 51.53, 46.50 +CTUN, 770, 0.34, 0.99, 0.000000, 0, 0, -10, 770, 0 +ATT, 0.00, -1.12, 0.00, -1.43, 0.00, 50.79, 46.50 +CTUN, 771, 0.34, 0.92, 0.000000, 0, 0, -11, 771, 0 +ATT, 0.00, -1.01, 0.00, -0.09, 0.00, 50.05, 46.50 +CTUN, 771, 0.32, 0.98, 0.000000, 0, 0, -14, 770, 0 +ATT, 0.00, -0.37, 0.00, 0.83, 0.00, 49.32, 46.50 +CTUN, 771, 0.32, 1.00, 0.000000, 0, 0, -16, 771, 0 +ATT, 0.00, 1.49, 0.00, 0.77, 0.00, 48.64, 46.50 +CTUN, 771, 0.29, 0.92, 0.000000, 0, 0, -18, 770, 0 +ATT, 0.00, 2.09, 0.00, 0.47, 0.00, 48.20, 46.50 +CTUN, 771, 0.29, 0.88, 0.000000, 0, 0, -17, 770, 0 +ATT, 0.00, 1.15, 0.00, 0.26, 0.00, 47.93, 46.50 +DU32, 7, 166140 +CURR, 771, 721989, 1023, 2096, 5028, 544.432920 +CTUN, 771, 0.26, 0.90, 0.000000, 0, 0, -14, 771, 0 +ATT, 0.00, 0.78, 0.00, 0.06, 0.00, 47.80, 46.50 +CTUN, 770, 0.26, 0.89, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, 1.00, 0.00, 0.41, 0.00, 48.03, 46.50 +CTUN, 771, 0.22, 0.75, 0.000000, 0, 0, -7, 771, 0 +ATT, -0.37, 1.22, 0.00, 0.92, 0.00, 48.49, 46.50 +CTUN, 771, 0.22, 0.79, 0.000000, 0, 0, -3, 771, 0 +ATT, -0.75, 0.80, 0.00, 1.06, 0.00, 49.05, 46.50 +CTUN, 771, 0.21, 0.80, 0.000000, 0, 0, -1, 771, 0 +ATT, -0.75, -0.40, 0.00, 0.83, 0.00, 49.71, 46.50 +CTUN, 771, 0.21, 0.94, 0.000000, 0, 0, -1, 771, 0 +ATT, -0.75, -0.19, 0.00, -0.29, 0.00, 50.46, 46.50 +CTUN, 771, 0.21, 0.88, 0.000000, 0, 0, 3, 770, 0 +ATT, -0.75, -0.14, 0.00, -1.15, 0.00, 51.20, 46.50 +CTUN, 770, 0.21, 1.02, 0.000000, 0, 0, 5, 771, 0 +ATT, -0.85, -0.63, 0.00, -1.00, 0.00, 52.06, 46.50 +CTUN, 770, 0.21, 0.87, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, -1.12, 0.00, -0.03, 0.00, 52.93, 46.50 +CTUN, 771, 0.21, 0.89, 0.000000, 0, 0, 14, 771, 0 +ATT, -1.32, -2.14, 0.00, 0.37, 0.00, 53.81, 46.50 +DU32, 7, 166140 +CURR, 771, 729699, 1031, 2039, 5051, 550.314940 +CTUN, 771, 0.21, 0.97, 0.000000, 0, 0, 13, 771, 0 +ATT, -2.17, -1.95, 0.00, 0.00, 0.00, 54.67, 46.50 +CTUN, 771, 0.24, 0.73, 0.000000, 0, 0, 14, 771, 0 +ATT, -0.94, -1.92, 0.00, -0.57, 0.00, 55.39, 46.50 +CTUN, 771, 0.24, 0.93, 0.000000, 0, 0, 13, 771, 0 +ATT, -0.66, -2.39, 0.00, -1.01, 0.00, 55.85, 46.50 +CTUN, 771, 0.26, 0.97, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, -2.18, 0.00, -0.87, 0.00, 55.97, 46.50 +CTUN, 770, 0.26, 0.95, 0.000000, 0, 0, 15, 770, 0 +ATT, 0.00, -1.87, -0.93, -0.70, 0.00, 55.85, 46.50 +CTUN, 770, 0.29, 0.86, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, -1.54, -1.58, -0.86, 0.00, 55.30, 46.50 +CTUN, 771, 0.29, 0.96, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, -1.33, -2.24, -0.86, 0.00, 54.18, 46.50 +CTUN, 771, 0.33, 1.01, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.00, -1.18, -2.52, -1.01, 0.00, 52.88, 46.50 +CTUN, 771, 0.33, 0.98, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, -1.64, -2.52, -1.08, 0.00, 51.60, 46.50 +CTUN, 771, 0.37, 0.92, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -2.00, -2.52, -1.09, 0.00, 50.24, 46.50 +DU32, 7, 166140 +CURR, 771, 737407, 1012, 2134, 5051, 556.350650 +CTUN, 771, 0.37, 0.93, 0.000000, 0, 0, 9, 770, 0 +ATT, 0.00, -1.84, -2.42, -0.16, 0.00, 48.65, 46.50 +CTUN, 771, 0.40, 1.11, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, -1.31, -2.42, 0.24, 0.00, 47.19, 46.50 +CTUN, 771, 0.40, 1.10, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, -0.70, -2.42, 0.13, 0.00, 46.08, 46.50 +CTUN, 771, 0.41, 1.10, 0.000000, 0, 0, -1, 771, 0 +ATT, 1.78, -0.32, -2.42, 0.42, 0.00, 45.36, 46.50 +CTUN, 771, 0.41, 0.93, 0.000000, 0, 0, -3, 770, 0 +ATT, 2.06, -0.07, -2.52, 0.97, 0.00, 44.84, 46.50 +CTUN, 770, 0.41, 1.14, 0.000000, 0, 0, -5, 770, 0 +ATT, 2.34, 0.13, -2.42, 0.90, 0.00, 44.34, 46.50 +CTUN, 770, 0.41, 1.05, 0.000000, 0, 0, -9, 770, 0 +ATT, 3.28, 0.85, -2.52, 0.16, 0.00, 43.77, 46.50 +CTUN, 770, 0.42, 1.13, 0.000000, 0, 0, -8, 770, 0 +ATT, 3.37, 1.94, -2.52, -0.37, 0.00, 43.32, 46.50 +CTUN, 771, 0.41, 1.07, 0.000000, 0, 0, -12, 771, 0 +ATT, 3.65, 2.72, -2.52, -0.57, 0.00, 43.17, 46.50 +CTUN, 770, 0.41, 1.13, 0.000000, 0, 0, -13, 771, 0 +ATT, 3.84, 3.25, -2.52, -0.93, 0.00, 43.31, 46.50 +DU32, 7, 166140 +CURR, 771, 745114, 1016, 2106, 5051, 562.206670 +CTUN, 770, 0.40, 1.09, 0.000000, 0, 1, -13, 771, 0 +ATT, 3.84, 3.22, -2.52, -1.06, 0.00, 43.44, 46.50 +CTUN, 771, 0.40, 1.09, 0.000000, 0, 1, -14, 772, 0 +ATT, 3.93, 3.46, -2.52, -0.99, 0.00, 43.36, 46.50 +CTUN, 770, 0.38, 1.05, 0.000000, 0, 1, -15, 772, 0 +ATT, 3.75, 4.07, -2.52, -0.57, 0.00, 43.02, 46.50 +CTUN, 770, 0.38, 1.06, 0.000000, 0, 1, -15, 772, 0 +ATT, 3.37, 4.71, -2.42, 0.07, 0.00, 42.57, 46.50 +CTUN, 771, 0.35, 0.90, 0.000000, 0, 2, -16, 772, 0 +ATT, 3.18, 4.37, -2.42, -0.02, 0.00, 41.80, 46.50 +CTUN, 771, 0.35, 1.01, 0.000000, 0, 1, -18, 772, 0 +ATT, 2.15, 3.42, -4.10, -0.86, 0.00, 41.04, 46.50 +CTUN, 771, 0.32, 0.88, 0.000000, 0, 1, -17, 771, 0 +ATT, 0.28, 3.67, -4.76, -2.21, 0.00, 40.58, 46.50 +CTUN, 771, 0.32, 1.02, 0.000000, 0, 1, -13, 772, 0 +ATT, 0.00, 2.27, -5.60, -3.04, 0.00, 40.44, 46.50 +CTUN, 771, 0.30, 0.99, 0.000000, 0, 1, -13, 772, 0 +ATT, 0.00, -0.46, -5.32, -3.51, 0.00, 40.34, 46.50 +CTUN, 771, 0.30, 0.82, 0.000000, 0, 1, -10, 772, 0 +ATT, 0.00, -1.45, -4.76, -3.91, 0.00, 40.27, 46.50 +DU32, 7, 166140 +CURR, 771, 752833, 1013, 2106, 5051, 568.069640 +CTUN, 771, 0.28, 0.81, 0.000000, 0, 1, -8, 771, 0 +ATT, 0.00, -0.45, -4.85, -2.98, 0.00, 40.16, 46.50 +CTUN, 771, 0.28, 0.96, 0.000000, 0, 0, -9, 771, 0 +ATT, 0.00, -0.27, -4.76, -1.64, 0.00, 40.12, 46.50 +CTUN, 770, 0.26, 0.75, 0.000000, 0, 0, -6, 770, 0 +ATT, 0.00, -0.58, -5.22, -1.17, 0.00, 40.22, 46.50 +CTUN, 771, 0.26, 0.85, 0.000000, 0, 0, -7, 770, 0 +ATT, 0.00, -0.76, -5.41, -1.60, 0.00, 40.53, 46.50 +CTUN, 771, 0.24, 0.87, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.42, -5.50, -1.82, 0.00, 41.06, 46.50 +CTUN, 770, 0.24, 0.96, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -0.46, -5.69, -1.48, 0.00, 41.77, 46.50 +CTUN, 770, 0.24, 0.85, 0.000000, 0, 0, -5, 770, 0 +ATT, 0.00, -0.84, -5.69, -0.90, 0.00, 42.63, 46.50 +CTUN, 771, 0.24, 0.81, 0.000000, 0, 0, -2, 770, 0 +PM, 0, 0, 0, 0, 1000, 10476, 0, 0 +ATT, 0.00, -1.53, -5.69, -0.32, 0.00, 43.67, 46.50 +CTUN, 771, 0.24, 0.83, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, -1.79, -5.69, 0.57, 0.00, 44.77, 46.50 +CTUN, 770, 0.24, 0.94, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -1.69, -7.74, 1.09, 0.00, 45.70, 46.50 +DU32, 7, 166140 +CURR, 771, 760540, 1021, 2094, 5051, 573.887210 +CTUN, 771, 0.23, 0.89, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -1.54, -10.26, 0.79, 0.00, 46.34, 46.50 +CTUN, 771, 0.23, 0.89, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -1.28, -14.09, -0.07, 0.00, 46.61, 46.50 +CTUN, 771, 0.23, 0.96, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -1.35, -16.24, -2.49, 0.00, 46.30, 46.50 +CTUN, 771, 0.23, 0.77, 0.000000, 0, 1, 0, 771, 0 +ATT, 0.00, -0.55, -17.36, -8.30, 0.00, 45.84, 46.50 +CTUN, 771, 0.23, 1.03, 0.000000, 0, 10, 4, 781, 0 +ATT, 0.00, 0.59, -17.64, -14.09, 0.00, 45.06, 46.50 +CTUN, 771, 0.23, 1.03, 0.000000, 0, 22, 7, 793, 0 +ATT, 0.00, 0.52, -17.17, -16.35, 0.00, 44.07, 46.50 +CTUN, 771, 0.23, 0.84, 0.000000, 0, 27, 13, 798, 0 +ATT, 0.00, 0.63, -14.84, -16.29, 0.00, 43.10, 46.50 +CTUN, 771, 0.24, 0.89, 0.000000, 0, 26, 17, 797, 0 +ATT, 0.00, 1.24, -7.46, -14.21, 0.00, 42.84, 46.50 +CTUN, 771, 0.24, 0.94, 0.000000, 0, 15, 23, 786, 0 +ATT, 0.00, 1.78, -1.68, -9.37, 0.00, 43.16, 46.50 +CTUN, 771, 0.26, 0.92, 0.000000, 0, 5, 26, 776, 0 +ATT, 0.00, 2.35, 0.00, -3.12, 0.00, 44.00, 46.50 +DU32, 7, 166140 +CURR, 770, 768358, 1015, 2143, 5051, 579.855900 +CTUN, 770, 0.26, 0.97, 0.000000, 0, 0, 28, 770, 0 +ATT, 0.00, 2.79, 0.00, 2.30, 0.00, 45.06, 46.50 +CTUN, 771, 0.29, 1.14, 0.000000, 0, 1, 29, 771, 0 +ATT, 0.00, 2.94, 0.00, 5.08, 0.00, 46.03, 46.50 +CTUN, 770, 0.29, 1.20, 0.000000, 0, 3, 25, 774, 0 +ATT, 0.00, 3.12, -1.96, 5.68, 0.00, 46.78, 46.50 +CTUN, 770, 0.34, 1.07, 0.000000, 0, 3, 21, 774, 0 +ATT, 0.00, 3.14, -2.52, 4.69, 0.00, 47.13, 46.50 +CTUN, 770, 0.34, 1.07, 0.000000, 0, 2, 18, 773, 0 +ATT, 0.00, 2.48, -3.26, 3.41, 0.00, 47.12, 46.50 +CTUN, 771, 0.39, 1.23, 0.000000, 0, 1, 18, 772, 0 +ATT, 0.00, 1.19, -4.10, 2.65, 0.00, 46.80, 46.50 +CTUN, 771, 0.39, 1.24, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.00, -0.33, -3.26, 2.19, 0.00, 46.22, 46.50 +CTUN, 770, 0.42, 1.29, 0.000000, 0, 0, 12, 770, 0 +ATT, 0.00, -0.90, -2.70, 1.94, 0.00, 45.61, 46.50 +CTUN, 771, 0.42, 1.33, 0.000000, 0, 0, 9, 771, 0 +ATT, -0.37, -0.33, -2.61, 2.15, 0.00, 45.18, 46.50 +CTUN, 770, 0.46, 1.17, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 0.26, -2.61, 2.32, 0.00, 44.89, 46.50 +DU32, 7, 166140 +CURR, 770, 776075, 1023, 2104, 5051, 585.731320 +CTUN, 771, 0.46, 1.22, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 0.31, -2.61, 2.12, 0.00, 44.70, 46.50 +CTUN, 771, 0.48, 1.34, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.15, -2.52, 1.67, 0.00, 44.54, 46.50 +CTUN, 771, 0.48, 1.42, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, 0.19, -2.42, 1.17, 0.00, 44.52, 46.50 +CTUN, 771, 0.49, 1.32, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, 0.56, -2.52, 0.98, 0.00, 44.56, 46.50 +CTUN, 770, 0.48, 1.27, 0.000000, 0, 0, -12, 770, 0 +ATT, 0.00, 0.55, -2.52, 0.92, 0.00, 44.58, 46.50 +CTUN, 770, 0.48, 1.35, 0.000000, 0, 0, -13, 771, 0 +ATT, 0.00, 0.35, -2.42, 0.70, 0.00, 44.73, 46.50 +CTUN, 771, 0.47, 1.27, 0.000000, 0, 0, -17, 771, 0 +ATT, 0.00, 0.22, -2.52, 0.21, 0.00, 44.96, 46.50 +CTUN, 770, 0.47, 1.36, 0.000000, 0, 0, -22, 771, 0 +ATT, 0.00, 0.10, -3.26, -0.17, 0.00, 45.30, 46.50 +CTUN, 771, 0.44, 1.21, 0.000000, 0, 0, -24, 770, 0 +ATT, 0.00, 0.02, -6.16, -0.56, 0.00, 45.83, 46.50 +CTUN, 771, 0.44, 1.18, 0.000000, 0, 0, -29, 770, 0 +ATT, 0.00, -0.40, -6.81, -1.96, 0.00, 46.40, 46.50 +DU32, 7, 166140 +CURR, 771, 783784, 1010, 2063, 5028, 591.523440 +CTUN, 771, 0.40, 1.08, 0.000000, 0, 0, -32, 771, 0 +ATT, -1.42, -1.00, -6.53, -3.66, 0.00, 47.06, 46.50 +CTUN, 771, 0.40, 0.98, 0.000000, 0, 1, -33, 771, 0 +ATT, -3.69, -1.42, -5.32, -4.58, 0.00, 47.83, 46.50 +CTUN, 771, 0.35, 1.00, 0.000000, 0, 2, -33, 773, 0 +ATT, -3.88, -2.92, -3.82, -4.56, 0.00, 48.74, 46.50 +CTUN, 771, 0.35, 0.92, 0.000000, 0, 2, -31, 773, 0 +ATT, -2.36, -4.30, -20.91, -3.43, 0.00, 49.61, 46.50 +CTUN, 771, 0.28, 0.91, 0.000000, 0, 2, -27, 773, 0 +ATT, -1.61, -4.22, -3.73, -2.43, 0.00, 50.43, 46.50 +CTUN, 771, 0.28, 1.00, 0.000000, 0, 2, -25, 773, 0 +ATT, -1.23, -2.73, -4.10, -2.52, 0.00, 51.12, 46.50 +CTUN, 770, 0.22, 0.80, 0.000000, 0, 0, -18, 770, 0 +ATT, -0.47, -1.57, -4.10, -2.11, 0.00, 51.38, 46.50 +CTUN, 770, 0.22, 0.71, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, -1.22, -4.20, -2.30, 0.00, 51.40, 46.50 +CTUN, 771, 0.20, 0.71, 0.000000, 0, 0, -7, 771, 0 +ATT, 0.00, -0.53, -3.17, -2.50, 0.00, 51.22, 46.50 +CTUN, 771, 0.20, 0.58, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -0.29, -3.08, -1.92, 0.00, 50.55, 46.50 +DU32, 7, 166140 +CURR, 771, 791502, 1020, 2082, 5028, 597.355040 +CTUN, 770, 0.20, 0.63, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, -0.67, -2.61, -0.40, 0.00, 49.67, 46.50 +CTUN, 771, 0.20, 0.62, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -1.36, -2.42, 0.87, 0.00, 48.79, 46.50 +CTUN, 771, 0.20, 0.69, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, -1.39, -2.42, 1.25, 0.00, 47.96, 46.50 +CTUN, 771, 0.20, 0.68, 0.000000, 0, 0, 19, 770, 0 +ATT, 0.00, -1.12, -2.52, 0.69, 0.00, 47.20, 46.50 +CTUN, 771, 0.20, 0.89, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.00, -1.00, -2.52, 0.15, 0.00, 46.44, 46.50 +CTUN, 771, 0.20, 0.93, 0.000000, 0, 0, 19, 771, 0 +ATT, 0.00, -0.94, -3.17, -0.03, 0.00, 45.73, 46.50 +CTUN, 771, 0.20, 0.91, 0.000000, 0, 0, 23, 771, 0 +ATT, 0.00, -0.30, -3.92, -0.03, 0.00, 45.20, 46.50 +CTUN, 771, 0.23, 0.93, 0.000000, 0, 0, 23, 770, 0 +ATT, 0.00, 0.04, -4.20, -0.47, 0.00, 44.92, 46.50 +CTUN, 771, 0.23, 0.92, 0.000000, 0, 0, 21, 771, 0 +ATT, 0.00, -0.19, -4.20, -1.39, 0.00, 44.75, 46.50 +CTUN, 770, 0.27, 0.99, 0.000000, 0, 0, 17, 770, 0 +ATT, 0.00, 0.33, -4.10, -2.10, 0.00, 44.59, 46.50 +DU32, 7, 166140 +CURR, 770, 799209, 1015, 2088, 5051, 603.138430 +CTUN, 771, 0.27, 0.98, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.46, 0.76, -4.20, -2.21, 0.00, 44.29, 46.50 +CTUN, 771, 0.31, 1.05, 0.000000, 0, 0, 15, 771, 0 +ATT, 1.59, 0.41, -3.92, -1.45, 0.00, 43.78, 46.50 +CTUN, 771, 0.31, 0.99, 0.000000, 0, 0, 10, 771, 0 +ATT, 1.50, 0.98, -3.73, -0.81, 0.00, 43.29, 46.50 +CTUN, 771, 0.35, 0.94, 0.000000, 0, 0, 7, 771, 0 +ATT, 1.59, 1.73, -3.64, -0.31, 0.00, 42.94, 46.50 +CTUN, 770, 0.35, 0.99, 0.000000, 0, 0, 0, 770, 0 +ATT, 1.59, 2.08, -3.92, 0.35, 0.00, 42.60, 46.50 +CTUN, 770, 0.37, 1.19, 0.000000, 0, 0, -3, 771, 0 +ATT, 1.59, 2.41, -4.01, 0.18, 0.00, 42.26, 46.50 +CTUN, 771, 0.37, 1.00, 0.000000, 0, 0, -4, 771, 0 +ATT, 1.59, 1.90, -4.85, -0.40, 0.00, 41.86, 46.50 +CTUN, 771, 0.37, 1.04, 0.000000, 0, 0, -10, 771, 0 +ATT, 1.59, 1.59, -6.34, -1.29, 0.00, 41.46, 46.50 +CTUN, 771, 0.37, 0.93, 0.000000, 0, 0, -12, 770, 0 +ATT, 1.50, 1.84, -6.72, -1.63, 0.00, 41.07, 46.50 +CTUN, 770, 0.37, 1.17, 0.000000, 0, 0, -13, 771, 0 +ATT, 1.59, 2.70, -6.72, -1.41, 0.00, 40.60, 46.50 +DU32, 7, 166140 +CURR, 771, 806918, 1015, 2102, 5051, 608.950930 +CTUN, 771, 0.37, 1.08, 0.000000, 0, 1, -15, 771, 0 +ATT, 1.50, 3.49, -6.81, -1.24, 0.00, 40.25, 46.50 +CTUN, 770, 0.37, 1.10, 0.000000, 0, 1, -17, 772, 0 +ATT, 1.59, 3.91, -6.72, -1.40, 0.00, 40.19, 46.50 +CTUN, 770, 0.34, 1.09, 0.000000, 0, 1, -19, 771, 0 +ATT, 1.59, 3.75, -6.81, -2.34, 0.00, 40.48, 46.50 +CTUN, 771, 0.34, 0.99, 0.000000, 0, 1, -17, 772, 0 +ATT, 1.50, 3.14, -6.81, -3.70, 0.00, 41.26, 46.50 +CTUN, 771, 0.31, 0.99, 0.000000, 0, 2, -19, 773, 0 +ATT, 0.00, 2.40, -6.72, -4.51, 0.00, 42.26, 46.50 +CTUN, 771, 0.31, 0.95, 0.000000, 0, 2, -16, 773, 0 +ATT, 0.00, 0.96, -6.06, -4.26, 0.00, 43.29, 46.50 +CTUN, 770, 0.29, 0.83, 0.000000, 0, 1, -15, 772, 0 +ATT, 0.00, -0.49, -4.38, -3.55, 0.00, 44.03, 46.50 +CTUN, 771, 0.29, 0.96, 0.000000, 0, 1, -10, 771, 0 +ATT, 0.00, -0.63, -3.08, -1.72, 0.00, 44.62, 46.50 +CTUN, 771, 0.27, 0.89, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, -1.08, -3.17, 0.18, 0.00, 45.07, 46.50 +CTUN, 770, 0.27, 1.05, 0.000000, 0, 0, -7, 771, 0 +ATT, 0.00, -1.72, -4.10, 1.55, 0.00, 45.35, 46.50 +DU32, 7, 166140 +CURR, 770, 814635, 1023, 2096, 5051, 614.819150 +CTUN, 771, 0.26, 0.93, 0.000000, 0, 0, -4, 770, 0 +ATT, 0.00, -1.13, -4.85, 1.93, 0.00, 45.60, 46.50 +CTUN, 771, 0.26, 1.05, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, -0.78, -5.50, 1.05, 0.00, 45.80, 46.50 +CTUN, 771, 0.26, 1.05, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.66, -6.16, -0.35, 0.00, 45.95, 46.50 +CTUN, 770, 0.26, 0.97, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, -0.30, -6.81, -1.66, 0.00, 46.03, 46.50 +CTUN, 771, 0.26, 0.95, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, -0.03, -6.81, -1.76, 0.00, 45.98, 46.50 +CTUN, 770, 0.26, 0.84, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, -0.08, -6.62, -1.65, 0.00, 45.96, 46.50 +CTUN, 771, 0.26, 1.02, 0.000000, 0, 0, 2, 770, 0 +ATT, 0.00, -0.01, -6.53, -2.02, 0.00, 46.04, 46.50 +CTUN, 771, 0.27, 0.94, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, -0.17, -6.53, -2.35, 0.00, 46.05, 46.50 +CTUN, 771, 0.27, 1.01, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.18, -6.62, -2.00, 0.00, 45.98, 46.50 +CTUN, 771, 0.27, 1.03, 0.000000, 0, 0, 1, 770, 0 +ATT, 0.00, 0.46, -6.72, -1.96, 0.00, 45.82, 46.50 +DU32, 7, 166140 +CURR, 771, 822341, 1012, 2104, 5028, 620.679630 +CTUN, 771, 0.27, 1.04, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, 0.87, -6.72, -2.28, 0.00, 45.44, 46.50 +CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, 1.52, -6.72, -2.82, 0.00, 44.88, 46.50 +CTUN, 771, 0.28, 0.98, 0.000000, 0, 1, -6, 772, 0 +ATT, 0.00, 1.56, -6.81, -3.03, 0.00, 44.25, 46.50 +CTUN, 771, 0.29, 0.96, 0.000000, 0, 1, -5, 772, 0 +ATT, 0.00, 1.32, -6.81, -2.71, 0.00, 43.57, 46.50 +CTUN, 771, 0.29, 1.02, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, 1.46, -6.72, -2.67, 0.00, 42.75, 46.50 +CTUN, 770, 0.29, 0.88, 0.000000, 0, 0, -11, 770, 0 +ATT, 0.00, 1.33, -6.62, -2.16, 0.00, 41.89, 46.50 +CTUN, 771, 0.29, 1.07, 0.000000, 0, 0, -13, 771, 0 +ATT, 0.00, 1.21, -6.53, -1.96, 0.00, 41.25, 46.50 +CTUN, 770, 0.29, 0.82, 0.000000, 0, 0, -11, 770, 0 +ATT, 0.00, 1.70, -6.53, -2.62, 0.00, 40.86, 46.50 +CTUN, 770, 0.28, 0.99, 0.000000, 0, 1, -13, 772, 0 +ATT, 0.00, 1.62, -6.53, -3.03, 0.00, 40.68, 46.50 +CTUN, 771, 0.28, 0.95, 0.000000, 0, 1, -13, 772, 0 +ATT, -1.04, -0.13, -6.53, -3.60, 0.00, 40.79, 46.50 +DU32, 7, 166140 +CURR, 770, 830055, 1015, 2110, 5028, 626.495730 +CTUN, 771, 0.28, 0.98, 0.000000, 0, 1, -11, 772, 0 +ATT, -2.17, -1.90, -5.69, -3.86, 0.00, 41.05, 46.50 +CTUN, 771, 0.28, 1.02, 0.000000, 0, 1, -7, 771, 0 +ATT, -3.22, -2.20, -3.17, -3.59, 0.00, 41.24, 46.50 +CTUN, 771, 0.27, 1.07, 0.000000, 0, 1, -5, 772, 0 +ATT, -3.78, -2.67, -3.73, -2.08, 0.00, 41.38, 46.50 +CTUN, 771, 0.27, 0.95, 0.000000, 0, 1, -3, 771, 0 +ATT, -2.93, -3.84, -2.89, -0.79, 0.00, 41.54, 46.50 +CTUN, 771, 0.27, 1.01, 0.000000, 0, 1, 0, 772, 0 +ATT, -2.65, -4.48, -2.61, -0.06, 0.00, 41.82, 46.50 +CTUN, 771, 0.27, 0.99, 0.000000, 0, 1, -1, 772, 0 +ATT, -2.27, -3.33, -2.24, -0.03, 0.00, 42.07, 46.50 +CTUN, 771, 0.27, 1.05, 0.000000, 0, 0, 0, 770, 0 +ATT, -0.75, -1.44, -2.70, 0.30, 0.00, 42.35, 46.50 +CTUN, 771, 0.27, 0.99, 0.000000, 0, 0, -1, 771, 0 +PM, 0, 0, 0, 0, 1001, 10488, 0, 0 +ATT, 0.00, -1.05, -2.52, 0.77, 0.00, 42.76, 46.50 +CTUN, 771, 0.27, 1.18, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.01, -2.24, 1.03, 0.00, 43.20, 46.50 +CTUN, 770, 0.27, 0.88, 0.000000, 0, 0, -5, 770, 0 +ATT, 0.00, 1.43, -2.52, 1.13, 0.00, 43.61, 46.50 +DU32, 7, 166140 +CURR, 771, 837768, 1013, 2075, 5028, 632.331120 +CTUN, 771, 0.26, 0.90, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, 1.11, -2.52, 1.22, 0.00, 44.06, 46.50 +CTUN, 771, 0.26, 1.03, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, 0.13, -2.52, 0.89, 0.00, 44.51, 46.50 +CTUN, 771, 0.26, 0.95, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.46, -2.61, -0.39, 0.00, 45.15, 46.50 +CTUN, 770, 0.26, 1.01, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.57, -2.52, -1.18, 0.00, 45.67, 46.50 +CTUN, 770, 0.25, 1.12, 0.000000, 0, 0, 2, 771, 0 +ATT, -1.13, -0.51, -20.91, -1.14, 0.00, 46.09, 46.50 +CTUN, 771, 0.25, 1.10, 0.000000, 0, 0, 3, 771, 0 +ATT, -0.66, -0.68, -2.61, -1.21, 0.00, 46.31, 46.50 +CTUN, 771, 0.25, 0.94, 0.000000, 0, 0, 3, 771, 0 +ATT, -0.75, -1.10, -2.70, -1.37, 0.00, 46.38, 46.50 +CTUN, 771, 0.25, 1.04, 0.000000, 0, 0, 4, 771, 0 +ATT, -0.75, -1.73, -2.61, -1.79, 0.00, 46.42, 46.50 +CTUN, 770, 0.25, 0.87, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -2.42, -2.70, -2.04, 0.00, 46.53, 46.50 +CTUN, 771, 0.26, 1.13, 0.000000, 0, 1, 5, 772, 0 +ATT, 0.00, -2.47, -2.70, -1.63, 0.00, 46.65, 46.50 +DU32, 7, 166140 +CURR, 770, 845478, 1020, 2076, 5051, 638.134460 +CTUN, 770, 0.26, 1.05, 0.000000, 0, 0, 8, 770, 0 +ATT, 0.00, -1.16, -2.70, -0.29, 0.00, 46.82, 46.50 +CTUN, 770, 0.27, 1.05, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.00, -0.11, -2.61, 0.78, 0.00, 47.15, 46.50 +CTUN, 770, 0.27, 0.98, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.37, -2.70, 0.66, 0.00, 47.54, 46.50 +CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.28, -2.70, -0.13, 0.00, 47.84, 46.50 +CTUN, 771, 0.28, 1.07, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, -0.01, -2.70, -0.52, 0.00, 48.13, 46.50 +CTUN, 771, 0.29, 1.02, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.12, -2.70, -1.11, 0.00, 48.42, 46.50 +CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, -0.52, -2.70, -1.91, 0.00, 48.50, 46.50 +CTUN, 771, 0.28, 0.96, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, -0.64, -2.52, -1.97, 0.00, 48.25, 46.50 +CTUN, 771, 0.28, 1.05, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.48, -2.61, -1.26, 0.00, 47.98, 46.50 +CTUN, 770, 0.28, 1.04, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 0.33, -2.70, -0.59, 0.00, 47.59, 46.50 +DU32, 7, 166140 +CURR, 770, 853185, 1018, 2086, 5051, 643.938420 +CTUN, 770, 0.28, 1.08, 0.000000, 0, 0, 2, 770, 0 +ATT, 0.00, -0.24, -2.70, -0.61, 0.00, 47.15, 46.50 +CTUN, 771, 0.28, 0.94, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, -1.04, -2.70, -0.50, 0.00, 46.79, 46.50 +CTUN, 771, 0.28, 1.12, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -0.95, -2.61, -0.18, 0.00, 46.42, 46.50 +CTUN, 771, 0.28, 1.11, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.54, -2.70, -0.15, 0.00, 46.08, 46.50 +CTUN, 771, 0.28, 1.05, 0.000000, 0, 0, 1, 770, 0 +ATT, 0.00, 1.12, -2.70, -0.83, 0.00, 45.98, 46.50 +CTUN, 771, 0.28, 1.05, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.58, -2.70, -1.30, 0.00, 46.12, 46.50 +CTUN, 771, 0.28, 1.02, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, 0.65, -2.80, -1.77, 0.00, 46.43, 46.50 +CTUN, 771, 0.28, 1.06, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 1.39, -2.70, -1.79, 0.00, 46.59, 46.50 +CTUN, 771, 0.28, 1.14, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 1.21, -2.61, -1.31, 0.00, 46.77, 46.50 +CTUN, 771, 0.28, 1.26, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.43, -2.70, -0.62, 0.00, 47.28, 46.50 +DU32, 7, 166140 +CURR, 770, 860891, 1016, 2102, 5051, 649.724790 +CTUN, 770, 0.28, 1.17, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, -0.20, -2.61, -0.24, 0.00, 48.04, 46.50 +CTUN, 771, 0.28, 1.12, 0.000000, 0, 0, -1, 770, 0 +ATT, 0.00, -0.11, -2.70, -0.71, 0.00, 48.95, 46.50 +CTUN, 770, 0.28, 0.96, 0.000000, 0, 0, -2, 770, 0 +ATT, 0.00, 0.13, -2.61, -1.50, 0.00, 49.80, 46.50 +CTUN, 771, 0.28, 1.00, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.02, -2.61, -1.72, 0.00, 50.39, 46.50 +CTUN, 771, 0.28, 1.13, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.51, -2.70, -1.59, 0.00, 50.57, 46.50 +CTUN, 771, 0.29, 1.09, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -0.53, -2.70, -1.18, 0.00, 50.38, 46.50 +CTUN, 771, 0.29, 1.18, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, 0.06, -2.70, -0.41, 0.00, 49.81, 46.50 +CTUN, 771, 0.29, 1.09, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, 0.39, -2.61, 0.13, 0.00, 49.05, 46.50 +CTUN, 770, 0.28, 1.05, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.00, -0.67, -2.89, -0.34, 0.00, 48.14, 46.50 +CTUN, 771, 0.28, 0.94, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, -1.94, -2.70, -1.10, 0.00, 47.16, 46.50 +DU32, 7, 166140 +CURR, 770, 868600, 1011, 2058, 5051, 655.494930 +CTUN, 771, 0.28, 1.06, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, -1.99, -2.61, -1.26, 0.00, 46.24, 46.50 +CTUN, 771, 0.28, 1.08, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -2.09, -2.89, -0.64, 0.00, 45.42, 46.50 +CTUN, 771, 0.27, 1.08, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.00, -1.23, -2.70, -0.37, 0.00, 44.96, 46.50 +CTUN, 771, 0.27, 1.09, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.84, -2.70, -0.50, 0.00, 44.88, 46.50 +CTUN, 771, 0.26, 1.04, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.15, -3.08, -0.94, 0.00, 44.99, 46.50 +CTUN, 770, 0.26, 1.00, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, 0.94, -3.64, -0.94, 0.00, 45.21, 46.50 +CTUN, 771, 0.26, 1.15, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, 1.12, -3.92, -1.12, 0.00, 45.54, 46.50 +CTUN, 771, 0.26, 1.15, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 0.53, -4.76, -1.64, 0.00, 45.94, 46.50 +CTUN, 770, 0.26, 1.10, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, 0.28, -4.76, -2.70, 0.00, 46.38, 46.50 +CTUN, 771, 0.26, 0.95, 0.000000, 0, 0, 5, 770, 0 +ATT, 0.00, 0.42, -4.76, -3.30, 0.00, 46.89, 46.50 +DU32, 7, 166140 +CURR, 770, 876308, 1008, 2093, 5051, 661.290470 +CTUN, 771, 0.26, 1.07, 0.000000, 0, 1, 7, 772, 0 +ATT, 0.00, 0.84, -4.76, -2.96, 0.00, 47.44, 46.50 +CTUN, 770, 0.27, 1.07, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, 0.26, -4.57, -2.58, 0.00, 47.98, 46.50 +CTUN, 770, 0.27, 1.07, 0.000000, 0, 0, 8, 770, 0 +ATT, 0.00, -0.67, -4.85, -2.31, 0.00, 48.51, 46.50 +CTUN, 771, 0.29, 1.14, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, -1.63, -4.76, -2.06, 0.00, 48.84, 46.50 +CTUN, 770, 0.29, 1.03, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, -1.79, -4.76, -2.06, 0.00, 48.92, 46.50 +CTUN, 770, 0.31, 1.13, 0.000000, 0, 0, 5, 770, 0 +ATT, 0.00, -1.13, -4.85, -2.42, 0.00, 48.88, 46.50 +CTUN, 770, 0.31, 1.09, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.00, -0.40, -4.76, -2.37, 0.00, 48.76, 46.50 +CTUN, 771, 0.32, 1.07, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 0.30, -4.57, -2.24, 0.00, 48.81, 46.50 +CTUN, 771, 0.32, 1.10, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.11, -4.85, -1.82, 0.00, 48.95, 46.50 +CTUN, 771, 0.33, 1.22, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.78, -4.57, -1.07, 0.00, 49.19, 46.50 +DU32, 7, 166140 +CURR, 770, 884015, 1020, 2108, 5051, 667.150390 +CTUN, 770, 0.33, 1.13, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, -0.88, -4.57, -1.26, 0.00, 49.48, 46.50 +CTUN, 770, 0.34, 1.13, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.14, -4.48, -2.18, 0.00, 49.92, 46.50 +CTUN, 770, 0.34, 1.29, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, 0.35, -4.57, -2.08, 0.00, 50.23, 46.50 +CTUN, 771, 0.35, 1.25, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.00, 0.15, -4.57, -1.46, 0.00, 50.36, 46.50 +CTUN, 771, 0.35, 1.19, 0.000000, 0, 0, -5, 771, 0 +ATT, 0.00, -0.21, -4.57, -0.73, 0.00, 50.21, 46.50 +CTUN, 771, 0.36, 1.23, 0.000000, 0, 0, -5, 771, 0 +ATT, 0.00, -0.45, -4.57, -0.13, 0.00, 49.79, 46.50 +CTUN, 771, 0.36, 1.36, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, -0.81, -4.48, -0.19, 0.00, 49.22, 46.50 +CTUN, 770, 0.36, 1.31, 0.000000, 0, 0, -8, 770, 0 +ATT, 0.00, -1.24, -4.57, -0.52, 0.00, 48.56, 46.50 +CTUN, 771, 0.35, 1.20, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, -0.99, -4.57, -0.74, 0.00, 47.81, 46.50 +CTUN, 770, 0.35, 1.25, 0.000000, 0, 0, -10, 770, 0 +ATT, 0.00, -0.51, -4.57, -0.64, 0.00, 47.16, 46.50 +DU32, 7, 166140 +CURR, 771, 891724, 1019, 2092, 5028, 672.946110 +CTUN, 771, 0.33, 1.18, 0.000000, 0, 0, -11, 771, 0 +ATT, 0.00, -0.56, -4.57, -0.73, 0.00, 46.92, 46.50 +CTUN, 771, 0.33, 1.19, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.00, -0.83, -4.57, -1.09, 0.00, 46.97, 46.50 +CTUN, 771, 0.32, 1.26, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.28, -0.92, -4.57, -1.51, 0.00, 47.13, 46.50 +CTUN, 771, 0.32, 1.17, 0.000000, 0, 0, -11, 771, 0 +ATT, 0.37, -0.41, -4.48, -1.53, 0.00, 47.31, 46.50 +CTUN, 771, 0.30, 1.18, 0.000000, 0, 0, -11, 771, 0 +ATT, 0.84, 0.56, -4.57, -1.27, 0.00, 47.54, 46.50 +CTUN, 771, 0.30, 1.09, 0.000000, 0, 0, -8, 771, 0 +ATT, 1.78, 1.39, -4.48, -0.93, 0.00, 47.64, 46.50 +CTUN, 770, 0.28, 1.13, 0.000000, 0, 0, -7, 770, 0 +ATT, 1.87, 2.06, -4.38, -0.86, 0.00, 47.67, 46.50 +CTUN, 771, 0.28, 1.11, 0.000000, 0, 0, -6, 771, 0 +ATT, 1.96, 2.75, -4.38, -1.15, 0.00, 47.75, 46.50 +CTUN, 771, 0.26, 1.01, 0.000000, 0, 1, -5, 772, 0 +ATT, 1.96, 2.52, -4.38, -2.24, 0.00, 47.78, 46.50 +CTUN, 770, 0.26, 0.99, 0.000000, 0, 1, -6, 771, 0 +ATT, 1.96, 1.71, -4.38, -3.36, 0.00, 47.65, 46.50 +DU32, 7, 166140 +CURR, 770, 899431, 1009, 2092, 5051, 678.761660 +CTUN, 770, 0.25, 1.00, 0.000000, 0, 1, -1, 772, 0 +ATT, 1.96, 1.44, -4.38, -3.41, 0.00, 47.48, 46.50 +CTUN, 771, 0.25, 0.96, 0.000000, 0, 1, 0, 772, 0 +ATT, 1.78, 1.30, -4.38, -2.47, 0.00, 47.40, 46.50 +CTUN, 771, 0.24, 1.07, 0.000000, 0, 0, 1, 770, 0 +ATT, 1.78, 0.95, -4.48, -1.28, 0.00, 47.32, 46.50 +CTUN, 771, 0.25, 0.97, 0.000000, 0, 0, 2, 771, 0 +ATT, 1.31, 0.56, -4.57, -0.68, 0.00, 47.31, 46.50 +CTUN, 771, 0.25, 0.98, 0.000000, 0, 0, 0, 771, 0 +ATT, 1.03, 1.01, -4.57, -0.59, 0.00, 47.32, 46.50 +CTUN, 770, 0.25, 1.08, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.65, 0.77, -4.48, -0.98, 0.00, 47.38, 46.50 +CTUN, 770, 0.24, 1.01, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.09, 0.65, -4.57, -1.50, 0.00, 47.43, 46.50 +CTUN, 771, 0.25, 1.10, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 1.05, -4.38, -1.41, 0.00, 47.52, 46.50 +CTUN, 771, 0.25, 1.05, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, 1.28, -4.85, -0.74, 0.00, 47.66, 46.50 +CTUN, 771, 0.26, 1.20, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 1.19, -4.76, -0.12, 0.00, 47.75, 46.50 +DU32, 7, 166140 +CURR, 771, 907141, 1006, 2123, 5051, 684.602050 +CTUN, 771, 0.26, 1.14, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.00, 0.82, -4.76, -0.94, 0.00, 47.74, 46.50 +CTUN, 771, 0.27, 1.10, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.40, -5.69, -1.52, 0.00, 47.68, 46.50 +CTUN, 771, 0.27, 1.08, 0.000000, 0, 0, 5, 770, 0 +ATT, 0.00, -0.51, -6.25, -1.76, 0.00, 47.59, 46.50 +CTUN, 771, 0.28, 1.22, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -1.17, -6.06, -1.86, 0.00, 47.61, 46.50 +CTUN, 770, 0.28, 1.12, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -1.53, -6.06, -1.97, 0.00, 47.53, 46.50 +CTUN, 771, 0.30, 1.22, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -1.22, -6.06, -2.16, 0.00, 47.15, 46.50 +CTUN, 770, 0.30, 1.08, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -1.18, -6.06, -2.48, 0.00, 46.63, 46.50 +CTUN, 771, 0.30, 1.09, 0.000000, 0, 0, -3, 771, 0 +PM, 0, 0, 0, 0, 1000, 10484, 0, 0 +ATT, 0.00, -1.21, -6.16, -2.52, 0.00, 46.08, 46.50 +CTUN, 771, 0.30, 1.21, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.00, -0.77, -5.04, -2.21, 0.00, 45.48, 46.50 +CTUN, 771, 0.30, 1.17, 0.000000, 0, 0, -6, 771, 0 +ATT, -0.09, -0.29, -4.85, -2.16, 0.00, 45.05, 46.50 +DU32, 7, 166140 +CURR, 771, 914848, 1018, 2088, 5051, 690.416750 +CTUN, 771, 0.29, 1.17, 0.000000, 0, 0, -6, 770, 0 +ATT, -0.18, -0.25, -5.04, -2.13, 0.00, 44.61, 46.50 +CTUN, 771, 0.29, 1.00, 0.000000, 0, 0, -8, 770, 0 +ATT, -0.18, -0.44, -5.04, -2.25, 0.00, 44.33, 46.50 +CTUN, 771, 0.28, 1.04, 0.000000, 0, 0, -11, 771, 0 +ATT, -0.18, -0.60, -5.04, -2.31, 0.00, 44.14, 46.50 +CTUN, 771, 0.28, 1.01, 0.000000, 0, 0, -11, 770, 0 +ATT, -0.18, -1.08, -5.04, -2.78, 0.00, 44.07, 46.50 +CTUN, 770, 0.26, 1.10, 0.000000, 0, 0, -13, 771, 0 +ATT, -0.18, -0.55, -4.76, -2.54, 0.00, 44.02, 46.50 +CTUN, 771, 0.26, 1.05, 0.000000, 0, 0, -8, 771, 0 +ATT, -0.18, 0.35, -4.85, -1.63, 0.00, 43.92, 46.50 +CTUN, 770, 0.25, 1.08, 0.000000, 0, 0, -7, 771, 0 +ATT, 0.00, 0.64, -4.85, -1.05, 0.00, 44.04, 46.50 +CTUN, 771, 0.25, 1.00, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, 0.07, -4.76, -1.23, 0.00, 44.39, 46.50 +CTUN, 770, 0.23, 1.05, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, -0.60, -4.85, -1.87, 0.00, 44.86, 46.50 +CTUN, 771, 0.23, 1.04, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, -0.22, -4.85, -1.94, 0.00, 45.44, 46.50 +DU32, 7, 166140 +CURR, 771, 922554, 1013, 2060, 5028, 696.159300 +CTUN, 770, 0.22, 1.11, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.00, -0.17, -4.76, -1.44, 0.00, 46.20, 46.50 +CTUN, 771, 0.22, 1.07, 0.000000, 0, 0, 1, 770, 0 +ATT, 0.00, -0.30, -4.76, -1.28, 0.00, 47.03, 46.50 +CTUN, 771, 0.21, 0.99, 0.000000, 0, 0, 2, 771, 0 +ATT, -0.75, -0.13, -2.52, -1.18, 0.00, 47.87, 46.50 +CTUN, 771, 0.21, 1.01, 0.000000, 0, 0, 5, 771, 0 +ATT, -0.75, -0.16, -2.61, -0.63, 0.00, 48.59, 46.50 +CTUN, 771, 0.21, 1.13, 0.000000, 0, 0, 8, 770, 0 +ATT, -0.75, -0.43, -2.70, 0.07, 0.00, 49.09, 46.50 +CTUN, 770, 0.22, 1.07, 0.000000, 0, 0, 8, 771, 0 +ATT, -0.75, -0.26, -2.61, 0.24, 0.00, 49.48, 46.50 +CTUN, 771, 0.22, 0.94, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, 0.06, -2.61, 0.41, 0.00, 49.67, 46.50 +CTUN, 771, 0.23, 1.15, 0.000000, 0, 0, 11, 770, 0 +ATT, 0.00, -0.21, -2.61, 0.29, 0.00, 49.79, 46.50 +CTUN, 771, 0.23, 1.23, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, -0.03, -3.08, -0.10, 0.00, 49.88, 46.50 +CTUN, 770, 0.23, 1.25, 0.000000, 0, 0, 11, 771, 0 +ATT, -0.75, 0.88, -3.08, -0.47, 0.00, 50.00, 46.50 +DU32, 7, 166140 +CURR, 771, 930261, 1010, 2098, 5051, 701.952940 +CTUN, 771, 0.23, 1.11, 0.000000, 0, 0, 11, 771, 0 +ATT, -0.85, 1.22, -3.26, -0.94, 0.00, 50.06, 46.50 +CTUN, 770, 0.25, 1.16, 0.000000, 0, 0, 11, 771, 0 +ATT, -2.17, 0.50, -3.92, -1.96, 0.00, 50.08, 46.50 +CTUN, 771, 0.25, 1.19, 0.000000, 0, 0, 9, 770, 0 +ATT, -2.36, -0.88, -4.10, -2.55, 0.00, 50.03, 46.50 +CTUN, 771, 0.27, 1.11, 0.000000, 0, 0, 9, 771, 0 +ATT, -2.17, -1.81, -4.10, -2.33, 0.00, 49.68, 46.50 +CTUN, 771, 0.27, 1.15, 0.000000, 0, 0, 6, 771, 0 +ATT, -2.27, -1.90, -4.01, -1.68, 0.00, 49.18, 46.50 +CTUN, 770, 0.28, 1.20, 0.000000, 0, 0, 6, 770, 0 +ATT, -2.36, -2.01, -2.33, -0.74, 0.00, 48.58, 46.50 +CTUN, 770, 0.28, 1.21, 0.000000, 0, 0, 6, 771, 0 +ATT, -2.36, -1.94, -2.33, 0.02, 0.00, 47.97, 46.50 +CTUN, 771, 0.28, 1.15, 0.000000, 0, 0, 3, 770, 0 +ATT, -2.36, -1.86, -2.33, 0.19, 0.00, 47.46, 46.50 +CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, 1, 771, 0 +ATT, -2.36, -1.23, -2.33, -0.40, 0.00, 47.11, 46.50 +CTUN, 771, 0.28, 1.14, 0.000000, 0, 0, 2, 771, 0 +ATT, -1.98, -1.10, -1.96, -0.69, 0.00, 46.89, 46.50 +DU32, 7, 166140 +CURR, 771, 937968, 1013, 2056, 5051, 707.722410 +CTUN, 771, 0.28, 1.24, 0.000000, 0, 0, 4, 771, 0 +ATT, -1.13, -1.33, -3.26, -0.52, 0.00, 46.77, 46.50 +CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, 3, 771, 0 +ATT, -0.75, -1.52, -3.64, -0.61, 0.00, 46.83, 46.50 +CTUN, 771, 0.27, 1.22, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -1.10, -3.73, -1.05, 0.00, 47.09, 46.50 +CTUN, 770, 0.27, 1.09, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -0.27, -3.73, -1.61, 0.00, 47.65, 46.50 +CTUN, 771, 0.27, 1.09, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.37, -3.82, -2.01, 0.00, 48.51, 46.50 +CTUN, 771, 0.28, 1.11, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, 0.69, -3.26, -1.63, 0.00, 49.43, 46.50 +CTUN, 770, 0.28, 1.20, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 0.32, -3.26, -1.22, 0.00, 50.46, 46.50 +CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, -0.11, -3.17, -0.89, 0.00, 51.43, 46.50 +CTUN, 771, 0.28, 1.32, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -0.51, -3.08, -0.79, 0.00, 52.33, 46.50 +CTUN, 771, 0.28, 1.21, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.50, -3.17, -1.23, 0.00, 52.97, 46.50 +DU32, 7, 166140 +CURR, 771, 945675, 1013, 2123, 5051, 713.567750 +CTUN, 771, 0.28, 1.13, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, 0.75, -3.17, -1.73, 0.00, 53.32, 46.50 +CTUN, 771, 0.28, 1.20, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, 1.14, -3.26, -1.16, 0.00, 53.58, 46.50 +CTUN, 771, 0.27, 1.23, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.32, -2.70, -0.56, 0.00, 53.62, 46.50 +CTUN, 771, 0.27, 1.15, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, -0.33, -2.70, -0.70, 0.00, 53.43, 46.50 +CTUN, 771, 0.27, 1.30, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, -0.79, -2.61, -0.79, 0.00, 53.05, 46.50 +CTUN, 771, 0.27, 1.23, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -1.29, -2.70, -0.60, 0.00, 52.49, 46.50 +CTUN, 771, 0.26, 1.41, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.50, -2.70, -0.81, 0.00, 51.93, 46.50 +CTUN, 771, 0.26, 1.21, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, -0.19, -2.61, -0.24, 0.00, 51.33, 46.50 +CTUN, 771, 0.25, 1.24, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, -0.61, -2.61, -0.02, 0.00, 50.56, 46.50 +CTUN, 770, 0.25, 1.18, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -1.19, -2.70, -0.72, 0.00, 49.72, 46.50 +DU32, 7, 166140 +CURR, 770, 953383, 1018, 2094, 5051, 719.391720 +CTUN, 771, 0.25, 1.05, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, -1.61, -2.70, -1.89, 0.00, 48.97, 46.50 +CTUN, 770, 0.25, 1.16, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -1.58, -2.89, -2.20, 0.00, 48.46, 46.50 +CTUN, 770, 0.24, 1.08, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, -0.59, -2.70, -1.74, 0.00, 48.04, 46.50 +CTUN, 770, 0.25, 0.97, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -0.04, -2.80, -1.16, 0.00, 47.74, 46.50 +CTUN, 771, 0.24, 1.12, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -0.52, -2.80, -1.19, 0.00, 47.54, 46.50 +CTUN, 771, 0.24, 1.25, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, -0.75, -2.80, -1.48, 0.00, 47.45, 46.50 +CTUN, 771, 0.24, 1.21, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -1.42, -2.89, -1.70, 0.00, 47.36, 46.50 +CTUN, 770, 0.25, 1.24, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -2.16, -2.80, -1.46, 0.00, 47.11, 46.50 +CTUN, 771, 0.25, 1.25, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.28, -1.64, -2.80, -0.50, 0.00, 46.60, 46.50 +CTUN, 771, 0.26, 1.41, 0.000000, 0, 0, 5, 770, 0 +ATT, 0.46, -0.56, -2.80, 0.15, 0.00, 46.23, 46.50 +DU32, 7, 166140 +CURR, 770, 961091, 1018, 2084, 5051, 725.147890 +CTUN, 771, 0.26, 1.26, 0.000000, 0, 0, 5, 771, 0 +ATT, 2.34, -0.40, -2.80, 0.07, 0.00, 46.23, 46.50 +CTUN, 771, 0.26, 1.13, 0.000000, 0, 0, 3, 771, 0 +ATT, 2.90, -0.02, -2.80, -0.57, 0.00, 46.55, 46.50 +CTUN, 771, 0.26, 1.11, 0.000000, 0, 0, 3, 771, 0 +ATT, 3.28, 1.09, -2.89, -0.66, 0.00, 46.85, 46.50 +CTUN, 770, 0.27, 1.28, 0.000000, 0, 0, 5, 771, 0 +ATT, 3.56, 2.16, -2.80, -0.21, 0.00, 47.03, 46.50 +CTUN, 771, 0.27, 1.17, 0.000000, 0, 0, 3, 771, 0 +ATT, 3.56, 3.67, -2.89, -0.10, 0.00, 47.14, 46.50 +CTUN, 771, 0.27, 1.15, 0.000000, 0, 1, 1, 772, 0 +ATT, 3.65, 4.57, -2.70, -0.32, 0.00, 47.24, 46.50 +CTUN, 771, 0.27, 1.20, 0.000000, 0, 1, 0, 771, 0 +ATT, 3.84, 4.29, -2.70, -0.22, 0.00, 47.28, 46.50 +CTUN, 771, 0.28, 1.16, 0.000000, 0, 1, 0, 772, 0 +ATT, 3.93, 4.07, -2.61, 0.21, 0.00, 47.20, 46.50 +CTUN, 771, 0.28, 1.06, 0.000000, 0, 1, -1, 772, 0 +ATT, 3.93, 4.24, -2.89, 0.46, 0.00, 46.99, 46.50 +CTUN, 771, 0.29, 1.22, 0.000000, 0, 1, -2, 772, 0 +ATT, 3.46, 4.58, -2.89, 0.61, 0.00, 46.77, 46.50 +DU32, 7, 166140 +CURR, 771, 968805, 1008, 2097, 5051, 730.960750 +CTUN, 771, 0.29, 1.17, 0.000000, 0, 2, -5, 773, 0 +ATT, 3.09, 4.54, -3.17, 0.56, 0.00, 46.55, 46.50 +CTUN, 770, 0.29, 1.12, 0.000000, 0, 1, -5, 772, 0 +ATT, 1.40, 4.31, -3.26, 0.44, 0.00, 46.34, 46.50 +CTUN, 771, 0.29, 1.10, 0.000000, 0, 1, -10, 772, 0 +ATT, 0.00, 3.75, -3.26, 0.00, 0.00, 46.09, 46.50 +CTUN, 771, 0.29, 1.01, 0.000000, 0, 0, -14, 771, 0 +ATT, 0.00, 2.31, -3.26, -0.44, 0.00, 45.90, 46.50 +CTUN, 771, 0.29, 1.23, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.00, 1.33, -4.48, -0.94, 0.00, 45.77, 46.50 +CTUN, 771, 0.29, 1.13, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, 0.75, -4.85, -1.66, 0.00, 45.77, 46.50 +CTUN, 771, 0.28, 1.23, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, 0.04, -4.66, -2.34, 0.00, 45.90, 46.50 +CTUN, 771, 0.28, 1.10, 0.000000, 0, 0, -15, 771, 0 +ATT, -1.13, -0.75, -4.57, -2.72, 0.00, 46.26, 46.50 +CTUN, 771, 0.26, 1.13, 0.000000, 0, 0, -12, 771, 0 +ATT, -3.69, -1.37, -3.64, -2.88, 0.00, 46.69, 46.50 +CTUN, 771, 0.26, 1.10, 0.000000, 0, 1, -11, 772, 0 +ATT, -4.16, -3.06, -4.10, -2.99, 0.00, 47.29, 46.50 +DU32, 7, 166140 +CURR, 771, 976521, 1013, 2069, 5028, 736.742430 +CTUN, 771, 0.23, 1.00, 0.000000, 0, 2, -11, 772, 0 +ATT, -4.16, -4.87, -4.10, -2.61, 0.00, 47.76, 46.50 +CTUN, 770, 0.23, 1.01, 0.000000, 0, 3, -9, 773, 0 +ATT, -3.97, -5.34, -3.92, -2.10, 0.00, 48.08, 46.50 +CTUN, 771, 0.23, 1.23, 0.000000, 0, 2, -6, 773, 0 +ATT, -3.78, -4.56, -3.92, -1.93, 0.00, 48.23, 46.50 +CTUN, 770, 0.23, 1.27, 0.000000, 0, 1, -1, 772, 0 +ATT, -1.61, -3.52, -3.92, -1.36, 0.00, 48.13, 46.50 +CTUN, 770, 0.21, 1.10, 0.000000, 0, 1, 1, 772, 0 +ATT, 0.00, -2.55, -4.01, -0.86, 0.00, 47.91, 46.50 +CTUN, 771, 0.22, 1.12, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, -0.93, -4.10, -0.69, 0.00, 47.50, 46.50 +CTUN, 771, 0.22, 1.28, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, -0.04, -3.92, -1.04, 0.00, 47.05, 46.50 +CTUN, 770, 0.22, 1.03, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, 0.30, -4.01, -1.36, 0.00, 46.47, 46.50 +CTUN, 771, 0.22, 1.09, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, -0.02, -3.92, -1.75, 0.00, 45.91, 46.50 +CTUN, 771, 0.24, 1.15, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, -0.47, -3.92, -2.08, 0.00, 45.34, 46.50 +DU32, 7, 166140 +CURR, 771, 984240, 1019, 2083, 5051, 742.546080 +CTUN, 770, 0.24, 1.24, 0.000000, 0, 0, 12, 771, 0 +ATT, 0.00, -0.14, -4.10, -2.28, 0.00, 44.78, 46.50 +CTUN, 771, 0.27, 1.11, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 1.03, -4.20, -2.77, 0.00, 44.27, 46.50 +CTUN, 770, 0.27, 1.14, 0.000000, 0, 1, 6, 772, 0 +ATT, 0.00, 1.57, -4.20, -3.05, 0.00, 43.83, 46.50 +CTUN, 770, 0.29, 1.18, 0.000000, 0, 1, 5, 772, 0 +ATT, 0.00, 1.30, -4.20, -2.77, 0.00, 43.48, 46.50 +CTUN, 770, 0.29, 1.31, 0.000000, 0, 0, 2, 770, 0 +ATT, 0.00, 0.98, -4.20, -1.94, 0.00, 43.13, 46.50 +CTUN, 771, 0.31, 1.30, 0.000000, 0, 0, 1, 770, 0 +ATT, 0.00, 0.42, -3.92, -1.35, 0.00, 42.85, 46.50 +CTUN, 770, 0.31, 1.26, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, 0.49, -4.20, -0.88, 0.00, 42.61, 46.50 +CTUN, 770, 0.31, 1.34, 0.000000, 0, 0, -5, 771, 0 +PM, 0, 0, 0, 0, 1000, 10476, 0, 0 +ATT, 0.00, 0.88, -3.73, -0.36, 0.00, 42.34, 46.50 +CTUN, 771, 0.31, 1.34, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, 1.05, -3.17, 0.25, 0.00, 42.08, 46.50 +CTUN, 771, 0.31, 1.24, 0.000000, 0, 0, -9, 771, 0 +ATT, 0.00, 0.87, -3.08, 0.76, 0.00, 41.74, 46.50 +DU32, 7, 166140 +CURR, 770, 991949, 1013, 2063, 5028, 748.299620 +CTUN, 771, 0.31, 1.29, 0.000000, 0, 0, -11, 771, 0 +ATT, 0.00, 0.35, -3.26, 1.31, 0.00, 41.43, 46.50 +CTUN, 770, 0.31, 1.21, 0.000000, 0, 0, -13, 771, 0 +ATT, 0.00, 0.16, -3.26, 1.57, 0.00, 41.21, 46.50 +CTUN, 770, 0.31, 1.26, 0.000000, 0, 0, -14, 771, 0 +ATT, 0.00, 0.51, -3.26, 1.62, 0.00, 41.18, 46.50 +CTUN, 771, 0.31, 1.10, 0.000000, 0, 0, -16, 771, 0 +ATT, 0.00, 0.72, -4.38, 0.94, 0.00, 41.52, 46.50 +CTUN, 769, 0.29, 1.18, 0.000000, 0, 0, -18, 769, 0 +ATT, 0.00, 0.16, -4.48, -0.36, 0.00, 42.05, 46.50 +CTUN, 771, 0.29, 1.13, 0.000000, 0, 0, -20, 770, 0 +ATT, 0.00, -0.29, -4.85, -1.54, 0.00, 42.67, 46.50 +CTUN, 770, 0.26, 1.09, 0.000000, 0, 0, -20, 770, 0 +ATT, 0.00, -0.58, -4.85, -1.94, 0.00, 43.24, 46.50 +CTUN, 770, 0.26, 1.25, 0.000000, 0, 0, -19, 770, 0 +ATT, 0.00, -0.67, -4.85, -2.29, 0.00, 43.70, 46.50 +CTUN, 770, 0.24, 1.09, 0.000000, 0, 0, -17, 770, 0 +ATT, 0.00, -0.23, -4.85, -2.31, 0.00, 44.13, 46.50 +CTUN, 770, 0.24, 1.00, 0.000000, 0, 0, -15, 770, 0 +ATT, 0.00, 0.30, -4.85, -2.24, 0.00, 44.50, 46.50 +DU32, 7, 166140 +CURR, 770, 999651, 1015, 2058, 5051, 754.029660 +CTUN, 770, 0.22, 0.73, 0.000000, 0, 0, -14, 769, 0 +ATT, 0.00, 0.20, -4.76, -1.75, 0.00, 44.82, 46.50 +CTUN, 770, 0.22, 1.04, 0.000000, 0, 0, -12, 770, 0 +ATT, 0.00, 0.30, -4.76, -1.23, 0.00, 45.02, 46.50 +CTUN, 770, 0.20, 1.10, 0.000000, 0, 0, -14, 770, 0 +ATT, 0.00, 0.53, -4.76, -1.01, 0.00, 45.11, 46.50 +CTUN, 770, 0.20, 1.18, 0.000000, 0, 0, -12, 769, 0 +ATT, 0.00, 0.53, -4.76, -1.40, 0.00, 45.15, 46.50 +CTUN, 770, 0.20, 0.72, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, 0.55, -4.85, -1.58, 0.00, 45.17, 46.50 +CTUN, 770, 0.20, 0.72, 0.000000, 0, 0, -3, 770, 0 +ATT, 0.00, 0.31, -4.85, -1.41, 0.00, 45.21, 46.50 +CTUN, 770, 0.20, 1.13, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, 0.45, -4.76, -1.26, 0.00, 45.38, 46.50 +CTUN, 769, 0.20, 1.13, 0.000000, 0, 0, 2, 770, 0 +ATT, -0.37, 0.79, -4.57, -1.62, 0.00, 45.77, 46.50 +CTUN, 771, 0.20, 1.06, 0.000000, 0, 0, 4, 771, 0 +ATT, -0.75, 0.85, -4.57, -1.91, 0.00, 46.21, 46.50 +CTUN, 770, 0.20, 1.08, 0.000000, 0, 0, 3, 770, 0 +ATT, -0.94, 0.16, -4.48, -2.49, 0.00, 46.61, 46.50 +DU32, 7, 166140 +CURR, 771, 1007352, 1013, 2070, 5051, 759.753540 +CTUN, 770, 0.20, 1.10, 0.000000, 0, 0, 2, 771, 0 +ATT, -2.17, -0.25, -4.48, -3.37, 0.00, 47.10, 46.50 +CTUN, 770, 0.21, 1.18, 0.000000, 0, 1, 4, 771, 0 +ATT, -3.31, -1.31, -3.26, -3.36, 0.00, 47.45, 46.50 +CTUN, 769, 0.21, 1.27, 0.000000, 0, 1, 4, 771, 0 +ATT, -3.12, -2.60, -3.08, -2.21, 0.00, 47.58, 46.50 +CTUN, 770, 0.22, 1.23, 0.000000, 0, 1, 0, 771, 0 +ATT, -2.84, -2.84, -2.89, -0.87, 0.00, 47.32, 46.50 +CTUN, 771, 0.22, 1.32, 0.000000, 0, 0, 2, 771, 0 +ATT, -2.65, -2.33, -2.61, 0.01, 0.00, 46.89, 46.50 +CTUN, 769, 0.24, 1.25, 0.000000, 0, 0, -1, 770, 0 +ATT, -2.65, -1.74, -2.61, -0.19, 0.00, 46.43, 46.50 +CTUN, 771, 0.24, 1.32, 0.000000, 0, 0, -1, 771, 0 +ATT, -2.65, -1.64, -2.52, -0.81, 0.00, 46.17, 46.50 +CTUN, 770, 0.25, 1.38, 0.000000, 0, 0, 0, 770, 0 +ATT, -2.08, -2.17, -2.05, -1.14, 0.00, 46.08, 46.50 +CTUN, 771, 0.25, 1.36, 0.000000, 0, 0, -1, 770, 0 +ATT, -3.12, -1.71, -1.58, -1.02, 0.00, 46.09, 46.50 +CTUN, 770, 0.25, 1.35, 0.000000, 0, 0, -4, 771, 0 +ATT, -3.69, -0.61, -1.21, -0.22, 0.00, 46.15, 46.50 +DU32, 7, 166140 +CURR, 769, 1015058, 1015, 2034, 5051, 765.463130 +CTUN, 770, 0.25, 1.15, 0.000000, 0, 0, -7, 770, 0 +ATT, -3.03, -1.82, -1.21, 0.37, 0.00, 46.31, 46.50 +CTUN, 770, 0.26, 1.32, 0.000000, 0, 0, -9, 770, 0 +ATT, -1.23, -3.71, -1.30, 0.03, 0.00, 46.45, 46.50 +CTUN, 769, 0.26, 1.26, 0.000000, 0, 2, -9, 772, 0 +ATT, -0.75, -5.07, -0.74, -0.54, 0.00, 46.49, 46.50 +CTUN, 770, 0.26, 1.30, 0.000000, 0, 1, -10, 771, 0 +ATT, 0.00, -3.26, -1.40, -0.72, 0.00, 46.65, 46.50 +CTUN, 771, 0.26, 1.19, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, -1.93, -1.49, 0.00, 0.00, 46.74, 46.50 +CTUN, 771, 0.26, 1.30, 0.000000, 0, 0, -4, 770, 0 +ATT, 0.00, -1.01, -1.68, 0.59, 0.00, 46.79, 46.50 +CTUN, 769, 0.24, 1.35, 0.000000, 0, 0, -3, 770, 0 +ATT, 0.00, -0.92, -2.24, 0.92, 0.00, 46.77, 46.50 +CTUN, 771, 0.24, 1.17, 0.000000, 0, 0, -5, 771, 0 +ATT, 0.00, -0.32, -2.24, 1.13, 0.00, 46.57, 46.50 +CTUN, 771, 0.23, 1.24, 0.000000, 0, 0, -5, 771, 0 +ATT, 0.00, 0.26, -2.52, 0.73, 0.00, 46.28, 46.50 +CTUN, 770, 0.23, 1.33, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.50, -2.70, 0.33, 0.00, 45.97, 46.50 +DU32, 7, 166140 +CURR, 771, 1022765, 1013, 2049, 5028, 771.203310 +CTUN, 771, 0.23, 1.18, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -1.50, -2.52, 0.14, 0.00, 45.69, 46.50 +CTUN, 771, 0.23, 1.19, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, -1.16, -2.70, -0.09, 0.00, 45.48, 46.50 +CTUN, 771, 0.23, 1.25, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, -0.14, -2.70, -0.55, 0.00, 45.39, 46.50 +CTUN, 771, 0.23, 1.23, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 0.03, -2.70, -0.39, 0.00, 45.45, 46.50 +CTUN, 771, 0.23, 1.18, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.28, -0.54, -3.17, -0.18, 0.00, 45.64, 46.50 +CTUN, 770, 0.23, 1.32, 0.000000, 0, 0, 5, 769, 0 +ATT, 1.40, -0.45, -3.26, -0.38, 0.00, 45.96, 46.50 +CTUN, 771, 0.23, 1.30, 0.000000, 0, 0, 4, 771, 0 +ATT, 1.78, 0.39, -3.26, -0.48, 0.00, 46.40, 46.50 +CTUN, 771, 0.24, 1.35, 0.000000, 0, 0, 4, 771, 0 +ATT, 1.96, 0.76, -3.26, -0.46, 0.00, 46.98, 46.50 +CTUN, 771, 0.24, 1.21, 0.000000, 0, 0, 5, 771, 0 +ATT, 2.71, 0.89, -3.26, -0.88, 0.00, 47.41, 46.50 +CTUN, 770, 0.25, 1.26, 0.000000, 0, 0, 5, 771, 0 +ATT, 3.18, 0.87, -3.26, -1.14, 0.00, 47.62, 46.50 +DU32, 7, 166140 +CURR, 770, 1030473, 1015, 2082, 5051, 776.955080 +CTUN, 771, 0.25, 1.32, 0.000000, 0, 0, 5, 771, 0 +ATT, 3.56, 1.24, -3.73, -0.48, 0.00, 47.48, 46.50 +CTUN, 770, 0.26, 1.37, 0.000000, 0, 0, 5, 771, 0 +ATT, 4.31, 2.09, -3.73, 0.20, 0.00, 47.08, 46.50 +CTUN, 771, 0.26, 1.27, 0.000000, 0, 0, 4, 771, 0 +ATT, 4.68, 2.78, -3.82, 0.16, 0.00, 46.53, 46.50 +CTUN, 771, 0.26, 1.43, 0.000000, 0, 1, 2, 772, 0 +ATT, 4.59, 3.36, -4.20, -0.13, 0.00, 45.95, 46.50 +CTUN, 771, 0.26, 1.36, 0.000000, 0, 0, 0, 770, 0 +ATT, 4.59, 2.80, -4.57, -0.22, 0.00, 45.20, 46.50 +CTUN, 771, 0.28, 1.43, 0.000000, 0, 0, 0, 771, 0 +ATT, 3.28, 3.60, -4.85, -0.01, 0.00, 44.44, 46.50 +CTUN, 771, 0.28, 1.31, 0.000000, 0, 2, -3, 773, 0 +ATT, 3.18, 5.02, -5.69, 0.35, 0.00, 43.84, 46.50 +CTUN, 771, 0.28, 1.30, 0.000000, 0, 2, -4, 773, 0 +ATT, 2.53, 4.76, -6.90, 0.02, 0.00, 43.36, 46.50 +CTUN, 771, 0.27, 1.46, 0.000000, 0, 1, -10, 771, 0 +ATT, 1.40, 4.18, -8.21, -1.32, 0.00, 42.96, 46.50 +CTUN, 770, 0.27, 1.24, 0.000000, 0, 2, -12, 773, 0 +ATT, 0.46, 3.38, -8.30, -3.59, 0.00, 42.52, 46.50 +DU32, 7, 166140 +CURR, 771, 1038187, 1013, 2085, 5051, 782.765140 +CTUN, 771, 0.26, 1.39, 0.000000, 0, 2, -12, 773, 0 +ATT, 0.00, 1.37, -8.21, -5.82, 0.00, 42.30, 46.50 +CTUN, 771, 0.26, 1.26, 0.000000, 0, 4, -9, 775, 0 +ATT, 0.00, 1.07, -8.02, -6.66, 0.00, 42.17, 46.50 +CTUN, 770, 0.24, 1.18, 0.000000, 0, 4, -8, 775, 0 +ATT, 0.00, 1.25, -7.46, -6.16, 0.00, 42.18, 46.50 +CTUN, 771, 0.24, 1.16, 0.000000, 0, 3, -7, 774, 0 +ATT, 0.00, 0.84, -6.81, -5.08, 0.00, 42.56, 46.50 +CTUN, 771, 0.23, 1.04, 0.000000, 0, 1, -4, 771, 0 +ATT, 0.00, 1.37, -6.06, -3.40, 0.00, 43.25, 46.50 +CTUN, 771, 0.23, 1.34, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 1.30, -5.78, -1.95, 0.00, 44.08, 46.50 +CTUN, 771, 0.21, 1.16, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.75, -5.88, -1.45, 0.00, 44.79, 46.50 +CTUN, 770, 0.21, 1.32, 0.000000, 0, 0, 2, 770, 0 +ATT, 0.00, 0.03, -5.69, -2.04, 0.00, 45.45, 46.50 +CTUN, 771, 0.21, 1.20, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, -1.10, -4.76, -2.77, 0.00, 46.04, 46.50 +CTUN, 771, 0.21, 1.06, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -1.28, -4.57, -2.68, 0.00, 46.47, 46.50 +DU32, 7, 166140 +CURR, 771, 1045909, 1008, 2048, 5051, 788.542110 +CTUN, 771, 0.20, 1.16, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.50, -3.73, -1.40, 0.00, 46.78, 46.50 +CTUN, 771, 0.20, 1.23, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.56, -3.17, -0.50, 0.00, 46.93, 46.50 +CTUN, 770, 0.20, 1.32, 0.000000, 0, 0, 12, 771, 0 +ATT, 0.00, -1.44, -3.08, -0.57, 0.00, 46.92, 46.50 +CTUN, 771, 0.20, 1.16, 0.000000, 0, 0, 13, 770, 0 +ATT, 0.00, -2.28, -3.26, -1.63, 0.00, 46.74, 46.50 +CTUN, 771, 0.20, 1.25, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.00, -1.30, -3.08, -1.86, 0.00, 46.41, 46.50 +CTUN, 771, 0.23, 1.21, 0.000000, 0, 0, 18, 770, 0 +ATT, 0.00, 0.29, -3.26, -1.06, 0.00, 45.89, 46.50 +CTUN, 771, 0.23, 1.38, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.00, 0.49, -3.17, -0.03, 0.00, 45.34, 46.50 +CTUN, 771, 0.25, 1.34, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, 0.02, -3.26, -0.05, 0.00, 45.07, 46.50 +CTUN, 771, 0.25, 1.31, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.00, -0.33, -3.26, -0.50, 0.00, 45.05, 46.50 +CTUN, 771, 0.27, 1.35, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.00, -0.13, -3.17, -1.13, 0.00, 45.19, 46.50 +DU32, 7, 166140 +CURR, 770, 1053619, 1002, 2075, 5051, 794.314510 +CTUN, 771, 0.27, 1.34, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.01, -3.26, -1.32, 0.00, 45.28, 46.50 +CTUN, 771, 0.30, 1.35, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, -0.35, -3.26, -1.39, 0.00, 45.46, 46.50 +CTUN, 770, 0.30, 1.29, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.59, -3.26, -1.46, 0.00, 45.68, 46.50 +CTUN, 771, 0.30, 1.39, 0.000000, 0, 0, 4, 768, 0 +ATT, 0.00, -0.57, -3.08, -1.17, 0.00, 45.85, 46.50 +CTUN, 771, 0.30, 1.51, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, -0.37, -3.26, -0.61, 0.00, 45.99, 46.50 +CTUN, 771, 0.30, 1.45, 0.000000, 0, 0, 1, 770, 0 +ATT, 0.00, -0.49, -3.08, 0.04, 0.00, 46.06, 46.50 +CTUN, 771, 0.30, 1.31, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.00, -1.15, -3.08, -0.17, 0.00, 46.05, 46.50 +CTUN, 771, 0.30, 1.42, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.00, -0.70, -3.17, -0.02, 0.00, 45.92, 46.50 +CTUN, 771, 0.30, 1.42, 0.000000, 0, 0, -5, 771, 0 +ATT, 0.00, 0.63, -2.98, 0.20, 0.00, 45.61, 46.50 +CTUN, 770, 0.30, 1.34, 0.000000, 0, 0, -7, 771, 0 +ATT, 0.00, 1.01, -3.26, 0.40, 0.00, 45.28, 46.50 +DU32, 7, 166140 +CURR, 771, 1061326, 1008, 2033, 5051, 800.036680 +CTUN, 771, 0.28, 1.36, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, 0.92, -3.26, -0.15, 0.00, 44.89, 46.50 +CTUN, 771, 0.28, 1.29, 0.000000, 0, 0, -12, 770, 0 +ATT, 0.00, 0.56, -3.26, -1.10, 0.00, 44.40, 46.50 +CTUN, 771, 0.26, 1.21, 0.000000, 0, 0, -12, 770, 0 +ATT, 0.00, 0.09, -3.26, -1.18, 0.00, 44.01, 46.50 +CTUN, 771, 0.26, 1.19, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, 0.22, -3.17, -0.41, 0.00, 43.77, 46.50 +CTUN, 770, 0.22, 1.16, 0.000000, 0, 0, -10, 770, 0 +ATT, 0.00, 0.11, -3.26, -0.51, 0.00, 43.66, 46.50 +CTUN, 771, 0.22, 1.23, 0.000000, 0, 0, -11, 770, 0 +ATT, 0.00, 0.33, -3.26, -1.02, 0.00, 43.75, 46.50 +CTUN, 771, 0.20, 1.11, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.00, 0.46, -3.17, -1.56, 0.00, 43.99, 46.50 +CTUN, 771, 0.20, 1.10, 0.000000, 0, 0, -1, 771, 0 +PM, 0, 0, 0, 0, 1001, 10480, 0, 0 +ATT, 0.00, 0.43, -3.26, -1.46, 0.00, 44.29, 46.50 +CTUN, 771, 0.20, 0.75, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 0.67, -3.26, -0.83, 0.00, 44.61, 46.50 +CTUN, 771, 0.20, 1.00, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, 0.65, -3.26, -0.31, 0.00, 45.04, 46.50 +DU32, 7, 166140 +CURR, 770, 1069032, 1008, 2046, 5051, 805.722960 +CTUN, 771, 0.20, 0.87, 0.000000, 0, 0, 5, 768, 0 +ATT, 0.00, 0.21, -3.17, -0.08, 0.00, 45.55, 46.50 +CTUN, 771, 0.20, 0.91, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.41, -3.26, 0.01, 0.00, 46.12, 46.50 +CTUN, 770, 0.20, 1.00, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, -0.60, -3.26, -0.11, 0.00, 46.70, 46.50 +CTUN, 771, 0.20, 0.81, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, -0.54, -3.26, -1.00, 0.00, 47.25, 46.50 +CTUN, 771, 0.20, 0.92, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, -0.29, -3.26, -1.75, 0.00, 47.55, 46.50 +CTUN, 770, 0.20, 1.32, 0.000000, 0, 0, 18, 771, 0 +ATT, 0.00, -0.18, -4.20, -1.79, 0.00, 47.61, 46.50 +CTUN, 771, 0.20, 1.21, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.00, -0.48, -4.76, -1.67, 0.00, 47.35, 46.50 +CTUN, 771, 0.20, 1.22, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.00, 0.41, -4.76, -1.74, 0.00, 46.99, 46.50 +CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.00, 1.16, -4.94, -1.70, 0.00, 46.44, 46.50 +CTUN, 771, 0.24, 1.35, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, 0.84, -5.04, -2.14, 0.00, 45.75, 46.50 +DU32, 7, 166140 +CURR, 770, 1076738, 1012, 2045, 5051, 811.423100 +CTUN, 770, 0.24, 1.28, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, 0.22, -5.04, -2.55, 0.00, 44.94, 46.50 +CTUN, 770, 0.27, 1.43, 0.000000, 0, 0, 9, 770, 0 +ATT, 0.00, -0.31, -5.04, -2.39, 0.00, 44.27, 46.50 +CTUN, 771, 0.27, 1.37, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.10, -5.04, -2.11, 0.00, 43.71, 46.50 +CTUN, 770, 0.28, 1.31, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, 0.86, -5.04, -1.75, 0.00, 43.34, 46.50 +CTUN, 771, 0.28, 1.30, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.99, -4.76, -1.43, 0.00, 43.14, 46.50 +CTUN, 771, 0.28, 1.32, 0.000000, 0, 0, -7, 770, 0 +ATT, 0.00, 0.44, -4.85, -0.80, 0.00, 43.07, 46.50 +CTUN, 771, 0.28, 1.45, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, 0.23, -4.76, -0.46, 0.00, 43.03, 46.50 +CTUN, 771, 0.28, 1.32, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.00, 0.15, -4.76, -0.82, 0.00, 43.04, 46.50 +CTUN, 770, 0.27, 1.29, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.00, -0.35, -4.76, -1.10, 0.00, 43.16, 46.50 +CTUN, 771, 0.27, 1.29, 0.000000, 0, 0, -13, 770, 0 +ATT, 0.00, -0.36, -4.76, -1.26, 0.00, 43.31, 46.50 +DU32, 7, 166140 +CURR, 770, 1084445, 1007, 2053, 5051, 817.112060 +CTUN, 771, 0.25, 1.24, 0.000000, 0, 0, -13, 771, 0 +ATT, 0.00, 0.37, -4.76, -1.02, 0.00, 43.38, 46.50 +CTUN, 770, 0.25, 1.27, 0.000000, 0, 0, -13, 771, 0 +ATT, 0.00, 0.36, -4.76, -1.26, 0.00, 43.54, 46.50 +CTUN, 771, 0.23, 1.37, 0.000000, 0, 0, -8, 771, 0 +ATT, 0.00, 0.08, -4.76, -1.66, 0.00, 43.75, 46.50 +CTUN, 771, 0.23, 1.28, 0.000000, 0, 0, -13, 770, 0 +ATT, 0.00, 0.39, -4.76, -2.30, 0.00, 44.02, 46.50 +CTUN, 771, 0.21, 1.29, 0.000000, 0, 0, -12, 771, 0 +ATT, 0.00, 0.61, -4.85, -2.83, 0.00, 44.33, 46.50 +CTUN, 770, 0.21, 1.27, 0.000000, 0, 0, -10, 771, 0 +ATT, 0.00, 0.96, -4.76, -3.05, 0.00, 44.55, 46.50 +CTUN, 771, 0.20, 1.29, 0.000000, 0, 1, -5, 771, 0 +ATT, 0.00, 1.04, -4.76, -2.97, 0.00, 44.86, 46.50 +CTUN, 770, 0.20, 1.25, 0.000000, 0, 0, -6, 771, 0 +ATT, 0.00, 0.59, -4.76, -2.42, 0.00, 45.22, 46.50 +CTUN, 771, 0.20, 1.27, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.00, -0.23, -4.76, -1.39, 0.00, 45.72, 46.50 +CTUN, 771, 0.20, 1.18, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.78, -4.57, -1.20, 0.00, 46.26, 46.50 +DU32, 7, 166140 +CURR, 771, 1092151, 1017, 2067, 5051, 822.834530 +CTUN, 771, 0.20, 1.26, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -0.78, -4.57, -1.25, 0.00, 46.79, 46.50 +CTUN, 771, 0.20, 1.19, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, -0.64, -4.57, -1.11, 0.00, 47.35, 46.50 +CTUN, 771, 0.20, 1.30, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, -0.80, -4.76, -0.68, 0.00, 47.94, 46.50 +CTUN, 771, 0.20, 1.34, 0.000000, 0, 0, 4, 770, 0 +ATT, 0.00, -0.18, -4.66, -0.58, 0.00, 48.38, 46.50 +CTUN, 771, 0.20, 1.44, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 0.19, -4.57, -1.04, 0.00, 48.73, 46.50 +CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 0.35, -4.48, -1.50, 0.00, 49.03, 46.50 +CTUN, 771, 0.20, 1.20, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, 0.95, -4.48, -1.56, 0.00, 49.19, 46.50 +CTUN, 771, 0.22, 1.36, 0.000000, 0, 0, 7, 771, 0 +ATT, 0.00, 1.05, -4.48, -1.38, 0.00, 49.08, 46.50 +CTUN, 771, 0.22, 1.32, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.67, -4.57, -0.98, 0.00, 48.81, 46.50 +CTUN, 771, 0.25, 1.28, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.09, 0.07, -4.38, -0.41, 0.00, 48.50, 46.50 +DU32, 7, 166140 +CURR, 770, 1099860, 1016, 2070, 5051, 828.593200 +CTUN, 771, 0.25, 1.38, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.18, 0.11, -4.38, -0.91, 0.00, 48.18, 46.50 +CTUN, 771, 0.26, 1.41, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.09, -0.04, -4.38, -1.85, 0.00, 47.91, 46.50 +CTUN, 771, 0.26, 1.26, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.09, -0.50, -4.29, -2.58, 0.00, 47.88, 46.50 +CTUN, 771, 0.27, 1.33, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.09, -0.92, -4.38, -2.92, 0.00, 48.08, 46.50 +CTUN, 771, 0.27, 1.46, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.09, -0.42, -4.38, -2.51, 0.00, 48.35, 46.50 +CTUN, 771, 0.27, 1.36, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.09, -0.14, -4.38, -1.72, 0.00, 48.67, 46.50 +CTUN, 770, 0.27, 1.30, 0.000000, 0, 0, -1, 771, 0 +ATT, 0.09, -0.42, -4.38, -1.21, 0.00, 48.92, 46.50 +CTUN, 770, 0.28, 1.46, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.28, -0.27, -4.29, -1.03, 0.00, 49.06, 46.50 +CTUN, 771, 0.28, 1.48, 0.000000, 0, 0, -2, 771, 0 +ATT, 1.59, 0.30, -2.89, -1.10, 0.00, 49.19, 46.50 +CTUN, 771, 0.28, 1.41, 0.000000, 0, 0, -2, 770, 0 +ATT, 2.34, 0.88, -2.42, -0.61, 0.00, 49.37, 46.50 +DU32, 7, 166140 +CURR, 771, 1107567, 1004, 2063, 5051, 834.336240 +CTUN, 770, 0.28, 1.43, 0.000000, 0, 0, -4, 771, 0 +ATT, 3.00, 1.30, -2.52, 0.49, 0.00, 49.64, 46.50 +CTUN, 771, 0.28, 1.41, 0.000000, 0, 0, -7, 766, 0 +ATT, 3.18, 1.97, -2.42, 0.85, 0.00, 49.91, 46.50 +CTUN, 770, 0.27, 1.48, 0.000000, 0, 0, -9, 771, 0 +ATT, 3.28, 2.17, -2.52, 0.72, 0.00, 50.13, 46.50 +CTUN, 770, 0.27, 1.40, 0.000000, 0, 0, -12, 770, 0 +ATT, 3.09, 2.51, -2.42, 0.95, 0.00, 50.34, 46.50 +CTUN, 771, 0.26, 1.30, 0.000000, 0, 0, -13, 771, 0 +ATT, 3.28, 2.75, -2.42, 1.24, 0.00, 50.47, 46.50 +CTUN, 771, 0.26, 1.30, 0.000000, 0, 0, -13, 770, 0 +ATT, 3.18, 2.36, -2.42, 1.32, 0.00, 50.63, 46.50 +CTUN, 771, 0.24, 1.28, 0.000000, 0, 0, -14, 771, 0 +ATT, 3.09, 1.85, -2.42, 1.00, 0.00, 50.78, 46.50 +CTUN, 770, 0.24, 1.18, 0.000000, 0, 0, -11, 770, 0 +ATT, 3.18, 1.89, -2.42, 0.60, 0.00, 50.84, 46.50 +CTUN, 771, 0.22, 1.22, 0.000000, 0, 0, -11, 771, 0 +ATT, 2.90, 1.68, -2.61, 0.41, 0.00, 50.87, 46.50 +CTUN, 771, 0.22, 1.16, 0.000000, 0, 0, -10, 770, 0 +ATT, 2.81, 0.76, -2.70, 0.24, 0.00, 50.90, 46.50 +DU32, 7, 166140 +CURR, 771, 1115275, 1002, 2065, 5051, 840.063660 +CTUN, 770, 0.20, 1.13, 0.000000, 0, 0, -11, 771, 0 +ATT, 2.90, 0.46, -2.89, -0.24, 0.00, 50.90, 46.50 +CTUN, 771, 0.20, 1.20, 0.000000, 0, 0, -6, 770, 0 +ATT, 2.90, 0.81, -3.08, -0.55, 0.00, 50.75, 46.50 +CTUN, 770, 0.20, 1.11, 0.000000, 0, 0, -2, 771, 0 +ATT, 2.62, 1.42, -3.26, -0.91, 0.00, 50.45, 46.50 +CTUN, 771, 0.20, 1.11, 0.000000, 0, 0, 0, 770, 0 +ATT, 2.71, 2.28, -3.26, -2.07, 0.00, 50.08, 46.50 +CTUN, 771, 0.20, 1.14, 0.000000, 0, 1, 2, 771, 0 +ATT, 2.81, 2.57, -3.17, -2.93, 0.00, 49.46, 46.50 +CTUN, 771, 0.20, 1.08, 0.000000, 0, 1, 4, 772, 0 +ATT, 2.62, 2.21, -3.26, -2.85, 0.00, 48.88, 46.50 +CTUN, 771, 0.20, 1.13, 0.000000, 0, 0, 9, 770, 0 +ATT, 2.53, 1.51, -3.26, -2.09, 0.00, 48.29, 46.50 +CTUN, 770, 0.20, 0.93, 0.000000, 0, 0, 7, 771, 0 +ATT, 2.53, 1.47, -2.70, -1.59, 0.00, 47.75, 46.50 +CTUN, 771, 0.20, 1.25, 0.000000, 0, 0, 9, 770, 0 +ATT, 1.87, 1.68, -2.61, -1.44, 0.00, 47.30, 46.50 +CTUN, 771, 0.20, 1.24, 0.000000, 0, 0, 8, 770, 0 +ATT, 1.03, 1.58, -2.61, -1.38, 0.00, 46.97, 46.50 +DU32, 7, 166140 +CURR, 771, 1122988, 1004, 2056, 5028, 845.803220 +CTUN, 771, 0.20, 1.23, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.00, 1.15, -2.61, -1.05, 0.00, 46.71, 46.50 +CTUN, 770, 0.21, 1.29, 0.000000, 0, 0, 8, 770, 0 +ATT, 0.00, 0.43, -2.70, -0.52, 0.00, 46.42, 46.50 +CTUN, 770, 0.21, 1.35, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 0.22, -2.61, -0.31, 0.00, 46.13, 46.50 +CTUN, 771, 0.23, 1.27, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 0.50, -2.70, -0.62, 0.00, 45.98, 46.50 +CTUN, 771, 0.23, 1.40, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.00, 0.97, -2.70, -0.84, 0.00, 45.97, 46.50 +CTUN, 771, 0.25, 1.33, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.99, -2.70, -1.06, 0.00, 46.04, 46.50 +CTUN, 771, 0.25, 1.35, 0.000000, 0, 0, 2, 770, 0 +ATT, 0.00, 0.74, -2.70, -1.25, 0.00, 46.27, 46.50 +CTUN, 771, 0.25, 1.42, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.00, 1.29, -2.52, -1.27, 0.00, 46.60, 46.50 +CTUN, 770, 0.25, 1.32, 0.000000, 0, 0, -1, 770, 0 +ATT, -2.55, 1.67, -2.52, -1.37, 0.00, 46.89, 46.50 +CTUN, 771, 0.26, 1.23, 0.000000, 0, 0, 1, 770, 0 +ATT, -4.54, 0.61, -2.33, -1.04, 0.00, 47.08, 46.50 +DU32, 7, 166140 +CURR, 771, 1130697, 999, 2070, 5028, 851.504210 +CTUN, 771, 0.25, 1.50, 0.000000, 0, 0, 0, 771, 0 +ATT, -6.25, -1.41, -2.14, -0.79, 0.00, 47.25, 46.50 +CTUN, 771, 0.25, 1.47, 0.000000, 0, 0, -4, 771, 0 +ATT, -6.06, -3.70, -2.05, -1.55, 0.00, 47.54, 46.50 +CTUN, 770, 0.25, 1.47, 0.000000, 0, 2, -5, 772, 0 +ATT, -6.53, -4.95, -2.05, -2.92, 0.00, 47.91, 46.50 +CTUN, 770, 0.26, 1.48, 0.000000, 0, 3, -4, 773, 0 +ATT, -6.72, -4.84, -2.05, -2.81, 0.00, 48.10, 46.50 +CTUN, 771, 0.26, 1.51, 0.000000, 0, 2, -6, 773, 0 +ATT, -6.72, -4.61, -1.86, -0.91, 0.00, 47.94, 46.50 +CTUN, 770, 0.26, 1.38, 0.000000, 0, 1, -7, 772, 0 +ATT, -5.77, -4.30, -1.58, 0.74, 0.00, 47.58, 46.50 +CTUN, 771, 0.25, 1.31, 0.000000, 0, 1, -8, 772, 0 +ATT, -5.49, -4.22, -1.40, 0.87, 0.00, 47.16, 46.50 +CTUN, 771, 0.25, 1.44, 0.000000, 0, 1, -10, 772, 0 +ATT, -5.30, -4.12, -1.40, 0.21, 0.00, 46.67, 46.50 +CTUN, 771, 0.25, 1.43, 0.000000, 0, 1, -7, 772, 0 +ATT, -4.45, -4.12, -1.40, 0.17, 0.00, 46.00, 46.50 +CTUN, 771, 0.25, 1.42, 0.000000, 0, 1, -4, 772, 0 +ATT, -3.69, -3.75, -1.40, 0.94, 0.00, 45.13, 46.50 +DU32, 7, 166140 +CURR, 769, 1138417, 1015, 2039, 5051, 857.233220 +CTUN, 770, 0.23, 1.30, 0.000000, 0, 1, 0, 772, 0 +ATT, -3.88, -3.06, -1.21, 1.33, 0.00, 44.35, 46.50 +CTUN, 771, 0.24, 1.34, 0.000000, 0, 1, 1, 772, 0 +ATT, -0.85, -2.75, -2.52, 1.66, 0.00, 43.60, 46.50 +CTUN, 771, 0.23, 1.34, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, -2.00, -2.52, 1.16, 0.00, 43.11, 46.50 +CTUN, 771, 0.23, 1.41, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.22, -3.92, 0.13, 0.00, 42.81, 46.50 +CTUN, 770, 0.20, 1.23, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 1.83, -4.20, -0.76, 0.00, 42.75, 46.50 +CTUN, 771, 0.20, 1.37, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.00, 2.22, -4.38, -1.31, 0.00, 42.85, 46.50 +CTUN, 771, 0.20, 1.47, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.00, 1.37, -4.38, -1.69, 0.00, 43.10, 46.50 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +CTUN, 771, 0.20, 1.17, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, 0.49, -4.57, -2.29, 0.00, 43.41, 46.50 +CTUN, 771, 0.20, 1.16, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, 0.61, -4.48, -2.26, 0.00, 43.82, 46.50 +CTUN, 770, 0.20, 0.97, 0.000000, 0, 0, 9, 770, 0 +ATT, 0.00, 0.48, -4.57, -2.22, 0.00, 44.37, 46.50 +DU32, 7, 166140 +CURR, 771, 1146128, 1006, 2037, 5051, 862.919490 +CTUN, 770, 0.20, 1.41, 0.000000, 0, 0, 12, 771, 0 +ATT, 0.00, 0.15, -4.57, -1.77, 0.00, 44.96, 46.50 +CTUN, 771, 0.20, 1.51, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.00, 0.09, -4.48, -1.36, 0.00, 45.53, 46.50 +CTUN, 771, 0.20, 1.33, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, 0.52, -4.57, -1.08, 0.00, 45.99, 46.50 +CTUN, 771, 0.22, 1.41, 0.000000, 0, 0, 15, 770, 0 +ATT, 0.00, 0.26, -4.66, -0.83, 0.00, 46.32, 46.50 +CTUN, 770, 0.22, 1.41, 0.000000, 0, 0, 15, 770, 0 +ATT, 0.28, -0.32, -4.76, -1.10, 0.00, 46.48, 46.50 +CTUN, 771, 0.23, 1.46, 0.000000, 0, 0, 14, 771, 0 +ATT, 0.46, -0.03, -4.66, -2.53, 0.00, 46.63, 46.50 +CTUN, 771, 0.23, 1.61, 0.000000, 0, 1, 11, 771, 0 +ATT, 0.46, 0.33, -4.76, -3.69, 0.00, 46.59, 46.50 +CTUN, 770, 0.25, 1.42, 0.000000, 0, 1, 14, 772, 0 +ATT, 0.46, 0.11, -4.76, -3.65, 0.00, 46.36, 46.50 +CTUN, 770, 0.25, 1.41, 0.000000, 0, 1, 10, 772, 0 +ATT, 0.46, -0.06, -4.76, -3.46, 0.00, 46.09, 46.50 +CTUN, 771, 0.27, 1.52, 0.000000, 0, 1, 11, 771, 0 +ATT, 0.46, -0.35, -4.57, -2.87, 0.00, 45.71, 46.50 +DU32, 7, 166140 +CURR, 770, 1153836, 1006, 2060, 5051, 868.642330 +CTUN, 771, 0.27, 1.49, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.46, -0.69, -4.57, -1.53, 0.00, 45.30, 46.50 +CTUN, 771, 0.28, 1.36, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.28, -0.82, -2.61, -0.14, 0.00, 44.91, 46.50 +CTUN, 771, 0.28, 1.36, 0.000000, 0, 0, 10, 771, 0 +ATT, 1.03, -1.07, -2.24, 1.09, 0.00, 44.70, 46.50 +CTUN, 770, 0.28, 1.70, 0.000000, 0, 0, 5, 771, 0 +ATT, 1.87, -0.62, -2.14, 2.30, 0.00, 44.77, 46.50 +CTUN, 771, 0.28, 1.55, 0.000000, 0, 0, 3, 771, 0 +ATT, 2.90, -0.07, -2.24, 2.65, 0.00, 45.04, 46.50 +CTUN, 771, 0.28, 1.54, 0.000000, 0, 0, 0, 771, 0 +ATT, 2.90, 1.08, -2.24, 1.82, 0.00, 45.50, 46.50 +CTUN, 771, 0.28, 1.60, 0.000000, 0, 0, -1, 771, 0 +ATT, 2.90, 2.48, -2.52, 0.80, 0.00, 46.05, 46.50 +CTUN, 771, 0.28, 1.54, 0.000000, 0, 0, -2, 771, 0 +ATT, 2.90, 2.47, -2.61, -0.06, 0.00, 46.48, 46.50 +CTUN, 770, 0.27, 1.55, 0.000000, 0, 0, -2, 770, 0 +ATT, 2.81, 1.76, -2.52, -0.47, 0.00, 46.81, 46.50 +CTUN, 771, 0.27, 1.35, 0.000000, 0, 0, -1, 770, 0 +ATT, 2.71, 1.41, -3.26, -0.63, 0.00, 47.12, 46.50 +DU32, 7, 166140 +CURR, 770, 1161540, 1007, 2061, 5051, 874.380550 +CTUN, 771, 0.27, 1.39, 0.000000, 0, 0, -3, 770, 0 +ATT, 2.71, 1.74, -3.26, -0.66, 0.00, 47.22, 46.50 +CTUN, 771, 0.27, 1.29, 0.000000, 0, 0, -3, 771, 0 +ATT, 2.81, 1.56, -3.45, -0.85, 0.00, 47.09, 46.50 +CTUN, 771, 0.25, 1.25, 0.000000, 0, 0, -4, 770, 0 +ATT, 2.81, 1.29, -4.20, -0.93, 0.00, 46.75, 46.50 +CTUN, 771, 0.25, 1.39, 0.000000, 0, 0, -5, 771, 0 +ATT, 2.53, 1.90, -4.38, -1.00, 0.00, 46.24, 46.50 +CTUN, 771, 0.22, 1.24, 0.000000, 0, 0, -7, 771, 0 +ATT, 2.53, 2.66, -4.57, -1.32, 0.00, 45.73, 46.50 +CTUN, 771, 0.22, 1.30, 0.000000, 0, 1, -6, 771, 0 +ATT, 2.53, 3.40, -4.48, -1.94, 0.00, 45.16, 46.50 +CTUN, 770, 0.20, 1.39, 0.000000, 0, 1, -6, 771, 0 +ATT, 2.06, 3.63, -4.57, -2.39, 0.00, 44.69, 46.50 +CTUN, 770, 0.20, 1.22, 0.000000, 0, 1, -3, 772, 0 +ATT, 1.59, 3.36, -4.48, -2.66, 0.00, 44.33, 46.50 +CTUN, 771, 0.20, 1.46, 0.000000, 0, 1, -5, 772, 0 +ATT, 0.37, 2.58, -4.38, -3.00, 0.00, 44.02, 46.50 +CTUN, 771, 0.20, 1.28, 0.000000, 0, 1, 0, 772, 0 +ATT, 0.00, 1.68, -2.80, -3.02, 0.00, 43.81, 46.50 +DU32, 7, 166140 +CURR, 771, 1169248, 1015, 2060, 5051, 880.068730 +CTUN, 770, 0.20, 1.19, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.00, 0.54, -2.42, -2.06, 0.00, 43.75, 46.50 +CTUN, 771, 0.20, 1.43, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.60, -2.52, -0.21, 0.00, 43.84, 46.50 +CTUN, 771, 0.20, 1.20, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -1.34, -2.42, 0.97, 0.00, 43.98, 46.50 +CTUN, 771, 0.20, 1.30, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, -1.65, -2.52, 1.11, 0.00, 44.21, 46.50 +CTUN, 771, 0.20, 1.29, 0.000000, 0, 0, 13, 770, 0 +ATT, 0.00, -1.86, -2.61, 0.53, 0.00, 44.44, 46.50 +CTUN, 771, 0.20, 1.46, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.00, -2.20, -2.70, 0.29, 0.00, 44.72, 46.50 +CTUN, 771, 0.20, 1.30, 0.000000, 0, 0, 19, 771, 0 +ATT, 0.00, -1.46, -2.61, -0.22, 0.00, 44.99, 46.50 +CTUN, 770, 0.21, 1.50, 0.000000, 0, 0, 17, 770, 0 +ATT, 0.00, -0.49, -2.61, -0.69, 0.00, 45.24, 46.50 +CTUN, 771, 0.21, 1.41, 0.000000, 0, 0, 19, 771, 0 +ATT, 0.00, -0.22, -2.70, -0.63, 0.00, 45.37, 46.50 +CTUN, 771, 0.22, 1.41, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.00, -0.50, -2.80, -0.16, 0.00, 45.36, 46.50 +DU32, 7, 166140 +CURR, 770, 1176957, 1015, 2061, 5051, 885.775390 +CTUN, 770, 0.22, 1.45, 0.000000, 0, 0, 18, 770, 0 +ATT, 0.00, 0.05, -2.89, 0.18, 0.00, 45.08, 46.50 +CTUN, 771, 0.25, 1.49, 0.000000, 0, 0, 14, 770, 0 +ATT, 0.00, 0.96, -3.26, 0.16, 0.00, 44.63, 46.50 +CTUN, 771, 0.25, 1.33, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.00, 1.95, -4.38, -0.65, 0.00, 44.00, 46.50 +CTUN, 770, 0.26, 1.56, 0.000000, 0, 0, 11, 770, 0 +ATT, 0.00, 2.75, -4.57, -1.82, 0.00, 43.38, 46.50 +CTUN, 771, 0.26, 1.52, 0.000000, 0, 1, 13, 771, 0 +ATT, 0.00, 2.58, -4.76, -2.61, 0.00, 43.01, 46.50 +CTUN, 771, 0.28, 1.46, 0.000000, 0, 1, 9, 771, 0 +ATT, 0.00, 2.24, -4.57, -3.54, 0.00, 42.87, 46.50 +CTUN, 771, 0.28, 1.50, 0.000000, 0, 1, 8, 772, 0 +ATT, -0.37, 1.44, -4.38, -4.01, 0.00, 42.73, 46.50 +CTUN, 771, 0.28, 1.55, 0.000000, 0, 1, 9, 772, 0 +ATT, -2.36, 1.14, -2.33, -3.30, 0.00, 42.52, 46.50 +CTUN, 770, 0.28, 1.47, 0.000000, 0, 0, 5, 771, 0 +ATT, -2.27, 0.33, -2.24, -1.92, 0.00, 42.30, 46.50 +CTUN, 771, 0.29, 1.51, 0.000000, 0, 0, 2, 771, 0 +ATT, -2.08, -0.61, -2.05, -0.58, 0.00, 42.00, 46.50 +DU32, 7, 166140 +CURR, 770, 1184664, 1008, 2065, 5051, 891.542660 +CTUN, 770, 0.29, 1.63, 0.000000, 0, 0, 0, 771, 0 +ATT, -3.88, -0.88, -2.05, 0.01, 0.00, 41.75, 46.50 +CTUN, 771, 0.29, 1.69, 0.000000, 0, 0, -4, 771, 0 +ATT, -4.35, -1.73, -2.24, -0.03, 0.00, 41.69, 46.50 +CTUN, 771, 0.29, 1.50, 0.000000, 0, 0, -5, 771, 0 +ATT, -4.73, -2.82, -2.52, -0.84, 0.00, 41.90, 46.50 +CTUN, 770, 0.29, 1.56, 0.000000, 0, 1, -6, 772, 0 +ATT, -4.83, -3.73, -2.42, -1.18, 0.00, 42.30, 46.50 +CTUN, 771, 0.26, 1.41, 0.000000, 0, 1, -6, 772, 0 +ATT, -4.35, -3.94, -2.52, -0.95, 0.00, 42.83, 46.50 +CTUN, 770, 0.26, 1.36, 0.000000, 0, 1, -1, 772, 0 +ATT, -4.35, -3.60, -2.52, -0.34, 0.00, 43.34, 46.50 +CTUN, 770, 0.24, 1.49, 0.000000, 0, 1, -4, 771, 0 +ATT, -2.55, -3.39, -2.42, -0.13, 0.00, 43.81, 46.50 +CTUN, 771, 0.24, 1.69, 0.000000, 0, 0, -2, 771, 0 +ATT, -2.46, -2.92, -2.42, -0.61, 0.00, 44.36, 46.50 +CTUN, 771, 0.20, 1.52, 0.000000, 0, 0, 0, 771, 0 +ATT, -2.36, -2.82, -2.42, -0.75, 0.00, 45.02, 46.50 +CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 0, 771, 0 +ATT, -2.55, -2.69, -2.52, -1.04, 0.00, 45.67, 46.50 +DU32, 7, 166140 +CURR, 771, 1192375, 1010, 2039, 5028, 897.232540 +CTUN, 770, 0.20, 1.59, 0.000000, 0, 0, 4, 771, 0 +ATT, -2.46, -3.17, -2.52, -0.85, 0.00, 46.13, 46.50 +CTUN, 771, 0.20, 1.41, 0.000000, 0, 1, 8, 772, 0 +ATT, -2.36, -3.96, -2.33, -0.36, 0.00, 46.41, 46.50 +CTUN, 771, 0.20, 1.57, 0.000000, 0, 1, 14, 772, 0 +ATT, -1.80, -3.28, -1.77, -0.07, 0.00, 46.45, 46.50 +CTUN, 771, 0.20, 1.39, 0.000000, 0, 0, 16, 770, 0 +ATT, -0.94, -2.49, -2.61, 0.09, 0.00, 46.33, 46.50 +CTUN, 771, 0.20, 1.34, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.00, -2.13, -2.52, 0.30, 0.00, 46.17, 46.50 +CTUN, 770, 0.20, 1.38, 0.000000, 0, 0, 24, 770, 0 +ATT, 0.00, -1.45, -2.80, 0.16, 0.00, 46.09, 46.50 +CTUN, 771, 0.20, 1.36, 0.000000, 0, 0, 23, 771, 0 +ATT, 0.00, -1.20, -3.08, -0.05, 0.00, 46.05, 46.50 +CTUN, 771, 0.21, 1.51, 0.000000, 0, 0, 23, 771, 0 +ATT, 0.00, -0.82, -3.26, -0.38, 0.00, 46.02, 46.50 +CTUN, 770, 0.21, 1.56, 0.000000, 0, 0, 21, 770, 0 +ATT, 0.00, -0.02, -3.26, -0.76, 0.00, 46.07, 46.50 +CTUN, 771, 0.22, 1.49, 0.000000, 0, 0, 24, 771, 0 +ATT, 0.00, 0.14, -3.26, -1.44, 0.00, 46.04, 46.50 +DU32, 7, 166140 +CURR, 771, 1200085, 1005, 2054, 5051, 902.959410 +CTUN, 771, 0.22, 1.60, 0.000000, 0, 0, 24, 771, 0 +ATT, 0.00, 0.73, -3.45, -1.68, 0.00, 45.94, 46.50 +CTUN, 771, 0.24, 1.54, 0.000000, 0, 0, 26, 771, 0 +ATT, 0.00, 1.37, -3.26, -1.60, 0.00, 45.67, 46.50 +CTUN, 770, 0.24, 1.62, 0.000000, 0, 0, 22, 770, 0 +ATT, 0.09, 1.11, -3.45, -1.16, 0.00, 45.30, 46.50 +CTUN, 770, 0.27, 1.62, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.18, 0.91, -3.26, -0.81, 0.00, 44.83, 46.50 +CTUN, 771, 0.27, 1.66, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.28, 1.07, -3.45, -0.62, 0.00, 44.44, 46.50 +CTUN, 771, 0.29, 1.58, 0.000000, 0, 0, 17, 771, 0 +ATT, 0.37, 1.08, -3.45, -0.51, 0.00, 44.15, 46.50 +CTUN, 771, 0.29, 1.64, 0.000000, 0, 0, 11, 770, 0 +ATT, 0.46, 0.49, -3.54, -0.43, 0.00, 44.12, 46.50 +CTUN, 771, 0.31, 1.57, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.37, 0.62, -3.54, -0.41, 0.00, 44.31, 46.50 +CTUN, 770, 0.31, 1.68, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.18, 1.22, -3.26, -0.39, 0.00, 44.57, 46.50 +CTUN, 770, 0.31, 1.56, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.28, 1.27, -3.17, -0.22, 0.00, 44.92, 46.50 +DU32, 7, 166140 +CURR, 771, 1207791, 999, 2057, 5051, 908.689450 +CTUN, 771, 0.31, 1.77, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.46, 1.09, -3.45, -0.28, 0.00, 45.44, 46.50 +CTUN, 771, 0.31, 1.64, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.46, 0.96, -3.45, -0.50, 0.00, 45.81, 46.50 +CTUN, 771, 0.31, 1.66, 0.000000, 0, 0, -4, 771, 0 +ATT, 0.28, 1.43, -3.54, -0.67, 0.00, 46.22, 46.50 +CTUN, 770, 0.31, 1.48, 0.000000, 0, 0, -2, 771, 0 +ATT, 0.28, 1.93, -3.92, -1.00, 0.00, 46.73, 46.50 +CTUN, 770, 0.28, 1.57, 0.000000, 0, 0, -1, 770, 0 +ATT, 0.37, 2.11, -4.38, -1.29, 0.00, 47.25, 46.50 +CTUN, 771, 0.28, 1.60, 0.000000, 0, 0, 1, 771, 0 +ATT, 0.28, 1.90, -4.38, -1.78, 0.00, 47.69, 46.50 +CTUN, 771, 0.26, 1.54, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.28, 0.99, -4.38, -2.30, 0.00, 48.00, 46.50 +CTUN, 771, 0.26, 1.56, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.18, 0.74, -4.38, -2.31, 0.00, 48.23, 46.50 +CTUN, 771, 0.24, 1.54, 0.000000, 0, 0, 1, 770, 0 +ATT, 0.18, 0.65, -4.20, -1.84, 0.00, 48.42, 46.50 +CTUN, 771, 0.24, 1.45, 0.000000, 0, 0, 3, 770, 0 +ATT, 0.00, 0.07, -3.73, -1.18, 0.00, 48.64, 46.50 +DU32, 7, 166140 +CURR, 771, 1215500, 1002, 2093, 5028, 914.448360 +CTUN, 771, 0.23, 1.51, 0.000000, 0, 0, 3, 771, 0 +ATT, 0.00, -0.89, -3.36, -0.97, 0.00, 48.84, 46.50 +CTUN, 770, 0.23, 1.48, 0.000000, 0, 0, 5, 771, 0 +ATT, 0.00, -0.59, -3.26, -0.71, 0.00, 49.11, 46.50 +CTUN, 770, 0.21, 1.47, 0.000000, 0, 0, 6, 771, 0 +ATT, 0.00, -0.10, -3.08, 0.00, 0.00, 49.57, 46.50 +CTUN, 771, 0.21, 1.48, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.29, -2.61, 0.79, 0.00, 50.28, 46.50 +CTUN, 770, 0.21, 1.44, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.00, -1.16, -2.61, 0.82, 0.00, 50.87, 46.50 +CTUN, 771, 0.21, 1.46, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.00, -0.89, -2.61, 0.60, 0.00, 51.34, 46.50 +CTUN, 771, 0.21, 1.52, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.50, -3.26, 0.73, 0.00, 51.63, 46.50 +PM, 0, 0, 0, 0, 1000, 10480, 0, 0 +CTUN, 771, 0.21, 1.46, 0.000000, 0, 0, 12, 771, 0 +ATT, 0.00, -0.39, -4.01, 0.67, 0.00, 51.69, 46.50 +CTUN, 770, 0.21, 1.52, 0.000000, 0, 0, 12, 771, 0 +ATT, 0.00, -0.83, -4.57, 0.34, 0.00, 51.68, 46.50 +CTUN, 771, 0.22, 1.52, 0.000000, 0, 0, 12, 770, 0 +ATT, 0.00, -1.11, -4.76, -0.53, 0.00, 51.49, 46.50 +DU32, 7, 166140 +CURR, 771, 1223209, 1012, 2067, 5051, 920.225280 +CTUN, 771, 0.22, 1.57, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -1.30, -5.22, -1.44, 0.00, 51.20, 46.50 +CTUN, 771, 0.23, 1.54, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.00, -0.58, -6.34, -1.58, 0.00, 50.81, 46.50 +CTUN, 771, 0.23, 1.52, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.84, 0.49, -6.25, -0.75, 0.00, 50.48, 46.50 +CTUN, 771, 0.24, 1.51, 0.000000, 0, 0, 11, 771, 0 +ATT, 1.50, 1.44, -6.16, -0.05, 0.00, 50.24, 46.50 +CTUN, 771, 0.24, 1.75, 0.000000, 0, 0, 8, 771, 0 +ATT, 1.78, 1.93, -6.06, -0.47, 0.00, 50.10, 46.50 +CTUN, 770, 0.25, 1.67, 0.000000, 0, 0, 8, 771, 0 +ATT, 1.87, 1.28, -6.06, -2.00, 0.00, 49.98, 46.50 +CTUN, 771, 0.25, 1.47, 0.000000, 0, 0, 8, 771, 0 +ATT, 1.40, 1.20, -6.53, -2.57, 0.00, 49.98, 46.50 +CTUN, 770, 0.25, 1.59, 0.000000, 0, 0, 6, 770, 0 +ATT, 0.28, 1.91, -6.53, -2.32, 0.00, 50.19, 46.50 +CTUN, 770, 0.25, 1.61, 0.000000, 0, 0, 7, 770, 0 +ATT, 0.46, 1.23, -6.81, -2.25, 0.00, 50.58, 46.50 +CTUN, 771, 0.25, 1.53, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.46, 0.69, -6.81, -1.79, 0.00, 50.97, 46.50 +DU32, 7, 166140 +CURR, 771, 1230918, 1003, 2082, 5051, 925.962770 +CTUN, 771, 0.25, 1.55, 0.000000, 0, 0, 4, 771, 0 +ATT, 0.46, 0.53, -6.72, -2.01, 0.00, 51.21, 46.50 +CTUN, 771, 0.25, 1.75, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.46, 0.26, -6.81, -2.51, 0.00, 51.26, 46.50 +CTUN, 771, 0.25, 1.69, 0.000000, 0, 0, 0, 771, 0 +ATT, 0.37, 0.11, -6.81, -2.36, 0.00, 51.07, 46.50 +CTUN, 771, 0.25, 1.65, 0.000000, 0, 0, -2, 770, 0 +ATT, 0.09, -0.08, -6.81, -1.77, 0.00, 50.57, 46.50 +CTUN, 771, 0.24, 1.47, 0.000000, 0, 0, -3, 771, 0 +ATT, 0.28, -0.71, -7.37, -2.52, 0.00, 49.84, 46.50 +CTUN, 770, 0.24, 1.61, 0.000000, 0, 1, -4, 772, 0 +ATT, 0.09, -0.93, -7.56, -3.45, 0.00, 49.03, 46.50 +CTUN, 771, 0.23, 1.52, 0.000000, 0, 1, -3, 771, 0 +ATT, 0.09, -0.11, -7.46, -3.27, 0.00, 48.23, 46.50 +CTUN, 771, 0.23, 1.63, 0.000000, 0, 0, 0, 770, 0 +ATT, 0.09, 0.48, -7.46, -2.51, 0.00, 47.53, 46.50 +CTUN, 771, 0.21, 1.59, 0.000000, 0, 0, 2, 771, 0 +ATT, 0.09, -0.45, -6.72, -2.42, 0.00, 47.06, 46.50 +CTUN, 770, 0.21, 1.48, 0.000000, 0, 0, 8, 771, 0 +ATT, 0.09, -0.38, -6.53, -1.68, 0.00, 46.70, 46.50 +DU32, 7, 166140 +CURR, 771, 1238625, 1008, 2071, 5051, 931.673460 +CTUN, 771, 0.20, 1.52, 0.000000, 0, 0, 11, 770, 0 +ATT, 0.09, -0.28, -6.16, -1.15, 0.00, 46.37, 46.50 +CTUN, 771, 0.21, 1.52, 0.000000, 0, 0, 9, 771, 0 +ATT, 0.09, -0.61, -5.88, -1.14, 0.00, 46.20, 46.50 +CTUN, 771, 0.20, 1.49, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.09, -0.64, -5.22, -0.98, 0.00, 46.07, 46.50 +CTUN, 771, 0.21, 1.56, 0.000000, 0, 0, 12, 770, 0 +ATT, 0.09, -0.63, -4.76, -0.54, 0.00, 45.97, 46.50 +CTUN, 771, 0.21, 1.59, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.09, -0.19, -4.57, 0.12, 0.00, 45.82, 46.50 +CTUN, 771, 0.21, 1.52, 0.000000, 0, 0, 10, 771, 0 +ATT, 0.09, 0.32, -4.57, 0.35, 0.00, 45.66, 46.50 +CTUN, 771, 0.21, 1.64, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.09, 0.75, -4.48, -0.24, 0.00, 45.47, 46.50 +CTUN, 770, 0.21, 1.59, 0.000000, 0, 0, 12, 771, 0 +ATT, 0.09, 0.67, -4.57, -1.12, 0.00, 45.29, 46.50 +CTUN, 771, 0.21, 1.60, 0.000000, 0, 0, 11, 771, 0 +ATT, 0.09, -0.14, -4.57, -1.77, 0.00, 45.47, 46.50 +CTUN, 771, 0.22, 1.47, 0.000000, 0, 0, 13, 771, 0 +ATT, 0.09, 0.07, -4.66, -1.42, 0.00, 45.96, 46.50 +DU32, 7, 166140 +CURR, 771, 1246334, 1006, 2055, 5051, 937.392030 +CTUN, 771, 0.22, 1.62, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.09, 0.73, -4.57, -1.01, 0.00, 46.63, 46.50 +CTUN, 770, 0.22, 1.69, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.00, 1.22, -4.85, -0.11, 0.00, 47.34, 46.50 +CTUN, 771, 0.22, 1.72, 0.000000, 0, 0, 15, 770, 0 +ATT, 0.09, 0.90, -4.76, 0.50, 0.00, 48.07, 46.50 +CTUN, 771, 0.23, 1.56, 0.000000, 0, 0, 18, 770, 0 +ATT, 0.09, 0.50, -4.76, 0.61, 0.00, 48.62, 46.50 +CTUN, 773, 0.23, 1.68, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.09, 0.61, -4.85, -0.35, 0.00, 48.99, 46.50 +CTUN, 771, 0.24, 1.66, 0.000000, 0, 0, 15, 771, 0 +ATT, 0.18, 0.95, -4.76, -1.31, 0.00, 49.11, 46.50 +CTUN, 771, 0.24, 1.81, 0.000000, 0, 0, 19, 770, 0 +ATT, 0.09, 1.19, -4.76, -1.40, 0.00, 48.93, 46.50 +CTUN, 771, 0.25, 1.56, 0.000000, 0, 0, 20, 771, 0 +ATT, 0.09, 1.15, -4.76, -0.97, 0.00, 48.39, 46.50 +CTUN, 770, 0.25, 1.71, 0.000000, 0, 0, 19, 770, 0 +ATT, 0.09, 0.39, -5.04, -1.11, 0.00, 47.64, 46.50 +CTUN, 771, 0.27, 1.71, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.00, 0.24, -5.50, -1.34, 0.19, 46.78, 46.50 +DU32, 7, 166140 +CURR, 770, 1254041, 1006, 2043, 5051, 943.124760 +CTUN, 775, 0.27, 1.55, 0.000000, 0, 0, 16, 771, 0 +ATT, 0.09, 0.08, -6.06, -1.15, 0.19, 45.94, 46.50 +CTUN, 787, 0.28, 1.70, 0.000000, 0, 0, 16, 786, 0 +ATT, 0.09, 0.54, -6.34, -0.70, 0.19, 45.07, 46.50 +CTUN, 789, 0.28, 1.69, 0.000000, 0, 0, 14, 789, 0 +ATT, 0.09, 0.94, -6.44, -0.74, 0.09, 44.17, 46.50 +CTUN, 792, 0.29, 1.73, 0.000000, 0, 0, 14, 791, 0 +ATT, 0.09, 0.24, -6.53, -1.63, 0.86, 43.39, 46.75 +CTUN, 791, 0.29, 1.76, 0.000000, 0, 0, 15, 791, 0 +ATT, 0.09, -0.54, -6.34, -2.39, 1.25, 42.77, 47.18 +CTUN, 792, 0.29, 1.73, 0.000000, 0, 0, 15, 792, 0 +ATT, 0.09, -0.73, -6.25, -2.22, 2.01, 42.35, 47.96 +CTUN, 793, 0.29, 1.79, 0.000000, 0, 0, 15, 792, 0 +ATT, 0.09, -0.23, -6.34, -1.81, 2.21, 42.28, 48.87 +CTUN, 795, 0.30, 1.73, 0.000000, 0, 0, 17, 796, 0 +ATT, 0.09, 0.24, -6.53, -1.88, 2.21, 42.64, 49.78 +CTUN, 795, 0.30, 1.79, 0.000000, 0, 0, 17, 795, 0 +ATT, 0.09, -0.18, -6.53, -2.15, 3.07, 43.28, 50.80 +CTUN, 796, 0.32, 1.83, 0.000000, 0, 0, 16, 796, 0 +ATT, 0.09, -0.85, -6.53, -2.51, 3.46, 44.20, 52.25 +DU32, 7, 166140 +CURR, 796, 1261938, 997, 2176, 5051, 949.100770 +CTUN, 796, 0.32, 1.75, 0.000000, 0, 0, 16, 796, 0 +ATT, 0.09, 0.04, -6.53, -2.55, 3.26, 45.52, 53.69 +CTUN, 796, 0.33, 1.81, 0.000000, 0, 0, 13, 796, 0 +ATT, 0.09, 0.96, -6.53, -2.48, 3.17, 47.18, 55.17 +CTUN, 796, 0.33, 1.85, 0.000000, 0, 0, 14, 796, 0 +ATT, 0.09, 1.34, -6.53, -1.78, 3.55, 49.13, 56.68 +CTUN, 796, 0.33, 1.76, 0.000000, 0, 0, 15, 796, 0 +ATT, 0.46, 1.90, -6.53, -0.79, 2.11, 51.26, 57.98 +CTUN, 796, 0.33, 1.77, 0.000000, 0, 0, 16, 796, 0 +ATT, 1.31, 1.90, -6.53, -0.52, 0.00, 53.48, 58.46 +CTUN, 794, 0.35, 1.98, 0.000000, 0, 0, 13, 796, 0 +ATT, 1.50, 2.06, -6.53, -1.05, 0.00, 55.40, 58.46 +CTUN, 791, 0.35, 1.86, 0.000000, 0, 0, 14, 796, 0 +ATT, 1.31, 2.55, -6.53, -1.53, 0.00, 56.88, 58.46 +CTUN, 786, 0.36, 1.83, 0.000000, 0, 0, 16, 786, 0 +ATT, 0.00, 2.14, -6.44, -1.52, 0.00, 57.95, 58.46 +CTUN, 786, 0.36, 1.80, 0.000000, 0, 0, 15, 786, 0 +ATT, 0.00, 0.88, -6.16, -1.59, 0.00, 58.33, 58.46 +CTUN, 786, 0.37, 1.89, 0.000000, 0, 0, 13, 786, 0 +ATT, 0.00, 0.34, -5.13, -1.77, 0.00, 58.23, 58.46 +DU32, 7, 166140 +CURR, 786, 1269867, 992, 2140, 5051, 955.139830 +CTUN, 786, 0.37, 1.91, 0.000000, 0, 0, 10, 786, 0 +ATT, 0.00, -0.07, -4.66, -1.29, 0.00, 57.76, 58.46 +CTUN, 786, 0.37, 1.92, 0.000000, 0, 0, 7, 786, 0 +ATT, 0.00, -0.40, -4.57, -0.69, 0.00, 57.09, 58.46 +CTUN, 786, 0.37, 1.79, 0.000000, 0, 0, 7, 786, 0 +ATT, 0.00, -0.05, -4.48, -0.60, 0.00, 56.38, 58.46 +CTUN, 786, 0.37, 1.87, 0.000000, 0, 0, 6, 786, 0 +ATT, 0.00, -0.76, -4.29, -0.14, 0.00, 55.60, 58.46 +CTUN, 786, 0.37, 1.85, 0.000000, 0, 0, 4, 786, 0 +ATT, 0.00, -1.02, -4.57, -0.11, 0.00, 54.91, 58.46 +CTUN, 786, 0.37, 1.82, 0.000000, 0, 0, 3, 787, 0 +ATT, 0.00, -0.16, -4.57, -0.12, 0.00, 54.52, 58.46 +CTUN, 786, 0.36, 1.97, 0.000000, 0, 0, 2, 785, 0 +ATT, 0.00, 1.15, -4.48, -0.60, 0.00, 54.48, 58.46 +CTUN, 786, 0.36, 1.75, 0.000000, 0, 0, 1, 786, 0 +ATT, 0.00, 1.37, -4.38, -1.09, 0.00, 54.84, 58.46 +CTUN, 786, 0.34, 1.88, 0.000000, 0, 0, -2, 786, 0 +ATT, 0.00, 0.69, -4.38, -1.11, 0.00, 55.56, 58.46 +CTUN, 786, 0.34, 1.79, 0.000000, 0, 0, -1, 786, 0 +ATT, -0.28, 0.75, -3.26, -1.02, 0.00, 56.65, 58.46 +DU32, 7, 166140 +CURR, 787, 1277727, 1001, 2107, 5051, 961.042660 +CTUN, 786, 0.32, 1.94, 0.000000, 0, 0, -3, 786, 0 +ATT, -2.17, 0.51, -2.14, -1.03, 0.00, 57.73, 58.46 +CTUN, 785, 0.32, 1.79, 0.000000, 0, 0, -4, 786, 0 +ATT, -2.55, -0.23, -2.52, -0.13, 0.00, 58.78, 58.46 +CTUN, 786, 0.29, 1.79, 0.000000, 0, 0, -3, 786, 0 +ATT, -2.46, -1.85, -2.42, 0.33, 0.00, 59.74, 58.46 +CTUN, 785, 0.29, 1.80, 0.000000, 0, 0, -3, 787, 0 +ATT, -2.36, -3.67, -2.14, 0.25, 0.00, 60.55, 58.46 +CTUN, 787, 0.27, 1.65, 0.000000, 0, 1, 0, 788, 0 +ATT, -2.17, -4.20, -2.14, 0.77, 0.00, 61.12, 58.46 +CTUN, 786, 0.27, 1.73, 0.000000, 0, 1, 4, 787, 0 +ATT, -1.80, -3.45, -1.77, 1.16, 0.00, 61.57, 58.46 +CTUN, 786, 0.25, 1.76, 0.000000, 0, 1, 9, 787, 0 +ATT, -1.89, -3.15, -1.86, 1.38, 0.00, 62.01, 58.46 +CTUN, 787, 0.25, 1.93, 0.000000, 0, 1, 11, 788, 0 +ATT, 0.00, -2.74, -3.26, 1.47, 0.00, 62.54, 58.46 +CTUN, 787, 0.24, 1.65, 0.000000, 0, 0, 15, 786, 0 +ATT, 0.00, -2.40, -3.73, 0.53, 0.00, 62.92, 58.46 +CTUN, 786, 0.24, 1.83, 0.000000, 0, 0, 16, 786, 0 +ATT, 0.00, -1.40, -3.82, -0.28, 0.00, 63.21, 58.46 +DU32, 7, 166140 +CURR, 785, 1285589, 1003, 2173, 5028, 966.961730 +CTUN, 785, 0.24, 1.73, 0.000000, 0, 0, 19, 785, 0 +ATT, 0.00, 0.56, -3.92, -0.47, 0.00, 63.29, 58.46 +CTUN, 786, 0.24, 1.73, 0.000000, 0, 0, 20, 786, 0 +ATT, 0.00, 1.34, -4.20, -0.06, 0.00, 63.03, 58.46 +CTUN, 786, 0.24, 1.75, 0.000000, 0, 0, 20, 786, 0 +ATT, 0.00, 0.86, -4.20, -0.49, 0.00, 62.45, 58.46 +CTUN, 786, 0.26, 1.70, 0.000000, 0, 0, 22, 786, 0 +ATT, 0.00, -0.30, -4.20, -1.37, 0.00, 61.56, 58.46 +CTUN, 786, 0.25, 1.64, 0.000000, 0, 0, 21, 785, 0 +ATT, 0.00, -0.08, -4.20, -1.76, 0.00, 60.49, 58.46 +CTUN, 786, 0.26, 1.78, 0.000000, 0, 0, 23, 786, 0 +ATT, 0.00, 0.18, -4.20, -2.14, 0.00, 59.42, 58.46 +CTUN, 785, 0.26, 1.71, 0.000000, 0, 0, 25, 786, 0 +ATT, 0.00, 0.14, -4.20, -2.38, 0.00, 58.42, 58.46 +CTUN, 786, 0.27, 1.83, 0.000000, 0, 0, 23, 785, 0 +ATT, 0.00, -0.38, -4.20, -2.65, 0.00, 57.54, 58.46 +CTUN, 786, 0.27, 1.68, 0.000000, 0, 0, 21, 786, 0 +ATT, 0.00, -0.99, -3.92, -2.41, 0.00, 56.89, 58.46 +CTUN, 785, 0.29, 1.84, 0.000000, 0, 0, 20, 786, 0 +ATT, 0.00, -1.02, -3.45, -1.50, 0.00, 56.54, 58.46 +DU32, 7, 166140 +CURR, 785, 1293448, 1005, 2112, 5051, 972.883060 +CTUN, 785, 0.29, 1.66, 0.000000, 0, 0, 17, 786, 0 +ATT, 0.00, -1.40, -3.45, -0.50, 0.00, 56.27, 58.46 +CTUN, 786, 0.31, 1.72, 0.000000, 0, 0, 18, 785, 0 +ATT, 0.00, -1.36, -3.36, 0.71, 0.00, 55.99, 58.46 +CTUN, 786, 0.31, 1.89, 0.000000, 0, 0, 13, 787, 0 +ATT, 0.00, -0.72, -3.54, 1.61, 0.00, 55.85, 58.46 +CTUN, 786, 0.32, 1.78, 0.000000, 0, 0, 10, 786, 0 +ATT, 0.00, -0.57, -3.45, 1.69, 0.00, 55.90, 58.46 +CTUN, 786, 0.32, 1.71, 0.000000, 0, 0, 7, 787, 0 +ATT, 0.18, -0.68, -3.26, 1.64, 0.00, 56.14, 58.46 +CTUN, 786, 0.32, 1.90, 0.000000, 0, 0, 3, 786, 0 +ATT, 0.18, -0.86, -3.45, 1.49, 0.00, 56.57, 58.46 +CTUN, 785, 0.31, 1.79, 0.000000, 0, 0, 0, 785, 0 +ATT, 0.28, -0.51, -3.45, 1.59, 0.00, 57.08, 58.46 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 786, 0.32, 1.76, 0.000000, 0, 0, 0, 786, 0 +ATT, 0.28, -0.14, -3.45, 1.57, 0.00, 57.43, 58.46 +CTUN, 786, 0.31, 1.64, 0.000000, 0, 0, -2, 786, 0 +ATT, 0.46, 0.09, -3.36, 0.93, 0.00, 57.78, 58.46 +CTUN, 785, 0.31, 1.73, 0.000000, 0, 0, -5, 786, 0 +ATT, 0.46, 0.76, -3.45, -0.19, 0.00, 58.01, 58.46 +DU32, 7, 166140 +CURR, 787, 1301307, 994, 2105, 5051, 978.759830 +CTUN, 786, 0.28, 1.78, 0.000000, 0, 0, -6, 786, 0 +ATT, 0.28, 1.74, -4.10, -0.84, 0.00, 58.14, 58.46 +CTUN, 786, 0.28, 1.73, 0.000000, 0, 0, -6, 786, 0 +ATT, 0.28, 1.33, -5.50, -0.25, 0.00, 58.31, 58.46 +CTUN, 786, 0.26, 1.85, 0.000000, 0, 0, -4, 786, 0 +ATT, 0.46, 0.00, -6.72, 0.32, 0.00, 58.38, 58.46 +CTUN, 785, 0.26, 1.74, 0.000000, 0, 0, 0, 786, 0 +ATT, 0.46, -0.38, -7.00, -0.80, 0.00, 58.51, 58.46 +CTUN, 786, 0.24, 1.74, 0.000000, 0, 0, 4, 786, 0 +ATT, 0.46, 0.28, -6.81, -2.86, 0.00, 58.74, 58.46 +CTUN, 786, 0.24, 1.69, 0.000000, 0, 1, 4, 787, 0 +ATT, 0.56, 0.53, -6.81, -4.56, 0.00, 58.81, 58.46 +CTUN, 786, 0.22, 1.72, 0.000000, 0, 2, 5, 788, 0 +ATT, 0.46, 0.35, -6.72, -4.97, 0.00, 58.86, 58.46 +CTUN, 786, 0.22, 1.68, 0.000000, 0, 2, 11, 788, 0 +ATT, 0.56, 0.81, -6.81, -5.12, 0.00, 58.84, 58.46 +CTUN, 786, 0.22, 1.52, 0.000000, 0, 2, 13, 788, 0 +ATT, 0.75, 1.14, -6.72, -5.41, 0.00, 58.83, 58.46 +CTUN, 786, 0.22, 1.73, 0.000000, 0, 3, 12, 789, 0 +ATT, 1.78, 1.07, -5.78, -5.08, 0.00, 58.88, 58.46 +DU32, 7, 166140 +CURR, 786, 1309178, 997, 2142, 5051, 984.664730 +CTUN, 786, 0.22, 1.70, 0.000000, 0, 2, 15, 788, 0 +ATT, 1.78, 1.86, -4.76, -5.08, 0.00, 58.92, 58.46 +CTUN, 786, 0.22, 1.66, 0.000000, 0, 3, 19, 789, 0 +ATT, 0.46, 3.33, -2.14, -4.32, 0.00, 58.88, 58.46 +CTUN, 786, 0.22, 1.73, 0.000000, 0, 2, 21, 787, 0 +ATT, 0.37, 3.48, -2.24, -2.05, 0.00, 58.82, 58.46 +CTUN, 785, 0.23, 1.66, 0.000000, 0, 1, 21, 787, 0 +ATT, 0.28, 1.97, -2.24, 0.36, 0.00, 58.81, 58.46 +CTUN, 785, 0.23, 1.88, 0.000000, 0, 0, 19, 786, 0 +ATT, 0.00, 0.12, -2.24, 1.24, 0.00, 58.77, 58.46 +CTUN, 786, 0.25, 1.84, 0.000000, 0, 0, 19, 786, 0 +ATT, 0.00, -0.33, -2.24, 1.09, 0.00, 58.73, 58.46 +CTUN, 786, 0.25, 1.90, 0.000000, 0, 0, 20, 786, 0 +ATT, 0.00, -0.42, -2.24, 1.20, 0.00, 58.73, 58.46 +CTUN, 785, 0.29, 1.78, 0.000000, 0, 0, 20, 785, 0 +ATT, 0.00, -0.40, -2.24, 2.06, 0.00, 58.80, 58.46 +CTUN, 787, 0.29, 1.79, 0.000000, 0, 0, 17, 786, 0 +ATT, 0.00, 0.52, -3.26, 3.06, 0.00, 58.87, 58.46 +CTUN, 786, 0.31, 1.76, 0.000000, 0, 1, 15, 787, 0 +ATT, 0.00, 1.15, -4.57, 3.16, 0.00, 59.04, 58.46 +DU32, 7, 166140 +CURR, 787, 1317045, 1002, 2140, 5051, 990.616090 +CTUN, 785, 0.31, 1.99, 0.000000, 0, 0, 12, 785, 0 +ATT, 0.00, 0.51, -5.13, 2.18, 0.00, 59.36, 58.46 +CTUN, 786, 0.33, 1.89, 0.000000, 0, 0, 9, 786, 0 +ATT, 0.00, -0.89, -5.69, 0.18, 0.00, 59.77, 58.46 +CTUN, 786, 0.33, 1.87, 0.000000, 0, 0, 7, 786, 0 +ATT, 0.00, -1.76, -6.81, -1.50, 0.00, 60.28, 58.46 +CTUN, 787, 0.35, 1.83, 0.000000, 0, 0, 5, 786, 0 +ATT, 0.00, -1.83, -7.46, -2.39, -0.09, 60.79, 58.45 +CTUN, 786, 0.35, 1.90, 0.000000, 0, 1, 4, 787, 0 +ATT, 0.00, -1.94, -6.62, -2.61, -0.75, 61.27, 58.25 +CTUN, 786, 0.35, 1.93, 0.000000, 0, 1, 3, 787, 0 +ATT, 0.00, -2.10, -6.16, -2.19, -1.13, 61.48, 57.70 +CTUN, 785, 0.35, 1.85, 0.000000, 0, 0, 0, 786, 0 +ATT, 0.00, -1.63, -5.22, -1.69, -2.26, 61.39, 56.90 +CTUN, 786, 0.35, 1.94, 0.000000, 0, 0, 0, 786, 0 +ATT, 0.00, -1.35, -5.22, -1.04, -2.73, 60.70, 55.72 +CTUN, 786, 0.35, 1.88, 0.000000, 0, 0, 0, 786, 0 +ATT, 0.00, -1.48, -5.22, -0.54, -3.11, 59.55, 54.33 +CTUN, 786, 0.35, 2.05, 0.000000, 0, 0, -2, 786, 0 +ATT, 0.00, -1.04, -5.41, -0.59, -3.39, 57.88, 52.86 +DU32, 7, 166140 +CURR, 786, 1324906, 996, 2133, 5051, 996.541990 +CTUN, 785, 0.33, 1.89, 0.000000, 0, 0, -3, 785, 0 +ATT, 0.00, -0.43, -5.50, -1.16, -3.39, 55.98, 51.29 +CTUN, 786, 0.33, 1.84, 0.000000, 0, 0, -3, 787, 0 +ATT, 0.00, -0.46, -5.69, -1.83, -3.20, 53.94, 49.69 +CTUN, 786, 0.31, 1.80, 0.000000, 0, 0, -1, 786, 0 +ATT, 0.28, -0.61, -5.88, -2.49, -3.20, 51.71, 48.20 +CTUN, 786, 0.31, 1.82, 0.000000, 0, 0, -2, 786, 0 +ATT, 0.18, -0.31, -5.78, -3.38, -3.20, 49.39, 46.71 +CTUN, 787, 0.30, 1.81, 0.000000, 0, 1, 1, 788, 0 +ATT, 0.28, 0.03, -5.88, -3.32, -3.20, 47.15, 45.20 +CTUN, 786, 0.30, 1.81, 0.000000, 0, 0, 2, 786, 0 +ATT, 0.28, 0.89, -4.85, -2.07, -3.20, 45.14, 43.70 +CTUN, 786, 0.28, 1.88, 0.000000, 0, 0, 2, 786, 0 +ATT, 0.28, 1.34, -3.73, -1.28, -3.20, 43.37, 42.19 +CTUN, 786, 0.28, 1.71, 0.000000, 0, 0, 4, 786, 0 +ATT, 0.00, 1.56, -2.24, -0.74, -3.20, 41.78, 40.69 +CTUN, 786, 0.27, 1.77, 0.000000, 0, 0, 6, 786, 0 +ATT, 0.28, 1.28, -2.52, -0.09, -3.20, 40.45, 39.16 +CTUN, 785, 0.27, 1.68, 0.000000, 0, 0, 10, 786, 0 +ATT, 0.00, 1.06, -2.05, 1.07, -3.20, 39.21, 37.66 +DU32, 7, 166140 +CURR, 786, 1332768, 994, 2146, 5051, 1002.471300 +CTUN, 786, 0.26, 1.68, 0.000000, 0, 0, 11, 786, 0 +ATT, 0.00, 1.30, -2.14, 2.76, -3.30, 38.00, 36.16 +CTUN, 786, 0.27, 1.86, 0.000000, 0, 1, 9, 787, 0 +ATT, 0.00, 1.25, -2.14, 3.78, -3.20, 36.76, 34.66 +CTUN, 787, 0.26, 1.87, 0.000000, 0, 1, 7, 788, 0 +ATT, 0.00, 0.81, -3.26, 3.19, -3.20, 35.45, 33.16 +CTUN, 785, 0.27, 1.87, 0.000000, 0, 0, 6, 785, 0 +ATT, 0.00, 0.36, -4.66, 1.57, -3.20, 34.32, 31.66 +CTUN, 786, 0.27, 1.74, 0.000000, 0, 0, 7, 786, 0 +ATT, 0.00, 0.20, -6.06, -0.20, -3.20, 33.24, 30.17 +CTUN, 786, 0.27, 1.72, 0.000000, 0, 0, 10, 786, 0 +ATT, 0.00, 0.84, -6.53, -1.35, -3.20, 32.25, 28.67 +CTUN, 786, 0.27, 1.82, 0.000000, 0, 0, 8, 786, 0 +ATT, 0.00, 0.99, -6.62, -2.53, -3.20, 31.34, 27.17 +CTUN, 785, 0.27, 1.75, 0.000000, 0, 0, 11, 786, 0 +ATT, 0.00, -0.14, -6.53, -3.29, -3.20, 30.23, 25.68 +CTUN, 786, 0.27, 1.76, 0.000000, 0, 1, 9, 787, 0 +ATT, 0.00, -1.10, -6.53, -3.71, -3.20, 28.94, 24.18 +CTUN, 786, 0.28, 1.80, 0.000000, 0, 1, 13, 788, 0 +ATT, 0.00, -1.55, -5.69, -3.46, -3.20, 27.45, 22.69 +DU32, 7, 166140 +CURR, 786, 1340631, 995, 2149, 5028, 1008.435900 +CTUN, 785, 0.28, 1.86, 0.000000, 0, 1, 10, 786, 0 +ATT, 0.00, -1.34, -4.57, -3.01, -3.39, 26.08, 21.18 +CTUN, 786, 0.29, 1.73, 0.000000, 0, 0, 12, 786, 0 +ATT, 0.00, -0.58, -4.57, -2.05, -3.77, 24.57, 19.48 +CTUN, 785, 0.29, 1.69, 0.000000, 0, 0, 10, 785, 0 +ATT, 0.00, -0.13, -4.48, -1.33, -3.96, 22.89, 17.64 +CTUN, 785, 0.29, 1.88, 0.000000, 0, 0, 9, 785, 0 +ATT, 0.00, -0.91, -3.64, -0.95, -4.15, 20.90, 15.77 +CTUN, 782, 0.29, 1.82, 0.000000, 0, 0, 7, 782, 0 +ATT, 0.00, -1.04, -3.08, -1.16, -4.24, 18.69, 13.86 +CTUN, 782, 0.30, 1.84, 0.000000, 0, 0, 7, 782, 0 +ATT, 0.00, 0.02, -3.26, -1.21, -4.15, 16.41, 11.98 +CTUN, 782, 0.30, 1.93, 0.000000, 0, 0, 5, 782, 0 +ATT, 0.00, 0.49, -3.26, -0.69, -4.52, 14.42, 9.99 +CTUN, 776, 0.31, 1.83, 0.000000, 0, 0, 5, 780, 0 +ATT, 0.00, -0.67, -2.70, -0.09, -4.52, 12.41, 7.89 +CTUN, 773, 0.31, 2.02, 0.000000, 0, 0, 4, 773, 0 +ATT, 0.00, -1.82, -2.42, -0.23, -4.52, 10.35, 5.81 +CTUN, 773, 0.31, 1.93, 0.000000, 0, 0, 2, 773, 0 +ATT, 0.00, -1.24, -2.70, 0.22, -4.62, 7.97, 3.74 +DU32, 7, 166140 +CURR, 774, 1348448, 992, 2092, 5028, 1014.345000 +CTUN, 774, 0.31, 2.10, 0.000000, 0, 0, 1, 774, 0 +ATT, 0.00, 0.42, -2.89, 0.89, -4.71, 5.62, 1.55 +CTUN, 774, 0.31, 2.04, 0.000000, 0, 0, 0, 774, 0 +ATT, 0.00, 0.79, -3.26, 1.20, -4.62, 3.38, 359.42 +CTUN, 773, 0.31, 1.89, 0.000000, 0, 0, 0, 774, 0 +ATT, 0.00, -0.48, -3.64, 0.62, -5.09, 1.24, 357.17 +CTUN, 773, 0.31, 1.84, 0.000000, 0, 0, 0, 773, 0 +ATT, 0.00, -0.78, -3.73, -0.18, -5.09, 359.16, 354.87 +CTUN, 773, 0.31, 1.82, 0.000000, 0, 0, -2, 773, 0 +ATT, 0.00, -0.54, -4.57, -0.69, -5.09, 357.13, 352.56 +CTUN, 774, 0.31, 1.88, 0.000000, 0, 0, 0, 773, 0 +ATT, 0.00, -0.36, -5.04, -0.68, -5.37, 355.12, 350.10 +CTUN, 773, 0.29, 1.84, 0.000000, 0, 0, -4, 773, 0 +ATT, 0.00, -0.68, -5.60, -1.30, -5.37, 352.95, 347.61 +CTUN, 774, 0.29, 1.83, 0.000000, 0, 0, -4, 774, 0 +ATT, 0.00, -0.81, -5.69, -2.32, -5.47, 350.63, 345.14 +CTUN, 773, 0.29, 1.93, 0.000000, 0, 0, -8, 773, 0 +ATT, 0.00, -0.74, -5.78, -3.23, -5.09, 348.26, 342.73 +CTUN, 773, 0.29, 1.84, 0.000000, 0, 1, -8, 774, 0 +ATT, 0.00, -0.49, -6.16, -3.57, -4.90, 345.84, 340.43 +DU32, 7, 166140 +CURR, 773, 1356184, 1008, 2054, 5051, 1020.115400 +CTUN, 773, 0.27, 1.81, 0.000000, 0, 1, -7, 774, 0 +ATT, 0.00, -0.43, -6.53, -3.32, -4.33, 343.16, 338.29 +CTUN, 774, 0.27, 1.83, 0.000000, 0, 1, -9, 775, 0 +ATT, 0.00, -0.79, -6.53, -3.50, -3.77, 340.54, 336.40 +CTUN, 774, 0.23, 1.89, 0.000000, 0, 1, -10, 775, 0 +ATT, 0.00, -1.68, -5.97, -3.97, -3.01, 338.15, 334.81 +CTUN, 767, 0.23, 1.78, 0.000000, 0, 1, -11, 767, 0 +ATT, 0.00, -1.98, -5.50, -4.15, 0.00, 336.15, 334.30 +CTUN, 765, 0.21, 1.83, 0.000000, 0, 1, -6, 766, 0 +ATT, 0.09, -1.68, -5.41, -3.91, 0.00, 334.67, 334.30 +CTUN, 765, 0.21, 1.89, 0.000000, 0, 1, -4, 766, 0 +ATT, 1.31, -0.85, -5.88, -2.95, 0.00, 333.80, 334.30 +CTUN, 765, 0.20, 1.82, 0.000000, 0, 0, -3, 765, 0 +ATT, 2.53, 0.61, -6.06, -2.00, 0.00, 333.37, 334.30 +CTUN, 765, 0.20, 1.55, 0.000000, 0, 0, 0, 765, 0 +ATT, 3.56, 2.20, -5.69, -2.21, 0.00, 333.26, 334.30 +CTUN, 765, 0.20, 1.41, 0.000000, 0, 1, 1, 766, 0 +ATT, 3.56, 4.01, -4.85, -2.62, 0.00, 333.40, 334.30 +CTUN, 765, 0.20, 1.34, 0.000000, 0, 2, 4, 767, 0 +ATT, 6.37, 4.60, -2.14, -2.26, 0.00, 333.92, 334.30 +DU32, 7, 166140 +CURR, 765, 1363878, 999, 2022, 5051, 1025.738600 +CTUN, 764, 0.20, 1.40, 0.000000, 0, 2, 8, 766, 0 +ATT, 9.09, 5.12, -2.14, -1.33, 0.00, 334.90, 334.30 +CTUN, 759, 0.20, 1.57, 0.000000, 0, 3, 9, 763, 0 +ATT, 10.31, 7.74, 0.00, -0.03, 0.00, 336.05, 334.30 +CTUN, 755, 0.20, 1.54, 0.000000, 0, 8, 12, 763, 0 +ATT, 9.28, 10.62, 2.33, 1.03, 0.00, 337.19, 334.30 +CTUN, 751, 0.20, 1.62, 0.000000, 0, 12, 7, 765, 0 +ATT, 7.68, 11.10, 10.36, 1.49, 0.00, 338.20, 334.30 +CTUN, 748, 0.20, 1.68, 0.000000, 0, 11, 4, 759, 0 +ATT, 3.37, 9.98, 11.67, 3.60, 0.00, 339.40, 334.30 +CTUN, 748, 0.20, 1.74, 0.000000, 0, 9, 1, 757, 0 +ATT, 0.00, 7.25, 14.56, 7.22, 0.00, 340.27, 334.30 +CTUN, 747, 0.20, 1.71, 0.000000, 0, 11, -3, 757, 0 +ATT, 0.46, 4.37, 21.19, 11.13, 0.00, 340.52, 334.30 +CTUN, 745, 0.20, 1.70, 0.000000, 0, 17, -6, 762, 0 +ATT, 0.00, 2.26, 19.88, 15.58, 0.00, 340.08, 334.30 +CTUN, 745, 0.20, 1.72, 0.000000, 0, 30, -14, 775, 0 +ATT, -0.18, 0.93, 6.16, 19.17, 0.00, 339.50, 334.30 +CTUN, 745, 0.20, 1.58, 0.000000, 0, 37, -25, 782, 0 +ATT, -11.27, -0.42, 1.77, 18.63, 0.00, 338.84, 334.30 +DU32, 7, 166140 +CURR, 746, 1371525, 1005, 2170, 5051, 1031.436600 +CTUN, 747, 0.20, 1.74, 0.000000, 0, 25, -34, 772, 0 +ATT, -24.34, -4.35, 0.00, 12.53, 0.00, 338.40, 334.30 +CTUN, 746, 0.20, 0.77, 0.000000, 0, 13, -34, 759, 0 +ATT, -31.54, -13.67, -4.10, 4.16, 0.00, 338.50, 334.30 +CTUN, 746, 0.20, 0.80, 0.000000, 0, 30, -29, 776, 0 +ATT, -30.31, -20.75, -9.33, 0.31, 0.00, 339.19, 334.30 +CTUN, 746, 0.20, 0.91, 0.000000, 0, 33, -13, 779, 0 +ATT, -20.08, -14.57, -16.89, 8.07, 0.00, 340.79, 334.30 +CTUN, 741, 0.20, 1.04, 0.000000, 0, 19, -26, 763, 0 +ATT, -2.93, -7.99, -23.06, 7.13, 0.00, 347.90, 337.90 +CTUN, 730, 0.20, 1.12, 0.000000, 0, 6, -44, 740, 0 +ATT, 0.00, -5.73, -22.96, -1.95, 0.00, 355.03, 345.03 +CTUN, 708, 0.20, -1.26, 0.000000, 0, 1, -21, 720, 0 +ATT, -7.76, 0.38, -18.85, -0.95, 0.00, 0.42, 350.42 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 680, 2.10, -1.42, 0.000000, 0, 0, -13, 674, 0 +ATT, -16.10, -5.52, -16.89, -0.65, 0.00, 1.77, 351.77 +CTUN, 680, 2.10, -1.53, 0.000000, 0, 2, -12, 682, 0 +ATT, -18.47, -3.73, -14.09, -7.13, 0.00, 6.65, 356.65 +CTUN, 680, 6.51, -1.51, 0.000000, 0, 8, -6, 688, 0 +ATT, -20.65, -5.28, -10.82, -10.06, 2.11, 10.85, 0.85 +DU32, 7, 166140 +CURR, 677, 1378887, 1012, 1885, 5028, 1036.539800 +CTUN, 681, 6.51, -0.32, 0.000000, 0, 13, -11, 684, 0 +ATT, -21.97, -10.59, -8.49, -7.74, 6.15, 13.76, 3.83 +CTUN, 692, 6.51, 0.51, 0.000000, 0, 19, -14, 712, 0 +ATT, -18.00, -16.33, -8.21, -3.85, 6.05, 15.99, 6.86 +CTUN, 694, 1.62, 0.80, 0.000000, 0, 28, -23, 720, 0 +ATT, -4.64, -19.02, -8.49, -1.42, 3.36, 18.32, 8.80 +CTUN, 692, 1.62, 1.15, 0.000000, 0, 31, -32, 723, 0 +ATT, 0.00, -16.13, -10.64, -0.53, 0.38, 20.78, 10.78 +CTUN, 692, 0.20, 1.02, 0.000000, 0, 15, -41, 707, 0 +ATT, 0.00, -8.70, -10.64, -1.43, 0.00, 22.27, 12.27 +CTUN, 684, 0.20, 0.94, 0.000000, 0, 3, -38, 693, 0 +ATT, 0.00, -3.41, -8.12, -3.14, 0.00, 22.90, 12.90 +CTUN, 680, 0.20, 0.19, 0.000000, 0, 1, -37, 681, 0 +ATT, 3.09, -1.96, -2.42, -4.17, 2.59, 22.81, 13.39 +CTUN, 680, 0.22, -0.99, 0.000000, 0, 1, -35, 681, 0 +ATT, 3.65, -1.01, -2.80, -3.63, 14.23, 22.03, 17.92 +CTUN, 687, 0.21, -0.47, 0.000000, 0, 0, -33, 687, 0 +ATT, 10.03, 0.45, -6.53, -1.89, 15.09, 21.91, 24.49 +CTUN, 684, 0.21, -1.18, 0.000000, 0, 0, -34, 686, 0 +ATT, 18.00, 3.60, -6.72, -1.16, 18.36, 22.92, 31.87 +DU32, 7, 166140 +CURR, 680, 1385862, 1025, 1705, 5051, 1041.508200 +CTUN, 674, 0.20, -1.24, 0.000000, 0, 2, -28, 680, 0 +ATT, 22.59, 5.08, -4.76, 0.57, 19.90, 26.46, 36.46 +CTUN, 669, 0.20, -1.02, 0.000000, 0, 3, -26, 672, 0 +ATT, 15.00, 10.13, -2.33, 0.66, 18.46, 31.86, 41.86 +CTUN, 669, 0.20, -0.99, 0.000000, 0, 11, -23, 680, 0 +ATT, 7.03, 10.82, -2.33, 2.07, 13.55, 37.89, 47.82 +CTUN, 670, 0.20, -0.42, 0.000000, 0, 9, -32, 679, 0 +ATT, 0.00, 9.15, -2.52, 2.92, 5.57, 44.13, 51.69 +CTUN, 671, 0.20, -0.42, 0.000000, 0, 5, -39, 676, 0 +ATT, 0.00, 4.73, -2.52, 1.25, 0.00, 49.50, 52.50 +CTUN, 671, 0.20, -0.77, 0.000000, 0, 0, -45, 672, 0 +ATT, -1.13, 1.03, -3.45, -0.68, 0.00, 53.59, 52.50 +CTUN, 707, 0.20, -1.12, 0.000000, 0, 0, -48, 707, 0 +ATT, -3.22, 0.17, -3.17, -1.47, 0.00, 56.66, 52.50 +CTUN, 746, 0.20, -0.94, 0.000000, 0, 0, -48, 744, 0 +ATT, -2.74, -1.05, -5.78, -1.95, 0.00, 58.72, 52.50 +CTUN, 755, 0.20, -1.77, 0.000000, 0, 0, -41, 755, 0 +ATT, 0.00, -2.60, -5.69, -2.18, 0.00, 59.75, 52.50 +CTUN, 755, 0.21, -1.66, 0.000000, 0, 1, -24, 755, 0 +ATT, 0.00, -2.80, -5.60, -0.76, 0.00, 60.08, 52.50 +DU32, 7, 166140 +CURR, 756, 1392858, 1013, 2077, 5051, 1046.405300 +CTUN, 763, 0.21, -1.22, 0.000000, 0, 0, -14, 763, 0 +ATT, 0.00, -2.83, -5.22, 0.37, 0.00, 59.94, 52.50 +CTUN, 765, 0.21, -0.71, 0.000000, 0, 0, -9, 765, 0 +ATT, 0.00, -2.83, -5.32, 0.00, 0.00, 59.48, 52.50 +CTUN, 764, 0.20, 0.67, 0.000000, 0, 0, -7, 765, 0 +ATT, 0.00, -2.31, -5.69, -0.77, 0.00, 58.52, 52.50 +CTUN, 755, 0.20, 1.52, 0.000000, 0, 0, -4, 759, 0 +ATT, 0.00, -1.76, -7.56, -1.47, 0.00, 57.22, 52.50 +CTUN, 753, 0.20, 1.69, 0.000000, 0, 0, -6, 752, 0 +ATT, 1.40, -0.81, -10.64, -2.33, 0.00, 55.90, 52.50 +CTUN, 754, 0.20, 1.83, 0.000000, 0, 0, -8, 754, 0 +ATT, 6.84, 0.85, -10.92, -3.99, 0.00, 54.59, 52.50 +CTUN, 753, 0.20, 1.98, 0.000000, 0, 2, -12, 755, 0 +ATT, 8.62, 3.27, -11.29, -6.02, 0.00, 53.23, 52.50 +CTUN, 752, 0.24, 1.76, 0.000000, 0, 6, -14, 758, 0 +ATT, 8.81, 6.71, -11.57, -6.86, 0.00, 52.00, 52.50 +CTUN, 753, 0.24, 1.86, 0.000000, 0, 10, -18, 763, 0 +ATT, 8.62, 9.25, -11.10, -7.35, 0.00, 50.91, 52.50 +CTUN, 753, 0.26, 1.96, 0.000000, 0, 14, -28, 766, 0 +ATT, 7.40, 10.24, -10.92, -7.12, 0.00, 50.03, 52.50 +DU32, 7, 166140 +CURR, 752, 1400465, 997, 2003, 5028, 1051.960300 +CTUN, 753, 0.26, 1.95, 0.000000, 0, 14, -33, 767, 0 +ATT, 2.53, 9.32, -8.30, -6.16, 0.00, 49.34, 52.50 +CTUN, 755, 0.27, 1.92, 0.000000, 0, 10, -33, 764, 0 +ATT, 0.00, 7.26, -4.76, -5.05, 0.00, 48.67, 52.50 +CTUN, 755, 0.27, 2.07, 0.000000, 0, 4, -34, 759, 0 +ATT, -5.77, -1.59, -2.42, 0.73, 0.00, 47.94, 52.50 +CTUN, 741, 0.27, 1.81, 0.000000, 0, 1, -34, 742, 0 +ATT, -9.75, -3.71, -2.42, 3.63, 0.00, 47.50, 52.50 +CTUN, 742, 0.27, 1.83, 0.000000, 0, 3, -38, 744, 0 +ATT, -10.04, -6.43, -3.45, 4.26, 0.00, 47.40, 52.50 +CTUN, 742, 0.27, 1.84, 0.000000, 0, 7, -41, 748, 0 +ATT, -6.91, -10.04, -6.72, 2.13, 0.00, 47.87, 52.50 +CTUN, 741, 0.24, 1.83, 0.000000, 0, 11, -44, 753, 0 +ATT, -4.16, -10.85, -8.21, -1.43, 0.00, 48.76, 52.50 +CTUN, 741, 0.24, 1.76, 0.000000, 0, 10, -42, 751, 0 +ATT, 0.00, -8.74, -8.77, -4.40, 0.00, 49.30, 52.50 +CTUN, 741, 0.20, 1.29, 0.000000, 0, 7, -37, 749, 0 +ATT, 0.00, -5.52, -6.81, -5.85, 0.00, 49.23, 52.50 +CTUN, 742, 0.20, 0.46, 0.000000, 0, 4, -31, 745, 0 +ATT, 0.18, -3.07, -2.05, -4.90, 0.00, 48.93, 52.50 +DU32, 7, 166140 +CURR, 741, 1407990, 1017, 1927, 5051, 1057.430900 +CTUN, 740, 0.20, -0.68, 0.000000, 0, 1, -23, 741, 0 +ATT, 1.59, -1.33, -1.21, -1.90, 0.00, 48.80, 52.50 +CTUN, 741, 0.20, -0.98, 0.000000, 0, 0, -13, 740, 0 +ATT, 0.84, -0.58, 0.00, 1.74, 0.00, 48.80, 52.50 +CTUN, 741, 0.20, -1.50, 0.000000, 0, 0, -9, 741, 0 +ATT, 0.09, 0.01, 0.00, 3.41, 0.00, 48.94, 52.50 +CTUN, 741, 0.20, -1.33, 0.000000, 0, 1, 0, 742, 0 +ATT, 0.00, 0.74, 0.00, 3.79, 0.00, 49.26, 52.50 +CTUN, 740, 0.20, -1.17, 0.000000, 0, 1, 1, 742, 0 +ATT, 0.00, 0.45, 0.00, 3.66, 0.00, 49.60, 52.50 +CTUN, 740, 0.20, -0.45, 0.000000, 0, 1, 5, 741, 0 +ATT, 0.00, 0.11, 0.00, 3.64, 0.00, 50.08, 52.50 +CTUN, 740, 0.20, 0.55, 0.000000, 0, 1, 4, 742, 0 +ATT, 0.00, 0.08, 0.00, 4.61, 0.00, 50.65, 52.50 +CTUN, 740, 0.20, 1.12, 0.000000, 0, 2, 5, 742, 0 +ATT, 0.00, -0.27, 0.00, 5.92, 0.00, 51.33, 52.50 +CTUN, 740, 0.20, 1.51, 0.000000, 0, 3, 1, 744, 0 +ATT, 0.00, -0.41, 0.00, 5.49, 0.00, 51.97, 52.50 +CTUN, 740, 0.20, 1.62, 0.000000, 0, 2, -1, 742, 0 +ATT, 0.00, -0.26, -0.84, 4.04, 0.00, 52.46, 52.50 +DU32, 7, 166140 +CURR, 740, 1415407, 1008, 1897, 5051, 1062.697600 +CTUN, 740, 0.20, 1.83, 0.000000, 0, 1, -3, 741, 0 +ATT, 0.00, -0.15, -2.52, 2.82, 0.00, 52.86, 52.50 +CTUN, 736, 0.20, 1.84, 0.000000, 0, 0, -7, 736, 0 +ATT, 0.00, 0.00, -2.42, 1.94, 0.00, 53.10, 52.50 +CTUN, 736, 0.20, 1.93, 0.000000, 0, 0, -10, 735, 0 +ATT, 0.00, 0.21, -2.42, 1.30, 0.00, 53.27, 52.50 +CTUN, 736, 0.20, 1.84, 0.000000, 0, 0, -13, 736, 0 +ATT, 0.00, 0.36, -4.48, 1.08, 0.00, 53.38, 52.50 +CTUN, 737, 0.20, 1.80, 0.000000, 0, 0, -15, 737, 0 +ATT, 0.00, -0.02, -4.76, 0.72, 0.00, 53.39, 52.50 +CTUN, 742, 0.20, 1.65, 0.000000, 0, 0, -17, 741, 0 +ATT, 0.00, -0.32, -4.76, -0.54, 0.00, 53.36, 52.50 +CTUN, 745, 0.20, 1.43, 0.000000, 0, 0, -22, 745, 0 +ATT, 0.09, -0.90, -4.85, -1.55, 0.00, 53.24, 52.50 +CTUN, 751, 0.20, 0.99, 0.000000, 0, 0, -20, 751, 0 +ATT, 1.03, -1.45, -5.60, -2.22, 0.00, 53.10, 52.50 +CTUN, 768, 0.20, 1.16, 0.000000, 0, 0, -18, 767, 0 +ATT, 1.03, -0.96, -5.69, -2.26, 0.00, 52.94, 52.50 +CTUN, 782, 0.20, 0.85, 0.000000, 0, 0, -12, 782, 0 +ATT, 1.40, -0.19, -5.69, -2.20, 0.00, 52.68, 52.50 +DU32, 7, 166140 +CURR, 782, 1422866, 1004, 2076, 5051, 1068.017600 +CTUN, 788, 0.20, 0.98, 0.000000, 0, 0, -1, 786, 0 +ATT, 1.59, 0.25, -5.69, -1.72, 0.00, 52.43, 52.50 +CTUN, 789, 0.20, 0.32, 0.000000, 0, 0, 3, 788, 0 +ATT, 2.06, 0.49, -5.69, -1.44, 0.00, 52.09, 52.50 +CTUN, 789, 0.20, 1.01, 0.000000, 0, 0, 8, 789, 0 +ATT, 2.06, 0.61, -5.69, -1.75, 0.00, 51.71, 52.50 +CTUN, 789, 0.20, 0.91, 0.000000, 0, 0, 16, 789, 0 +ATT, 2.34, 0.35, -5.69, -1.99, 0.00, 51.46, 52.50 +CTUN, 789, 0.20, 1.62, 0.000000, 0, 0, 22, 789, 0 +ATT, 2.34, 0.36, -5.22, -2.24, 0.00, 51.34, 52.50 +CTUN, 789, 0.20, 1.85, 0.000000, 0, 0, 24, 789, 0 +ATT, 3.18, 0.72, -5.04, -2.24, 0.00, 51.27, 52.50 +CTUN, 789, 0.20, 1.80, 0.000000, 0, 0, 28, 789, 0 +ATT, 3.93, 1.30, -4.85, -2.42, 0.00, 51.17, 52.50 +CTUN, 789, 0.21, 1.95, 0.000000, 0, 0, 29, 789, 0 +ATT, 3.93, 2.02, -4.85, -2.40, 0.00, 51.07, 52.50 +CTUN, 789, 0.21, 1.93, 0.000000, 0, 1, 25, 791, 0 +ATT, 4.50, 2.88, -4.76, -2.33, 0.00, 50.94, 52.50 +CTUN, 789, 0.26, 2.12, 0.000000, 0, 1, 26, 790, 0 +ATT, 4.50, 3.02, -4.85, -1.77, 0.00, 50.74, 52.50 +DU32, 7, 166140 +CURR, 789, 1430750, 998, 2135, 5028, 1073.940600 +CTUN, 790, 0.26, 1.95, 0.000000, 0, 1, 23, 790, 0 +ATT, 3.75, 3.59, -4.76, -1.34, 0.00, 50.42, 52.50 +CTUN, 789, 0.31, 2.11, 0.000000, 0, 1, 18, 790, 0 +ATT, 3.28, 3.61, -4.48, -1.13, 0.00, 49.99, 52.50 +CTUN, 789, 0.31, 2.05, 0.000000, 0, 1, 14, 791, 0 +ATT, 1.78, 2.72, -3.08, -0.99, 0.00, 49.57, 52.50 +CTUN, 796, 0.36, 2.14, 0.000000, 0, 0, 8, 796, 0 +ATT, 0.00, 1.23, -2.24, -0.53, 0.00, 49.05, 52.50 +CTUN, 800, 0.36, 2.00, 0.000000, 0, 0, 9, 798, 0 +ATT, 0.00, -0.84, -2.24, 0.56, 0.00, 48.43, 52.50 +CTUN, 804, 0.39, 2.07, 0.000000, 0, 0, 5, 804, 0 +ATT, 0.00, -1.71, -2.52, 1.40, 0.00, 47.83, 52.50 +CTUN, 804, 0.39, 2.17, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, -1.27, -2.70, 1.84, 0.00, 47.51, 52.50 +CTUN, 813, 0.40, 2.14, 0.000000, 0, 0, 3, 813, 0 +ATT, 0.00, -0.83, -3.26, 1.71, 0.00, 47.29, 52.50 +CTUN, 819, 0.39, 2.14, 0.000000, 0, 0, 4, 818, 0 +ATT, 0.00, -1.00, -3.26, 1.14, 0.00, 47.20, 52.50 +CTUN, 830, 0.40, 2.21, 0.000000, 0, 0, 5, 828, 0 +ATT, 0.00, -1.06, -3.45, 0.85, 0.00, 47.27, 52.50 +DU32, 7, 166140 +CURR, 830, 1438770, 987, 2284, 5051, 1079.993700 +CTUN, 830, 0.40, 2.22, 0.000000, 0, 0, 8, 830, 0 +ATT, 0.00, -0.67, -3.92, 0.54, 0.00, 47.41, 52.50 +CTUN, 834, 0.40, 2.24, 0.000000, 0, 0, 11, 834, 0 +ATT, 0.00, -0.33, -4.20, 0.20, 0.00, 47.57, 52.50 +CTUN, 834, 0.40, 2.34, 0.000000, 0, 0, 12, 834, 0 +ATT, 0.00, 0.04, -4.57, 0.26, 0.00, 47.76, 52.50 +CTUN, 834, 0.40, 2.22, 0.000000, 0, 0, 17, 834, 0 +ATT, 0.09, 0.16, -4.57, 0.55, 0.00, 47.89, 52.50 +CTUN, 834, 0.40, 2.17, 0.000000, 0, 0, 22, 834, 0 +ATT, 0.18, 0.19, -4.57, 0.04, 0.00, 47.85, 52.50 +CTUN, 833, 0.41, 2.39, 0.000000, 0, 0, 21, 833, 0 +ATT, 0.28, 0.55, -4.57, -1.31, 0.00, 47.85, 52.50 +CTUN, 831, 0.41, 2.31, 0.000000, 0, 0, 22, 831, 0 +ATT, 0.37, 1.14, -4.57, -2.06, 0.00, 47.92, 52.50 +CTUN, 831, 0.43, 2.13, 0.000000, 0, 0, 25, 831, 0 +ATT, 0.28, 1.15, -5.04, -2.04, 0.00, 48.03, 52.50 +CTUN, 830, 0.43, 2.29, 0.000000, 0, 0, 26, 830, 0 +ATT, 0.28, 1.34, -6.81, -2.22, 0.00, 48.19, 52.50 +CTUN, 824, 0.46, 2.25, 0.000000, 0, 0, 30, 825, 0 +ATT, 0.09, 1.72, -6.81, -2.34, 0.00, 48.35, 52.50 +DU32, 7, 166140 +CURR, 821, 1447086, 988, 2314, 5051, 1086.510400 +CTUN, 821, 0.46, 2.40, 0.000000, 0, 0, 31, 821, 0 +ATT, 0.00, 1.26, -6.72, -2.53, 0.00, 48.50, 52.50 +CTUN, 821, 0.49, 2.52, 0.000000, 0, 0, 29, 821, 0 +ATT, 0.00, 0.61, -6.53, -3.07, 0.00, 48.49, 52.50 +CTUN, 815, 0.49, 2.54, 0.000000, 0, 1, 29, 816, 0 +ATT, 0.00, 0.53, -6.16, -3.51, 0.00, 48.40, 52.50 +CTUN, 803, 0.52, 2.36, 0.000000, 0, 1, 30, 806, 0 +ATT, 0.00, 0.74, -6.06, -2.97, 0.00, 48.23, 52.50 +CTUN, 796, 0.52, 2.46, 0.000000, 0, 0, 30, 796, 0 +ATT, 0.00, 0.60, -6.25, -2.34, 0.00, 48.08, 52.50 +CTUN, 795, 0.55, 2.41, 0.000000, 0, 0, 25, 795, 0 +ATT, 0.00, 0.24, -6.25, -2.39, 0.00, 48.01, 52.50 +CTUN, 795, 0.55, 2.33, 0.000000, 0, 0, 20, 794, 0 +ATT, 0.00, -0.31, -6.53, -3.01, 0.00, 47.90, 52.50 +PM, 0, 0, 0, 1, 1000, 111708, 0, 0 +CTUN, 795, 0.58, 2.48, 0.000000, 0, 1, 14, 796, 0 +ATT, 0.00, -0.76, -6.06, -3.53, 0.00, 47.91, 52.50 +CTUN, 795, 0.58, 2.33, 0.000000, 0, 1, 11, 796, 0 +ATT, 0.00, -0.35, -6.06, -3.86, 0.00, 48.05, 52.50 +CTUN, 796, 0.58, 2.40, 0.000000, 0, 1, 7, 797, 0 +ATT, 0.00, -0.10, -5.97, -3.62, 0.00, 48.26, 52.50 +DU32, 7, 166140 +CURR, 798, 1455130, 997, 2134, 5051, 1092.585100 +CTUN, 798, 0.58, 2.44, 0.000000, 0, 1, 6, 799, 0 +ATT, 0.00, -0.38, -4.76, -2.79, 0.00, 48.61, 52.50 +CTUN, 804, 0.58, 2.41, 0.000000, 0, 0, 2, 804, 0 +ATT, 0.00, -0.16, -4.57, -1.57, 0.00, 49.11, 52.50 +CTUN, 810, 0.57, 2.31, 0.000000, 0, 0, 0, 807, 0 +ATT, 0.00, 0.04, -4.38, -0.53, 0.00, 49.76, 52.50 +CTUN, 814, 0.57, 2.37, 0.000000, 0, 0, -1, 814, 0 +ATT, -0.18, -0.16, -2.70, 0.16, 0.00, 50.50, 52.50 +CTUN, 823, 0.53, 2.35, 0.000000, 0, 0, -3, 823, 0 +ATT, -0.75, -0.29, -2.70, 0.75, 0.00, 51.20, 52.50 +CTUN, 831, 0.53, 2.36, 0.000000, 0, 0, -3, 830, 0 +ATT, -0.75, 0.04, -2.42, 1.39, 0.00, 51.82, 52.50 +CTUN, 836, 0.50, 2.40, 0.000000, 0, 0, -4, 836, 0 +ATT, -0.75, 0.28, -2.52, 1.43, 0.00, 52.27, 52.50 +CTUN, 838, 0.50, 2.25, 0.000000, 0, 0, -1, 837, 0 +ATT, -0.94, 0.34, -2.70, 1.37, 0.00, 52.42, 52.50 +CTUN, 840, 0.46, 2.30, 0.000000, 0, 0, 0, 840, 0 +ATT, -1.13, 0.64, -2.89, 1.59, 0.00, 52.52, 52.50 +CTUN, 844, 0.46, 2.13, 0.000000, 0, 0, 3, 844, 0 +ATT, -1.80, 0.39, -1.96, 1.63, 0.00, 52.62, 52.50 +DU32, 7, 166140 +CURR, 846, 1463348, 984, 2402, 5051, 1098.897700 +CTUN, 847, 0.42, 2.18, 0.000000, 0, 0, 7, 847, 0 +ATT, -2.55, 0.77, -2.52, 1.67, 0.00, 52.82, 52.50 +CTUN, 846, 0.42, 1.99, 0.000000, 0, 0, 12, 846, 0 +ATT, -3.69, 0.82, -3.64, 1.49, 0.00, 53.13, 52.50 +CTUN, 847, 0.40, 2.24, 0.000000, 0, 0, 10, 847, 0 +ATT, -3.69, 0.19, -3.54, 0.40, 0.00, 53.44, 52.50 +CTUN, 846, 0.40, 2.16, 0.000000, 0, 0, 13, 846, 0 +ATT, -3.69, -1.46, -6.53, -1.23, 0.00, 53.61, 52.50 +CTUN, 844, 0.39, 2.14, 0.000000, 0, 0, 18, 844, 0 +ATT, -3.78, -2.52, -7.84, -2.89, 0.00, 53.78, 52.50 +CTUN, 842, 0.40, 2.03, 0.000000, 0, 2, 23, 844, 0 +ATT, -3.78, -2.61, -7.84, -4.55, 0.00, 53.77, 52.50 +CTUN, 840, 0.39, 2.08, 0.000000, 0, 3, 26, 843, 0 +ATT, -3.97, -2.16, -7.56, -5.48, 0.00, 53.79, 52.50 +CTUN, 838, 0.40, 2.00, 0.000000, 0, 3, 30, 841, 0 +ATT, -3.97, -2.58, -7.56, -5.48, 0.00, 53.95, 52.50 +CTUN, 835, 0.40, 2.19, 0.000000, 0, 4, 35, 840, 0 +ATT, -3.69, -3.80, -7.46, -4.82, 0.00, 54.16, 52.50 +CTUN, 830, 0.43, 2.17, 0.000000, 0, 3, 37, 833, 0 +ATT, -2.93, -3.90, -7.18, -4.34, 0.00, 54.26, 52.50 +DU32, 7, 166140 +CURR, 828, 1471782, 983, 2375, 5051, 1105.572000 +CTUN, 826, 0.43, 2.37, 0.000000, 0, 3, 38, 829, 0 +ATT, -1.80, -3.18, -6.72, -4.14, 0.00, 54.10, 52.50 +CTUN, 824, 0.47, 2.29, 0.000000, 0, 2, 42, 828, 0 +ATT, -0.94, -1.56, -6.72, -3.36, 0.00, 53.48, 52.50 +CTUN, 821, 0.47, 2.48, 0.000000, 0, 0, 40, 821, 0 +ATT, 0.00, -0.64, -6.06, -2.07, 0.00, 52.70, 52.50 +CTUN, 815, 0.51, 2.49, 0.000000, 0, 0, 40, 815, 0 +ATT, 0.00, -0.93, -4.76, -1.12, 0.00, 51.93, 52.50 +CTUN, 813, 0.51, 2.52, 0.000000, 0, 0, 41, 813, 0 +ATT, 0.00, 0.67, -4.57, -0.64, 0.00, 51.09, 52.50 +CTUN, 813, 0.57, 2.65, 0.000000, 0, 0, 39, 813, 0 +ATT, 0.00, 2.02, -4.57, -0.49, 0.00, 50.07, 52.50 +CTUN, 813, 0.57, 2.55, 0.000000, 0, 0, 35, 813, 0 +ATT, 0.00, 2.17, -4.38, -0.73, 0.00, 49.15, 52.50 +CTUN, 813, 0.61, 2.63, 0.000000, 0, 0, 29, 813, 0 +ATT, 0.00, 1.79, -4.57, -0.91, 0.00, 48.46, 52.50 +CTUN, 813, 0.61, 2.56, 0.000000, 0, 0, 25, 813, 0 +ATT, -0.94, 1.66, -3.92, -0.95, 0.00, 48.13, 52.50 +CTUN, 812, 0.64, 2.59, 0.000000, 0, 0, 22, 813, 0 +ATT, -1.32, 0.91, -3.73, -0.13, 0.00, 48.18, 52.50 +DU32, 7, 166140 +CURR, 813, 1479959, 987, 2201, 5051, 1111.829200 +CTUN, 812, 0.64, 2.59, 0.000000, 0, 0, 19, 812, 0 +ATT, -1.32, -0.50, -3.64, 1.50, 0.00, 48.38, 52.50 +CTUN, 813, 0.67, 2.51, 0.000000, 0, 0, 20, 813, 0 +ATT, -1.61, -1.71, -3.36, 3.55, 0.00, 48.74, 52.50 +CTUN, 813, 0.67, 2.61, 0.000000, 0, 2, 19, 815, 0 +ATT, -2.36, -1.99, -2.24, 4.67, 0.00, 49.38, 52.50 +CTUN, 816, 0.69, 2.58, 0.000000, 0, 3, 18, 817, 0 +ATT, -2.74, -2.49, -2.70, 4.89, 0.00, 50.30, 52.50 +CTUN, 816, 0.69, 2.63, 0.000000, 0, 3, 16, 819, 0 +ATT, -2.65, -2.90, -2.61, 4.30, 0.00, 51.38, 52.50 +CTUN, 816, 0.69, 2.61, 0.000000, 0, 2, 14, 817, 0 +ATT, -2.65, -3.30, -4.38, 3.67, 0.00, 52.22, 52.50 +CTUN, 818, 0.69, 2.63, 0.000000, 0, 2, 14, 820, 0 +ATT, -2.17, -3.53, -4.57, 3.26, 0.00, 53.00, 52.50 +CTUN, 824, 0.69, 2.73, 0.000000, 0, 2, 12, 826, 0 +ATT, -0.75, -3.65, -5.50, 2.49, 0.00, 53.66, 52.50 +CTUN, 825, 0.68, 2.68, 0.000000, 0, 1, 13, 826, 0 +ATT, 0.00, -3.60, -6.25, 0.70, 0.00, 54.31, 52.50 +CTUN, 827, 0.68, 2.63, 0.000000, 0, 1, 11, 828, 0 +ATT, 0.00, -2.93, -7.28, -1.99, 0.00, 54.87, 52.50 +DU32, 7, 166140 +CURR, 826, 1488145, 991, 2309, 5051, 1118.114700 +CTUN, 827, 0.68, 2.53, 0.000000, 0, 1, 10, 827, 0 +ATT, 0.00, -2.21, -7.84, -4.42, 0.00, 55.17, 52.50 +CTUN, 826, 0.68, 2.48, 0.000000, 0, 3, 12, 828, 0 +ATT, 0.00, -1.92, -8.02, -5.92, 0.00, 55.23, 52.50 +CTUN, 826, 0.65, 2.40, 0.000000, 0, 4, 13, 830, 0 +ATT, 0.28, -1.55, -8.12, -6.53, 0.00, 55.16, 52.50 +CTUN, 826, 0.65, 2.40, 0.000000, 0, 4, 14, 830, 0 +ATT, 1.78, -0.87, -7.56, -6.63, 0.00, 54.88, 52.50 +CTUN, 825, 0.65, 2.43, 0.000000, 0, 4, 14, 830, 0 +ATT, 3.18, -0.22, -6.81, -6.38, 0.00, 54.46, 52.50 +CTUN, 826, 0.65, 2.41, 0.000000, 0, 3, 16, 829, 0 +ATT, 3.09, 1.16, -6.16, -5.63, 0.00, 53.98, 52.50 +CTUN, 825, 0.63, 2.51, 0.000000, 0, 3, 17, 828, 0 +ATT, 3.18, 3.48, -5.97, -4.78, 0.00, 53.50, 52.50 +CTUN, 825, 0.63, 2.61, 0.000000, 0, 4, 17, 830, 0 +ATT, 3.09, 4.52, -5.88, -4.25, 0.00, 53.06, 52.50 +CTUN, 825, 0.63, 2.41, 0.000000, 0, 3, 19, 828, 0 +ATT, 3.18, 4.46, -5.50, -3.72, 0.00, 52.75, 52.50 +CTUN, 826, 0.64, 2.39, 0.000000, 0, 3, 22, 829, 0 +ATT, 0.28, 4.93, -4.76, -3.64, 0.00, 52.78, 52.50 +DU32, 7, 166140 +CURR, 825, 1496432, 986, 2343, 5028, 1124.604500 +CTUN, 825, 0.64, 2.37, 0.000000, 0, 4, 23, 829, 0 +ATT, 0.00, 4.52, -4.76, -3.62, 0.00, 53.17, 52.50 +CTUN, 825, 0.65, 2.55, 0.000000, 0, 2, 25, 828, 0 +ATT, 0.00, 1.87, -5.50, -3.39, 0.00, 53.73, 52.50 +CTUN, 825, 0.65, 2.61, 0.000000, 0, 1, 26, 826, 0 +ATT, 0.00, -0.23, -6.16, -2.72, 0.00, 54.47, 52.50 +CTUN, 824, 0.67, 2.59, 0.000000, 0, 0, 27, 825, 0 +ATT, 0.00, -0.90, -6.53, -2.03, 0.00, 55.36, 52.50 +CTUN, 824, 0.67, 2.65, 0.000000, 0, 0, 27, 824, 0 +ATT, 0.00, -1.25, -6.34, -1.76, 0.00, 56.38, 52.50 +CTUN, 824, 0.70, 2.63, 0.000000, 0, 0, 29, 824, 0 +ATT, 0.00, -1.29, -6.53, -2.15, 0.00, 57.32, 52.50 +CTUN, 823, 0.70, 2.63, 0.000000, 0, 0, 31, 824, 0 +ATT, 0.00, -1.34, -5.22, -2.85, 0.00, 58.23, 52.50 +CTUN, 823, 0.73, 2.70, 0.000000, 0, 1, 31, 824, 0 +ATT, 0.00, -1.46, -2.33, -3.20, 0.00, 59.09, 52.50 +CTUN, 824, 0.73, 2.66, 0.000000, 0, 1, 29, 825, 0 +ATT, 0.00, -0.98, -2.33, -2.26, 0.00, 59.73, 52.50 +CTUN, 824, 0.77, 2.76, 0.000000, 0, 0, 30, 824, 0 +ATT, 0.00, -0.74, -2.52, -0.29, 0.00, 60.00, 52.50 +DU32, 7, 166140 +CURR, 824, 1504683, 984, 2262, 5051, 1131.049000 +CTUN, 824, 0.77, 2.79, 0.000000, 0, 0, 29, 823, 0 +ATT, 0.00, -1.51, -2.52, 1.30, 0.00, 59.93, 52.50 +CTUN, 823, 0.79, 2.70, 0.000000, 0, 0, 26, 823, 0 +ATT, 0.00, -1.68, -2.52, 1.66, 0.00, 59.61, 52.50 +CTUN, 824, 0.79, 2.75, 0.000000, 0, 0, 26, 824, 0 +ATT, 0.00, -1.40, -2.52, 1.04, 0.00, 59.23, 52.50 +CTUN, 823, 0.82, 2.76, 0.000000, 0, 0, 25, 823, 0 +ATT, 0.00, -0.80, -2.52, -0.08, 0.00, 58.85, 52.50 +CTUN, 823, 0.82, 2.85, 0.000000, 0, 0, 24, 823, 0 +ATT, 0.00, -0.32, -2.52, -0.58, 0.00, 58.60, 52.50 +CTUN, 823, 0.85, 2.94, 0.000000, 0, 0, 27, 823, 0 +ATT, 0.00, -0.72, -2.70, -0.51, 0.00, 58.48, 52.50 +CTUN, 823, 0.85, 2.90, 0.000000, 0, 0, 27, 823, 0 +ATT, 0.00, -1.31, -2.61, -0.56, 0.00, 58.44, 52.50 +CTUN, 824, 0.87, 2.81, 0.000000, 0, 0, 27, 824, 0 +ATT, 0.00, -1.25, -2.61, -0.76, 0.00, 58.48, 52.50 +CTUN, 824, 0.87, 2.75, 0.000000, 0, 0, 27, 824, 0 +ATT, 0.00, -1.04, -2.61, -0.94, 0.00, 58.57, 52.50 +CTUN, 823, 0.90, 2.87, 0.000000, 0, 0, 27, 823, 0 +ATT, 0.00, -1.02, -2.70, -1.25, 0.00, 58.69, 52.50 +DU32, 7, 166140 +CURR, 823, 1512918, 985, 2317, 5051, 1137.431900 +CTUN, 823, 0.90, 2.87, 0.000000, 0, 0, 27, 823, 0 +ATT, 0.18, -1.19, -2.89, -1.70, 0.00, 58.77, 52.50 +CTUN, 823, 0.91, 2.81, 0.000000, 0, 0, 28, 823, 0 +ATT, 1.68, -1.38, -2.70, -2.05, 0.00, 58.80, 52.50 +CTUN, 823, 0.91, 2.86, 0.000000, 0, 0, 28, 824, 0 +ATT, 2.71, -0.94, -2.61, -1.99, 0.00, 58.75, 52.50 +CTUN, 823, 0.94, 2.88, 0.000000, 0, 0, 28, 823, 0 +ATT, 3.28, 0.51, -2.61, -1.84, 0.00, 58.69, 52.50 +CTUN, 822, 0.94, 3.00, 0.000000, 0, 0, 27, 821, 0 +ATT, 3.93, 1.78, -2.70, -1.73, 0.00, 58.61, 52.50 +CTUN, 816, 0.96, 2.93, 0.000000, 0, 0, 28, 816, 0 +ATT, 4.50, 2.82, -2.70, -1.54, 0.00, 58.47, 52.50 +CTUN, 804, 0.96, 2.89, 0.000000, 0, 1, 27, 805, 0 +ATT, 5.25, 3.97, -2.70, -1.55, 0.00, 58.18, 52.50 +CTUN, 792, 0.98, 2.82, 0.000000, 0, 2, 24, 794, 0 +ATT, 5.06, 5.16, -2.70, -1.90, 0.00, 57.69, 52.50 +CTUN, 789, 0.98, 2.99, 0.000000, 0, 3, 19, 792, 0 +ATT, 5.25, 5.95, -3.08, -2.35, 0.00, 57.13, 52.50 +CTUN, 788, 1.01, 2.97, 0.000000, 0, 4, 16, 793, 0 +ATT, 5.06, 6.37, -3.08, -2.55, 0.00, 56.49, 52.50 +DU32, 7, 166140 +CURR, 788, 1521038, 995, 2125, 5051, 1143.694700 +CTUN, 788, 1.01, 3.08, 0.000000, 0, 4, 11, 792, 0 +ATT, 4.96, 6.27, -3.08, -2.53, 0.00, 55.89, 52.50 +CTUN, 788, 1.02, 2.96, 0.000000, 0, 4, 10, 792, 0 +ATT, 3.93, 5.75, -3.26, -2.12, 0.00, 55.37, 52.50 +CTUN, 792, 1.02, 2.99, 0.000000, 0, 3, 5, 795, 0 +ATT, 2.53, 4.64, -2.80, -2.05, 0.00, 54.92, 52.50 +CTUN, 796, 1.02, 3.06, 0.000000, 0, 1, 4, 797, 0 +ATT, 0.37, 3.06, -2.52, -2.18, 0.00, 54.42, 52.50 +CTUN, 805, 1.02, 2.95, 0.000000, 0, 0, 0, 803, 0 +ATT, 0.00, 1.33, -2.70, -1.90, 0.00, 53.83, 52.50 +CTUN, 809, 1.02, 2.95, 0.000000, 0, 0, 0, 809, 0 +ATT, 0.00, 0.29, -2.98, -1.58, 0.00, 53.23, 52.50 +CTUN, 813, 1.00, 3.07, 0.000000, 0, 0, -1, 813, 0 +ATT, 0.00, 0.16, -3.36, -1.48, 0.00, 52.61, 52.50 +CTUN, 815, 1.00, 2.96, 0.000000, 0, 0, -1, 815, 0 +ATT, 0.00, 0.51, -3.64, -1.38, 0.00, 52.03, 52.50 +CTUN, 819, 0.98, 3.02, 0.000000, 0, 0, 0, 819, 0 +ATT, 0.00, 0.42, -4.01, -1.22, 0.00, 51.43, 52.50 +CTUN, 828, 0.98, 2.94, 0.000000, 0, 0, -4, 828, 0 +ATT, 0.00, 0.29, -3.92, -1.17, 0.00, 51.01, 52.50 +DU32, 7, 166140 +CURR, 830, 1529087, 986, 2257, 5028, 1149.725200 +CTUN, 830, 0.94, 2.88, 0.000000, 0, 0, -2, 829, 0 +ATT, 0.00, 0.21, -3.92, -0.92, 0.00, 50.76, 52.50 +CTUN, 831, 0.94, 2.81, 0.000000, 0, 0, -1, 831, 0 +ATT, 0.00, 0.77, -3.82, -0.54, 0.00, 50.73, 52.50 +CTUN, 833, 0.90, 2.85, 0.000000, 0, 0, 0, 833, 0 +ATT, 0.00, 1.26, -3.92, -0.08, 0.00, 50.83, 52.50 +CTUN, 838, 0.90, 2.81, 0.000000, 0, 0, 4, 836, 0 +ATT, -0.75, 1.15, -4.38, 0.10, 0.00, 50.97, 52.50 +CTUN, 838, 0.87, 2.86, 0.000000, 0, 0, 7, 838, 0 +ATT, -1.42, 0.93, -4.10, 0.03, 0.00, 51.22, 52.50 +CTUN, 838, 0.87, 2.76, 0.000000, 0, 0, 13, 838, 0 +ATT, -1.98, 0.54, -3.92, 0.05, 0.00, 51.63, 52.50 +CTUN, 837, 0.85, 2.70, 0.000000, 0, 0, 16, 837, 0 +ATT, -2.55, -0.05, -4.29, -0.15, 0.00, 52.04, 52.50 +PM, 0, 0, 0, 0, 1000, 10464, 0, 0 +CTUN, 838, 0.85, 2.80, 0.000000, 0, 0, 16, 838, 0 +ATT, -2.84, -1.51, -4.57, -2.00, 0.00, 52.41, 52.50 +CTUN, 838, 0.84, 2.74, 0.000000, 0, 1, 18, 839, 0 +ATT, -3.97, -2.33, -3.92, -2.61, 0.00, 52.62, 52.50 +CTUN, 838, 0.84, 2.79, 0.000000, 0, 1, 23, 839, 0 +ATT, -4.83, -2.26, -4.57, -1.63, 0.00, 52.54, 52.50 +DU32, 7, 166140 +CURR, 838, 1537441, 982, 2377, 5051, 1156.191200 +CTUN, 838, 0.84, 2.79, 0.000000, 0, 0, 24, 838, 0 +ATT, -4.54, -3.49, -4.48, -0.45, 0.00, 52.51, 52.50 +CTUN, 838, 0.84, 2.75, 0.000000, 0, 1, 28, 839, 0 +ATT, -4.64, -4.50, -4.57, 0.16, 0.00, 52.54, 52.50 +CTUN, 838, 0.84, 2.77, 0.000000, 0, 1, 28, 839, 0 +ATT, -4.35, -3.89, -4.29, 0.20, 0.00, 52.80, 52.50 +CTUN, 838, 0.87, 2.77, 0.000000, 0, 1, 32, 839, 0 +ATT, -4.16, -3.27, -4.10, 0.23, 0.00, 53.07, 52.50 +CTUN, 836, 0.87, 2.84, 0.000000, 0, 0, 34, 836, 0 +ATT, -3.22, -2.69, -4.94, 0.41, 0.00, 53.29, 52.50 +CTUN, 819, 0.88, 2.79, 0.000000, 0, 0, 35, 819, 0 +ATT, -1.98, -2.44, -5.22, 0.59, 0.00, 53.54, 52.50 +CTUN, 809, 0.87, 2.91, 0.000000, 0, 0, 32, 814, 0 +ATT, -1.80, -1.80, -5.69, -0.04, 0.00, 53.96, 52.50 +CTUN, 798, 0.88, 2.88, 0.000000, 0, 0, 32, 798, 0 +ATT, -1.70, -0.85, -6.06, -1.41, 0.00, 54.36, 52.50 +CTUN, 792, 0.88, 2.84, 0.000000, 0, 0, 30, 792, 0 +ATT, -1.61, -0.38, -6.53, -2.73, 0.00, 54.82, 52.50 +CTUN, 780, 0.96, 2.89, 0.000000, 0, 0, 26, 784, 0 +ATT, -1.61, -0.39, -6.44, -3.35, 0.00, 55.09, 52.50 +DU32, 7, 166140 +CURR, 766, 1545654, 994, 2089, 5051, 1162.539600 +CTUN, 765, 0.96, 2.87, 0.000000, 0, 1, 19, 766, 0 +ATT, -1.61, -0.48, -6.25, -3.82, 0.00, 55.28, 52.50 +CTUN, 766, 0.99, 2.97, 0.000000, 0, 1, 11, 767, 0 +ATT, -1.61, -0.78, -6.53, -4.32, 0.00, 55.21, 52.50 +CTUN, 768, 0.99, 2.99, 0.000000, 0, 2, 3, 769, 0 +ATT, -1.51, -1.02, -6.16, -4.69, 0.00, 54.94, 52.50 +CTUN, 782, 1.00, 2.94, 0.000000, 0, 2, -7, 784, 0 +ATT, -1.80, -1.18, -5.88, -5.09, 0.00, 54.63, 52.50 +CTUN, 790, 0.99, 2.97, 0.000000, 0, 2, -12, 792, 0 +ATT, -1.70, -0.85, -5.60, -5.23, 0.00, 54.28, 52.50 +CTUN, 805, 0.99, 2.88, 0.000000, 0, 2, -17, 801, 0 +ATT, -1.80, -0.41, -5.69, -4.71, 0.00, 53.74, 52.50 +CTUN, 813, 0.96, 2.96, 0.000000, 0, 1, -23, 814, 0 +ATT, -1.80, -0.28, -5.41, -3.77, 0.00, 52.84, 52.50 +CTUN, 815, 0.96, 2.91, 0.000000, 0, 0, -26, 815, 0 +ATT, -1.80, 0.28, -5.04, -2.31, 0.00, 51.54, 52.50 +CTUN, 817, 0.90, 2.97, 0.000000, 0, 0, -28, 817, 0 +ATT, -1.80, 0.15, -4.85, -0.96, 0.00, 50.18, 52.50 +CTUN, 821, 0.90, 2.83, 0.000000, 0, 0, -28, 821, 0 +ATT, -2.36, -1.67, -4.57, 0.56, 0.00, 49.03, 52.50 +DU32, 7, 166140 +CURR, 827, 1553592, 997, 2229, 5028, 1168.386000 +CTUN, 833, 0.80, 2.99, 0.000000, 0, 1, -32, 834, 0 +ATT, -3.60, -4.24, -3.45, 1.58, 0.00, 48.26, 52.50 +CTUN, 836, 0.80, 2.92, 0.000000, 0, 3, -33, 838, 0 +ATT, -3.12, -6.00, -3.08, 2.57, 0.00, 47.93, 52.50 +CTUN, 836, 0.73, 2.87, 0.000000, 0, 5, -30, 841, 0 +ATT, -3.12, -6.20, -3.08, 3.94, 0.00, 47.84, 52.50 +CTUN, 835, 0.73, 2.90, 0.000000, 0, 5, -34, 841, 0 +ATT, -2.74, -5.07, -2.80, 4.21, 0.00, 48.40, 52.50 +CTUN, 836, 0.65, 2.87, 0.000000, 0, 4, -35, 840, 0 +ATT, -0.75, -4.35, -4.85, 3.72, 0.00, 49.40, 52.50 +CTUN, 835, 0.65, 2.64, 0.000000, 0, 2, -33, 837, 0 +ATT, 0.00, -3.35, -5.13, 2.42, 0.00, 50.44, 52.50 +CTUN, 835, 0.56, 2.59, 0.000000, 0, 0, -33, 835, 0 +ATT, 0.00, -1.78, -5.78, 0.69, 0.00, 51.35, 52.50 +CTUN, 836, 0.56, 2.44, 0.000000, 0, 0, -33, 836, 0 +ATT, 0.00, -0.37, -5.50, -0.82, 0.00, 52.33, 52.50 +CTUN, 835, 0.46, 2.39, 0.000000, 0, 0, -32, 836, 0 +ATT, 0.00, 0.39, -5.22, -1.85, 0.00, 53.36, 52.50 +CTUN, 836, 0.46, 2.44, 0.000000, 0, 0, -28, 836, 0 +ATT, 0.00, 0.32, -5.50, -2.37, 0.00, 54.18, 52.50 +DU32, 7, 166140 +CURR, 836, 1561964, 973, 2352, 5051, 1174.850100 +CTUN, 835, 0.37, 2.39, 0.000000, 0, 0, -23, 835, 0 +ATT, 0.28, -0.67, -5.69, -2.39, 0.00, 54.81, 52.50 +CTUN, 836, 0.37, 2.29, 0.000000, 0, 0, -16, 836, 0 +ATT, 1.21, -0.60, -5.88, -2.59, 0.00, 55.27, 52.50 +CTUN, 835, 0.30, 2.36, 0.000000, 0, 0, -9, 836, 0 +ATT, 2.53, 0.05, -6.16, -2.42, 0.00, 55.47, 52.50 +CTUN, 836, 0.30, 2.14, 0.000000, 0, 0, -4, 836, 0 +ATT, 2.53, 0.32, -6.44, -2.28, 0.00, 55.69, 52.50 +CTUN, 836, 0.26, 2.14, 0.000000, 0, 0, 2, 836, 0 +ATT, 3.18, 0.97, -6.25, -2.35, 0.00, 55.84, 52.50 +CTUN, 836, 0.26, 2.01, 0.000000, 0, 0, 11, 835, 0 +ATT, 3.56, 1.59, -6.25, -2.66, 0.00, 55.86, 52.50 +CTUN, 836, 0.24, 2.11, 0.000000, 0, 1, 20, 837, 0 +ATT, 3.93, 2.92, -6.16, -2.52, 0.00, 55.86, 52.50 +CTUN, 835, 0.24, 2.10, 0.000000, 0, 1, 24, 837, 0 +ATT, 3.93, 2.98, -5.69, -1.79, 0.00, 55.92, 52.50 +CTUN, 836, 0.24, 2.24, 0.000000, 0, 1, 26, 837, 0 +ATT, 3.75, 2.59, -4.85, -1.03, 0.00, 55.98, 52.50 +CTUN, 835, 0.25, 2.21, 0.000000, 0, 0, 30, 835, 0 +ATT, 3.28, 2.61, -4.48, -0.18, 0.00, 55.91, 52.50 +DU32, 7, 166140 +CURR, 835, 1570325, 982, 2357, 5051, 1181.419100 +CTUN, 833, 0.25, 2.31, 0.000000, 0, 0, 33, 833, 0 +ATT, 1.78, 2.56, -5.69, 0.47, 0.00, 55.64, 52.50 +CTUN, 830, 0.29, 2.37, 0.000000, 0, 0, 32, 831, 0 +ATT, 0.28, 2.05, -8.02, 0.74, 0.00, 55.29, 52.50 +CTUN, 830, 0.29, 2.24, 0.000000, 0, 0, 32, 830, 0 +ATT, 0.09, 0.80, -8.21, -0.07, 0.00, 54.97, 52.50 +CTUN, 828, 0.35, 2.26, 0.000000, 0, 0, 34, 828, 0 +ATT, 0.28, -0.10, -8.40, -1.64, 0.00, 54.57, 52.50 +CTUN, 821, 0.35, 2.50, 0.000000, 0, 0, 33, 822, 0 +ATT, 0.09, -0.49, -8.77, -3.80, 0.00, 54.27, 52.50 +CTUN, 816, 0.40, 2.74, 0.000000, 0, 2, 33, 818, 0 +ATT, 1.78, -0.22, -10.36, -4.76, 0.00, 53.87, 52.50 +CTUN, 815, 0.40, 2.53, 0.000000, 0, 2, 30, 818, 0 +ATT, 2.43, 0.73, -10.64, -5.33, 0.00, 53.52, 52.50 +CTUN, 815, 0.45, 2.84, 0.000000, 0, 3, 30, 818, 0 +ATT, 3.18, 1.78, -10.64, -5.96, 0.00, 53.19, 52.50 +CTUN, 815, 0.45, 2.72, 0.000000, 0, 4, 25, 820, 0 +ATT, 3.37, 2.46, -10.64, -6.52, 0.00, 53.01, 52.50 +CTUN, 815, 0.50, 2.66, 0.000000, 0, 5, 26, 820, 0 +ATT, 2.81, 2.81, -8.96, -7.09, 0.00, 52.95, 52.50 +DU32, 7, 166140 +CURR, 815, 1578561, 987, 2263, 5028, 1187.802100 +CTUN, 816, 0.50, 2.59, 0.000000, 0, 6, 22, 822, 0 +ATT, 1.78, 3.11, -8.02, -7.19, 0.00, 53.11, 52.50 +CTUN, 815, 0.54, 2.56, 0.000000, 0, 5, 21, 820, 0 +ATT, 0.00, 2.57, -6.72, -6.14, 0.00, 53.44, 52.50 +CTUN, 816, 0.54, 2.60, 0.000000, 0, 3, 19, 819, 0 +ATT, 0.00, 0.70, -4.76, -4.33, 0.00, 54.06, 52.50 +CTUN, 815, 0.57, 2.61, 0.000000, 0, 1, 17, 816, 0 +ATT, 0.00, -0.29, -4.76, -2.52, 0.00, 54.83, 52.50 +CTUN, 815, 0.57, 2.72, 0.000000, 0, 0, 17, 815, 0 +ATT, 0.00, 0.02, -4.76, -0.89, 0.00, 55.47, 52.50 +CTUN, 816, 0.60, 2.73, 0.000000, 0, 0, 15, 815, 0 +ATT, 0.00, 0.88, -4.76, -0.16, 0.00, 56.04, 52.50 +CTUN, 815, 0.60, 2.67, 0.000000, 0, 0, 16, 815, 0 +ATT, 0.00, 1.22, -4.48, -0.49, 0.00, 56.57, 52.50 +CTUN, 816, 0.61, 2.84, 0.000000, 0, 0, 13, 815, 0 +ATT, 0.00, 1.14, -3.73, -1.25, 0.00, 56.92, 52.50 +CTUN, 813, 0.61, 2.75, 0.000000, 0, 0, 15, 813, 0 +ATT, 0.00, 0.49, -2.61, -1.60, 0.00, 57.06, 52.50 +CTUN, 812, 0.64, 2.76, 0.000000, 0, 0, 16, 812, 0 +ATT, 0.00, 0.00, -2.52, -1.10, 0.00, 56.93, 52.50 +DU32, 7, 166140 +CURR, 812, 1586727, 989, 2266, 5051, 1194.098300 +CTUN, 813, 0.64, 2.84, 0.000000, 0, 0, 16, 813, 0 +ATT, 0.00, 0.09, -2.52, -0.03, 0.00, 56.55, 52.50 +CTUN, 813, 0.66, 2.93, 0.000000, 0, 0, 13, 813, 0 +ATT, 0.00, 0.34, -2.52, 0.99, 0.00, 56.01, 52.50 +CTUN, 813, 0.66, 2.89, 0.000000, 0, 0, 12, 812, 0 +ATT, 0.00, 0.32, -2.52, 1.93, 0.00, 55.20, 52.50 +CTUN, 813, 0.69, 2.73, 0.000000, 0, 0, 13, 813, 0 +ATT, 0.00, 0.39, -2.05, 2.53, 0.00, 54.07, 52.50 +CTUN, 813, 0.69, 2.69, 0.000000, 0, 0, 16, 813, 0 +ATT, 0.00, 0.73, -2.33, 2.95, 0.00, 52.67, 52.50 +CTUN, 812, 0.70, 2.73, 0.000000, 0, 1, 12, 813, 0 +ATT, 0.00, 0.89, -2.42, 2.99, 0.00, 51.05, 52.50 +CTUN, 813, 0.70, 2.77, 0.000000, 0, 0, 11, 813, 0 +ATT, 0.00, 0.51, -3.26, 2.51, 0.00, 49.41, 52.50 +CTUN, 813, 0.71, 2.71, 0.000000, 0, 0, 9, 813, 0 +ATT, 0.00, -0.02, -4.20, 1.72, 0.00, 47.94, 52.50 +CTUN, 813, 0.71, 2.63, 0.000000, 0, 0, 8, 813, 0 +ATT, 0.00, -0.41, -4.76, 0.75, 0.00, 46.65, 52.50 +CTUN, 813, 0.72, 2.67, 0.000000, 0, 0, 6, 813, 0 +ATT, 0.00, -0.36, -4.57, -0.34, 0.00, 45.62, 52.50 +DU32, 7, 166140 +CURR, 813, 1594855, 989, 2242, 5028, 1200.329300 +CTUN, 812, 0.72, 2.69, 0.000000, 0, 0, 5, 812, 0 +ATT, 0.00, -0.01, -2.52, -1.42, 0.00, 44.88, 52.50 +CTUN, 813, 0.74, 2.67, 0.000000, 0, 0, 5, 812, 0 +ATT, 0.00, -0.09, -2.52, -1.14, 0.00, 44.44, 52.50 +CTUN, 813, 0.74, 2.77, 0.000000, 0, 0, 2, 813, 0 +ATT, 0.00, -0.40, -2.52, 0.01, 0.00, 44.35, 52.50 +CTUN, 813, 0.75, 2.81, 0.000000, 0, 0, 0, 813, 0 +ATT, 0.00, -1.36, -2.33, 1.28, 0.00, 44.69, 52.50 +CTUN, 813, 0.75, 2.76, 0.000000, 0, 0, 1, 813, 0 +ATT, 0.00, -1.96, -2.52, 2.01, 0.00, 45.39, 52.50 +CTUN, 813, 0.76, 2.86, 0.000000, 0, 0, -1, 813, 0 +ATT, 0.00, -1.10, -2.52, 1.60, 0.00, 46.31, 52.50 +CTUN, 812, 0.76, 2.76, 0.000000, 0, 0, -4, 812, 0 +ATT, 0.00, -0.10, -3.36, 1.12, 0.00, 47.36, 52.50 +CTUN, 813, 0.77, 2.87, 0.000000, 0, 0, -8, 813, 0 +ATT, 0.00, 0.48, -4.57, 0.56, 0.00, 48.47, 52.50 +CTUN, 812, 0.76, 2.81, 0.000000, 0, 0, -7, 812, 0 +ATT, 0.00, 1.02, -4.76, -0.71, 0.00, 49.71, 52.50 +CTUN, 812, 0.76, 2.94, 0.000000, 0, 0, -9, 812, 0 +ATT, 0.00, 1.13, -6.72, -1.59, 0.00, 50.72, 52.50 +DU32, 7, 166140 +CURR, 813, 1602982, 987, 2206, 5028, 1206.486700 +CTUN, 812, 0.76, 2.88, 0.000000, 0, 0, -12, 813, 0 +ATT, 0.00, 1.18, -6.72, -1.86, 0.00, 51.78, 52.50 +CTUN, 812, 0.76, 2.89, 0.000000, 0, 0, -16, 812, 0 +ATT, 0.00, 1.21, -4.85, -2.10, 0.00, 52.83, 52.50 +CTUN, 813, 0.73, 2.79, 0.000000, 0, 0, -18, 813, 0 +ATT, -0.18, 1.02, -4.76, -2.36, 0.00, 53.83, 52.50 +CTUN, 813, 0.73, 2.75, 0.000000, 0, 0, -24, 813, 0 +ATT, -2.08, 0.66, -4.38, -2.63, 0.00, 54.85, 52.50 +CTUN, 812, 0.71, 2.69, 0.000000, 0, 0, -24, 812, 0 +ATT, -3.41, -0.61, -3.36, -2.70, 0.00, 55.68, 52.50 +CTUN, 812, 0.71, 2.79, 0.000000, 0, 0, -26, 812, 0 +ATT, -3.12, -2.32, -3.08, -2.79, 0.00, 56.48, 52.50 +CTUN, 812, 0.67, 2.71, 0.000000, 0, 1, -27, 813, 0 +ATT, -3.12, -3.58, -3.08, -2.92, 0.00, 57.14, 52.50 +CTUN, 812, 0.67, 2.73, 0.000000, 0, 2, -30, 815, 0 +ATT, -3.31, -4.34, -3.26, -2.78, 0.00, 57.60, 52.50 +CTUN, 813, 0.63, 2.84, 0.000000, 0, 3, -34, 816, 0 +ATT, -3.22, -4.84, -3.26, -2.57, 0.00, 57.78, 52.50 +CTUN, 813, 0.63, 2.70, 0.000000, 0, 2, -37, 815, 0 +ATT, -3.03, -3.40, -3.08, -1.54, 0.00, 57.72, 52.50 +DU32, 7, 166140 +CURR, 812, 1611116, 985, 2239, 5051, 1212.663700 +CTUN, 813, 0.57, 2.67, 0.000000, 0, 0, -38, 813, 0 +ATT, -3.12, -2.22, -3.08, -0.44, 0.00, 57.36, 52.50 +CTUN, 813, 0.57, 2.52, 0.000000, 0, 0, -39, 813, 0 +ATT, -1.51, -1.66, -3.17, 0.45, 0.00, 56.82, 52.50 +CTUN, 813, 0.50, 2.38, 0.000000, 0, 0, -41, 813, 0 +ATT, -0.94, -2.41, -3.08, 1.14, 0.00, 56.30, 52.50 +CTUN, 813, 0.50, 2.54, 0.000000, 0, 0, -43, 813, 0 +ATT, -0.85, -2.25, -3.08, 0.39, 0.00, 55.93, 52.50 +CTUN, 813, 0.43, 2.54, 0.000000, 0, 0, -45, 813, 0 +ATT, -0.94, -0.13, -3.26, -0.95, 0.00, 55.80, 52.50 +CTUN, 813, 0.43, 2.21, 0.000000, 0, 0, -45, 813, 0 +ATT, -0.75, 1.06, -4.38, -2.06, 0.00, 55.77, 52.50 +CTUN, 813, 0.35, 2.26, 0.000000, 0, 0, -43, 813, 0 +ATT, -0.85, 0.70, -4.57, -2.52, 0.00, 55.98, 52.50 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +CTUN, 813, 0.35, 2.30, 0.000000, 0, 0, -40, 813, 0 +ATT, -0.94, 0.84, -3.54, -2.81, 0.00, 56.22, 52.50 +CTUN, 812, 0.27, 2.26, 0.000000, 0, 0, -35, 813, 0 +ATT, -1.80, 0.69, -1.77, -2.58, 0.00, 56.55, 52.50 +CTUN, 813, 0.27, 2.22, 0.000000, 0, 0, -25, 813, 0 +ATT, -2.55, -0.53, -2.52, -2.05, 0.00, 56.94, 52.50 +DU32, 7, 166140 +CURR, 813, 1619245, 979, 2232, 5051, 1218.859300 +CTUN, 812, 0.21, 2.09, 0.000000, 0, 0, -15, 813, 0 +ATT, -2.74, -1.23, -2.61, -1.34, 0.00, 57.44, 52.50 +CTUN, 812, 0.21, 2.10, 0.000000, 0, 0, -2, 812, 0 +ATT, -2.74, -1.61, -2.70, -0.52, 0.00, 57.87, 52.50 +CTUN, 813, 0.21, 2.30, 0.000000, 0, 0, 3, 813, 0 +ATT, -2.74, -1.90, -2.70, -0.72, 0.00, 58.22, 52.50 +CTUN, 813, 0.21, 2.14, 0.000000, 0, 0, 9, 813, 0 +ATT, -2.27, -2.51, -2.24, -1.44, 0.00, 58.62, 52.50 +CTUN, 812, 0.20, 2.20, 0.000000, 0, 0, 17, 813, 0 +ATT, -2.08, -1.81, -2.05, -1.83, 0.00, 58.91, 52.50 +CTUN, 813, 0.20, 2.26, 0.000000, 0, 0, 21, 812, 0 +ATT, -1.80, -0.82, -1.77, -0.67, 0.00, 59.18, 52.50 +CTUN, 813, 0.20, 2.20, 0.000000, 0, 0, 25, 813, 0 +ATT, -2.08, -0.92, -2.05, 0.87, 0.00, 59.57, 52.50 +CTUN, 812, 0.22, 2.26, 0.000000, 0, 0, 26, 812, 0 +ATT, 0.00, -0.89, -2.52, 1.89, 0.00, 59.96, 52.50 +CTUN, 812, 0.22, 2.41, 0.000000, 0, 0, 22, 812, 0 +ATT, 0.00, -0.09, -2.42, 1.84, 0.00, 60.31, 52.50 +CTUN, 813, 0.27, 2.21, 0.000000, 0, 0, 23, 813, 0 +ATT, 0.00, 2.19, -2.42, 2.14, 0.00, 60.69, 52.50 +DU32, 7, 166140 +CURR, 813, 1627375, 988, 2094, 5051, 1224.965100 +CTUN, 813, 0.27, 2.41, 0.000000, 0, 1, 18, 814, 0 +ATT, 0.00, 3.42, -2.52, 3.20, 0.00, 60.58, 52.50 +CTUN, 813, 0.31, 2.40, 0.000000, 0, 2, 10, 815, 0 +ATT, 0.00, 2.77, -2.52, 2.98, 0.00, 59.86, 52.50 +CTUN, 813, 0.31, 2.47, 0.000000, 0, 1, 4, 814, 0 +ATT, 0.00, 2.60, -2.42, 1.24, 0.00, 58.80, 52.50 +CTUN, 813, 0.34, 2.50, 0.000000, 0, 0, 4, 813, 0 +ATT, -0.09, 2.44, -2.42, -0.82, 0.00, 57.41, 52.50 +CTUN, 813, 0.34, 2.47, 0.000000, 0, 0, 8, 812, 0 +ATT, -0.75, 1.65, -2.52, -2.17, 0.00, 56.34, 52.50 +CTUN, 813, 0.36, 2.48, 0.000000, 0, 0, 9, 813, 0 +ATT, -0.75, 0.71, -2.70, -2.26, 0.00, 55.67, 52.50 +CTUN, 813, 0.36, 2.61, 0.000000, 0, 0, 10, 813, 0 +ATT, -0.56, -1.33, -2.52, -2.01, 0.00, 55.22, 52.50 +CTUN, 813, 0.38, 2.60, 0.000000, 0, 0, 8, 813, 0 +ATT, -0.75, -2.84, -2.52, -1.82, 0.00, 55.10, 52.50 +CTUN, 813, 0.38, 2.71, 0.000000, 0, 1, 7, 814, 0 +ATT, -0.66, -3.46, -2.70, -1.77, 0.00, 55.21, 52.50 +CTUN, 813, 0.42, 2.69, 0.000000, 0, 1, 4, 814, 0 +ATT, -0.66, -2.77, -2.61, -1.50, 0.00, 55.36, 52.50 +DU32, 7, 166140 +CURR, 813, 1635507, 986, 2239, 5028, 1231.110200 +CTUN, 813, 0.42, 2.72, 0.000000, 0, 0, 7, 813, 0 +ATT, 0.00, -1.09, -2.52, -0.14, 0.00, 55.58, 52.50 +CTUN, 813, 0.43, 2.65, 0.000000, 0, 0, 5, 813, 0 +ATT, 0.00, 0.02, -2.52, 2.04, 0.00, 56.00, 52.50 +CTUN, 812, 0.43, 2.77, 0.000000, 0, 0, 2, 812, 0 +ATT, 0.00, -0.05, -1.77, 2.50, 0.00, 56.77, 52.50 +CTUN, 813, 0.44, 2.43, 0.000000, 0, 0, 0, 813, 0 +ATT, 0.00, -0.05, -1.40, 1.07, 0.00, 57.38, 52.50 +CTUN, 813, 0.43, 2.63, 0.000000, 0, 0, 2, 813, 0 +ATT, 0.00, -0.26, -2.14, -0.06, 0.00, 57.19, 52.50 +CTUN, 813, 0.43, 2.64, 0.000000, 0, 0, 4, 813, 0 +ATT, 0.00, -0.45, -2.42, -1.08, 0.00, 56.36, 52.50 +CTUN, 813, 0.42, 2.47, 0.000000, 0, 0, 4, 813, 0 +ATT, 0.00, 0.83, -2.42, -1.86, 0.00, 54.80, 52.50 +CTUN, 813, 0.42, 2.52, 0.000000, 0, 0, 2, 812, 0 +ATT, 0.00, 0.91, -2.61, -1.72, 0.00, 52.91, 52.50 +CTUN, 813, 0.42, 2.48, 0.000000, 0, 0, 4, 813, 0 +ATT, 0.00, 0.06, -2.42, -1.12, 0.00, 51.81, 52.50 +CTUN, 813, 0.43, 2.66, 0.000000, 0, 0, 2, 812, 0 +ATT, 0.00, 0.08, -2.70, -0.84, 0.00, 51.26, 52.50 +DU32, 7, 166140 +CURR, 813, 1643634, 984, 2213, 5051, 1237.312500 +CTUN, 812, 0.42, 2.70, 0.000000, 0, 0, 1, 812, 0 +ATT, 0.00, 0.61, -2.70, -0.38, 0.00, 50.89, 52.50 +CTUN, 813, 0.43, 2.68, 0.000000, 0, 0, 0, 813, 0 +ATT, 0.00, 0.80, -2.61, -0.15, 0.00, 50.56, 52.50 +CTUN, 813, 0.42, 2.62, 0.000000, 0, 0, 0, 812, 0 +ATT, 0.00, 0.54, -2.70, 0.08, 0.00, 50.23, 52.50 +CTUN, 813, 0.42, 2.59, 0.000000, 0, 0, 0, 813, 0 +ATT, 0.00, 0.07, -2.89, 0.14, 0.00, 49.96, 52.50 +CTUN, 813, 0.42, 2.59, 0.000000, 0, 0, 0, 812, 0 +ATT, 0.00, 0.22, -2.70, 0.45, 0.00, 49.76, 52.50 +CTUN, 813, 0.42, 2.58, 0.000000, 0, 0, -2, 813, 0 +ATT, -0.37, 0.69, -3.36, 0.30, 0.00, 49.48, 52.50 +CTUN, 812, 0.42, 2.63, 0.000000, 0, 0, -5, 813, 0 +ATT, -0.66, 0.00, -4.29, -0.15, 0.00, 49.32, 52.50 +CTUN, 813, 0.42, 2.53, 0.000000, 0, 0, -10, 813, 0 +ATT, -0.75, -1.60, -4.76, -0.97, 0.00, 49.45, 52.50 +CTUN, 813, 0.40, 2.47, 0.000000, 0, 0, -16, 812, 0 +ATT, -0.85, -1.72, -4.76, -2.14, 0.00, 49.93, 52.50 +CTUN, 813, 0.40, 2.37, 0.000000, 0, 0, -17, 813, 0 +ATT, -1.42, -0.92, -4.76, -2.77, 0.00, 50.75, 52.50 +DU32, 7, 166140 +CURR, 812, 1651759, 982, 2180, 5051, 1243.450800 +CTUN, 813, 0.39, 2.62, 0.000000, 0, 0, -17, 813, 0 +ATT, -1.42, -0.49, -4.85, -2.48, 0.00, 51.46, 52.50 +CTUN, 813, 0.39, 2.50, 0.000000, 0, 0, -19, 813, 0 +ATT, -0.66, -0.59, -4.38, -2.48, 0.00, 52.33, 52.50 +CTUN, 813, 0.36, 2.46, 0.000000, 0, 0, -22, 813, 0 +ATT, -0.18, -0.95, -4.01, -3.38, 0.00, 53.37, 52.50 +CTUN, 813, 0.36, 2.55, 0.000000, 0, 1, -21, 814, 0 +ATT, -0.18, -0.36, -3.45, -3.63, 0.00, 54.34, 52.50 +CTUN, 813, 0.32, 2.61, 0.000000, 0, 1, -19, 814, 0 +ATT, 0.00, -0.64, -3.08, -2.45, 0.00, 55.04, 52.50 +CTUN, 813, 0.32, 2.37, 0.000000, 0, 0, -19, 813, 0 +ATT, 0.00, -1.17, -2.70, -1.69, 0.00, 55.58, 52.50 +CTUN, 812, 0.29, 2.49, 0.000000, 0, 0, -14, 812, 0 +ATT, 0.00, -0.76, -2.52, -0.75, 0.00, 55.87, 52.50 +CTUN, 813, 0.29, 2.37, 0.000000, 0, 0, -11, 812, 0 +ATT, 0.00, -0.73, -2.52, 0.49, 0.00, 55.97, 52.50 +CTUN, 812, 0.26, 2.31, 0.000000, 0, 0, -8, 812, 0 +ATT, 0.00, -0.57, -2.52, 1.18, 0.00, 56.11, 52.50 +CTUN, 813, 0.26, 2.14, 0.000000, 0, 0, -6, 813, 0 +ATT, 0.00, 0.26, -2.52, 0.56, 0.00, 56.40, 52.50 +DU32, 7, 166140 +CURR, 813, 1659888, 988, 2238, 5051, 1249.593900 +CTUN, 812, 0.25, 2.15, 0.000000, 0, 0, 0, 813, 0 +ATT, 0.00, 0.02, -2.52, -0.53, 0.00, 56.75, 52.50 +CTUN, 813, 0.25, 2.22, 0.000000, 0, 0, 1, 813, 0 +ATT, 0.00, -0.30, -2.61, -1.92, 0.00, 57.21, 52.50 +CTUN, 812, 0.25, 2.31, 0.000000, 0, 0, 6, 813, 0 +ATT, 0.00, 0.15, -2.70, -1.85, 0.00, 57.48, 52.50 +CTUN, 813, 0.25, 2.12, 0.000000, 0, 0, 12, 812, 0 +ATT, 0.00, -0.32, -2.70, -0.76, 0.00, 57.54, 52.50 +CTUN, 812, 0.25, 2.28, 0.000000, 0, 0, 14, 813, 0 +ATT, 0.00, -0.70, -2.61, -0.77, 0.00, 57.53, 52.50 +CTUN, 812, 0.28, 2.24, 0.000000, 0, 0, 14, 812, 0 +ATT, 0.00, 0.03, -2.70, -1.59, 0.00, 57.48, 52.50 +CTUN, 812, 0.28, 2.29, 0.000000, 0, 0, 11, 813, 0 +ATT, 0.00, 0.63, -2.70, -1.94, 0.00, 57.36, 52.50 +CTUN, 813, 0.31, 2.42, 0.000000, 0, 0, 11, 813, 0 +ATT, 0.00, 0.90, -2.61, -2.27, 0.00, 57.50, 52.50 +CTUN, 812, 0.31, 2.43, 0.000000, 0, 0, 12, 812, 0 +ATT, 0.00, 1.70, -2.61, -1.65, 0.00, 57.68, 52.50 +CTUN, 813, 0.34, 2.58, 0.000000, 0, 0, 13, 813, 0 +ATT, 0.00, 2.50, -2.70, -0.07, 0.00, 57.45, 52.50 +DU32, 7, 166140 +CURR, 812, 1668016, 992, 2136, 5051, 1255.850300 +CTUN, 812, 0.34, 2.58, 0.000000, 0, 0, 10, 812, 0 +ATT, 0.00, 1.94, -2.42, 0.30, 0.00, 56.94, 52.50 +CTUN, 812, 0.37, 2.58, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, 0.72, -2.52, 0.03, 0.00, 56.58, 52.50 +CTUN, 813, 0.37, 2.47, 0.000000, 0, 0, 8, 813, 0 +ATT, 0.00, -0.19, -2.24, -1.16, 0.00, 56.66, 52.50 +CTUN, 812, 0.40, 2.58, 0.000000, 0, 0, 6, 813, 0 +ATT, 0.00, -0.76, -2.42, -1.33, 0.00, 56.78, 52.50 +CTUN, 812, 0.40, 2.64, 0.000000, 0, 0, 9, 812, 0 +ATT, -0.56, -0.51, -2.33, -0.85, 0.00, 56.71, 52.50 +CTUN, 813, 0.41, 2.59, 0.000000, 0, 0, 7, 813, 0 +ATT, -0.75, 0.24, -0.74, -0.71, 0.00, 56.28, 52.50 +CTUN, 813, 0.41, 2.62, 0.000000, 0, 0, 12, 813, 0 +ATT, -0.75, -0.65, -0.74, 0.70, 0.00, 55.76, 52.50 +CTUN, 813, 0.43, 2.77, 0.000000, 0, 0, 14, 813, 0 +ATT, -0.56, -1.50, -0.56, 2.61, 0.00, 55.24, 52.50 +CTUN, 813, 0.43, 2.81, 0.000000, 0, 1, 13, 813, 0 +ATT, -0.37, -1.72, -0.37, 2.89, 0.00, 55.03, 52.50 +CTUN, 812, 0.45, 2.67, 0.000000, 0, 0, 13, 812, 0 +ATT, -0.75, -1.06, -0.74, 1.22, 0.00, 54.93, 52.50 +DU32, 7, 166140 +CURR, 812, 1676146, 983, 2254, 5051, 1262.135900 +CTUN, 813, 0.45, 2.80, 0.000000, 0, 0, 13, 813, 0 +ATT, 0.00, -1.41, -2.05, -0.04, 0.00, 54.84, 52.50 +CTUN, 812, 0.48, 2.76, 0.000000, 0, 0, 17, 812, 0 +ATT, 0.00, -1.65, -2.52, -0.96, 0.00, 54.57, 52.50 +CTUN, 813, 0.48, 2.86, 0.000000, 0, 0, 11, 813, 0 +ATT, 0.00, -0.88, -2.61, -2.28, 0.00, 54.23, 52.50 +CTUN, 813, 0.49, 2.79, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, -0.78, -2.70, -2.78, 0.00, 53.96, 52.50 +CTUN, 813, 0.49, 2.77, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, -0.56, -2.70, -2.79, 0.00, 53.52, 52.50 +CTUN, 813, 0.51, 2.90, 0.000000, 0, 0, 10, 813, 0 +ATT, 0.00, -0.12, -2.80, -2.59, 0.00, 53.11, 52.50 +CTUN, 812, 0.51, 2.85, 0.000000, 0, 0, 9, 812, 0 +ATT, 0.00, -0.69, -2.89, -2.55, 0.00, 53.05, 52.50 +CTUN, 813, 0.52, 2.82, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, -2.46, -2.70, -2.18, 0.00, 53.31, 52.50 +CTUN, 813, 0.52, 2.82, 0.000000, 0, 1, 13, 813, 0 +ATT, 0.00, -3.09, -2.70, -1.18, 0.00, 54.00, 52.50 +CTUN, 812, 0.54, 2.91, 0.000000, 0, 0, 14, 813, 0 +ATT, 0.00, -1.78, -2.70, -0.37, 0.00, 54.86, 52.50 +DU32, 7, 166140 +CURR, 813, 1684275, 987, 2272, 5051, 1268.367900 +CTUN, 813, 0.54, 2.89, 0.000000, 0, 0, 13, 813, 0 +ATT, 0.00, -1.07, -2.70, 0.41, 0.00, 55.79, 52.50 +CTUN, 813, 0.56, 2.85, 0.000000, 0, 0, 13, 812, 0 +ATT, 0.00, -2.11, -2.61, 1.54, 0.00, 57.00, 52.50 +CTUN, 813, 0.56, 2.78, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, -1.96, -2.61, 1.62, 0.00, 58.46, 52.50 +CTUN, 813, 0.58, 2.89, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, -1.35, -2.70, 1.01, 0.00, 59.86, 52.50 +CTUN, 813, 0.58, 2.75, 0.000000, 0, 0, 12, 813, 0 +ATT, 0.00, 0.09, -2.70, 0.56, 0.00, 61.13, 52.50 +CTUN, 810, 0.60, 2.93, 0.000000, 0, 0, 4, 810, 0 +ATT, 0.00, 1.32, -2.61, 0.69, 0.00, 62.34, 52.50 +CTUN, 809, 0.60, 2.76, 0.000000, 0, 0, -2, 809, 0 +ATT, 0.00, 1.01, -2.61, 0.72, 0.00, 63.41, 53.41 +CTUN, 808, 0.60, 2.82, 0.000000, 0, 0, -10, 808, 0 +ATT, 0.00, 0.31, -2.80, 0.37, 0.00, 64.35, 54.35 +CTUN, 806, 0.60, 2.90, 0.000000, 0, 0, -17, 807, 0 +ATT, 0.09, -0.17, -3.08, -0.03, 0.00, 65.01, 55.01 +CTUN, 805, 0.60, 2.84, 0.000000, 0, 0, -20, 805, 0 +ATT, 0.46, -0.27, -3.17, -0.33, 0.00, 65.31, 55.31 +DU32, 7, 166140 +CURR, 805, 1692378, 992, 2200, 5051, 1274.398100 +CTUN, 805, 0.57, 2.80, 0.000000, 0, 0, -26, 805, 0 +ATT, 0.46, 0.46, -3.26, -0.31, 0.00, 65.39, 55.40 +CTUN, 804, 0.57, 2.58, 0.000000, 0, 0, -31, 804, 0 +ATT, 0.46, 1.33, -3.73, -0.15, 0.00, 65.26, 55.40 +CTUN, 804, 0.50, 2.74, 0.000000, 0, 0, -42, 804, 0 +ATT, 1.78, 0.78, -4.29, -0.44, 0.00, 64.81, 55.40 +CTUN, 804, 0.50, 2.48, 0.000000, 0, 0, -44, 805, 0 +ATT, 1.59, -0.16, -4.38, -0.82, 0.00, 63.99, 55.40 +CTUN, 805, 0.43, 2.53, 0.000000, 0, 0, -47, 805, 0 +ATT, 1.59, -0.16, -4.57, -0.77, 0.00, 62.80, 55.40 +CTUN, 804, 0.43, 2.54, 0.000000, 0, 0, -48, 804, 0 +ATT, 1.59, 0.34, -4.57, -0.90, 0.00, 61.17, 55.40 +CTUN, 805, 0.33, 2.40, 0.000000, 0, 0, -44, 805, 0 +ATT, 1.40, 0.62, -4.76, -1.48, 0.00, 59.36, 55.40 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 805, 0.33, 2.38, 0.000000, 0, 0, -41, 805, 0 +ATT, 1.78, 0.20, -4.76, -2.22, 0.00, 57.76, 55.40 +CTUN, 804, 0.25, 1.98, 0.000000, 0, 0, -33, 805, 0 +ATT, 1.78, 0.24, -4.85, -2.18, 0.00, 56.40, 55.40 +CTUN, 805, 0.25, 2.06, 0.000000, 0, 0, -21, 804, 0 +ATT, 1.68, 0.14, -4.85, -1.06, 0.00, 55.42, 55.40 +DU32, 7, 166140 +CURR, 804, 1700422, 984, 2192, 5051, 1280.453400 +CTUN, 804, 0.20, 1.20, 0.000000, 0, 0, -9, 804, 0 +ATT, 1.78, 0.05, -4.76, -0.11, 0.00, 54.57, 55.40 +CTUN, 805, 0.20, 0.69, 0.000000, 0, 0, 0, 805, 0 +ATT, 2.81, 0.57, -4.48, 0.17, 0.00, 53.67, 55.40 +CTUN, 805, 0.20, 0.64, 0.000000, 0, 0, 7, 804, 0 +ATT, 2.90, 0.75, -4.57, 0.09, 0.00, 52.94, 55.40 +CTUN, 805, 0.20, 1.07, 0.000000, 0, 0, 14, 805, 0 +ATT, 3.09, 0.73, -4.85, 0.14, 0.00, 52.43, 55.40 +CTUN, 805, 0.20, 1.05, 0.000000, 0, 0, 22, 805, 0 +ATT, 3.37, 1.48, -4.76, -0.43, 0.00, 52.19, 55.40 +CTUN, 804, 0.20, 1.92, 0.000000, 0, 0, 25, 805, 0 +ATT, 6.00, 1.26, -6.16, -1.18, 0.00, 52.19, 55.40 +CTUN, 804, 0.20, 2.27, 0.000000, 0, 0, 27, 804, 0 +ATT, 7.12, 2.30, -6.53, -2.06, 0.00, 52.22, 55.40 +CTUN, 805, 0.21, 2.28, 0.000000, 0, 1, 31, 805, 0 +ATT, 7.87, 5.53, -6.72, -2.35, 0.00, 52.40, 55.40 +CTUN, 804, 0.21, 2.45, 0.000000, 0, 5, 31, 809, 0 +ATT, 7.87, 8.42, -6.72, -2.49, 0.00, 52.83, 55.40 +CTUN, 804, 0.24, 2.49, 0.000000, 0, 9, 28, 814, 0 +ATT, 7.78, 9.36, -6.81, -3.20, 0.00, 53.34, 55.40 +DU32, 7, 166140 +CURR, 804, 1708481, 994, 2223, 5051, 1286.538800 +CTUN, 804, 0.24, 2.46, 0.000000, 0, 11, 23, 815, 0 +ATT, 6.28, 9.72, -6.81, -4.34, 0.00, 53.78, 55.40 +CTUN, 805, 0.30, 2.54, 0.000000, 0, 11, 22, 815, 0 +ATT, 0.28, 8.89, -6.72, -4.51, 0.00, 54.15, 55.40 +CTUN, 804, 0.30, 2.45, 0.000000, 0, 8, 19, 813, 0 +ATT, 0.00, 5.31, -6.72, -3.84, 0.00, 54.34, 55.40 +CTUN, 803, 0.36, 2.61, 0.000000, 0, 3, 15, 808, 0 +ATT, 0.00, 1.64, -6.06, -3.62, 0.00, 54.06, 55.40 +CTUN, 805, 0.36, 2.61, 0.000000, 0, 1, 13, 805, 0 +ATT, 0.00, 0.60, -6.06, -3.07, 0.00, 53.36, 55.40 +CTUN, 805, 0.43, 2.65, 0.000000, 0, 0, 9, 805, 0 +ATT, 0.00, 0.64, -6.72, -1.80, 0.00, 52.46, 55.40 +CTUN, 804, 0.43, 2.82, 0.000000, 0, 0, 6, 805, 0 +ATT, -1.32, 0.19, -6.81, -1.06, 0.00, 51.66, 55.40 +CTUN, 805, 0.46, 2.88, 0.000000, 0, 0, 3, 805, 0 +ATT, -4.16, -0.64, -7.93, -1.78, 0.00, 51.30, 55.40 +CTUN, 804, 0.46, 2.81, 0.000000, 0, 0, 1, 804, 0 +ATT, -6.25, -1.86, -8.30, -3.19, 0.00, 51.03, 55.40 +CTUN, 805, 0.50, 2.73, 0.000000, 0, 1, 0, 806, 0 +ATT, -7.76, -3.84, -7.56, -4.51, 0.00, 50.84, 55.40 +DU32, 7, 166140 +CURR, 804, 1716561, 997, 2179, 5051, 1292.618400 +CTUN, 805, 0.50, 2.81, 0.000000, 0, 4, -4, 809, 0 +ATT, -7.76, -6.16, -9.42, -5.05, 0.00, 50.50, 55.40 +CTUN, 804, 0.52, 2.67, 0.000000, 0, 7, -5, 811, 0 +ATT, -7.67, -7.35, -7.56, -5.51, 0.00, 49.96, 55.40 +CTUN, 804, 0.52, 2.72, 0.000000, 0, 9, -5, 813, 0 +ATT, -6.25, -7.23, -8.12, -5.50, 0.00, 49.18, 55.40 +CTUN, 805, 0.54, 2.72, 0.000000, 0, 7, -5, 812, 0 +ATT, -2.55, -6.27, -7.56, -5.15, 0.00, 48.41, 55.40 +CTUN, 805, 0.53, 2.82, 0.000000, 0, 6, -7, 811, 0 +ATT, -0.37, -4.68, -6.34, -4.90, 0.00, 47.79, 55.40 +CTUN, 804, 0.53, 2.92, 0.000000, 0, 3, -10, 808, 0 +ATT, 0.00, -2.61, -4.57, -4.25, 0.00, 47.34, 55.40 +CTUN, 804, 0.52, 2.81, 0.000000, 0, 1, -13, 806, 0 +ATT, 0.00, -0.55, -2.52, -3.20, 0.00, 47.20, 55.40 +CTUN, 805, 0.52, 2.89, 0.000000, 0, 0, -12, 805, 0 +ATT, 0.00, 0.64, -2.70, -1.73, 0.00, 47.52, 55.40 +CTUN, 804, 0.52, 2.96, 0.000000, 0, 0, -16, 804, 0 +ATT, 0.00, 1.25, -2.42, 0.19, 0.00, 48.17, 55.40 +CTUN, 804, 0.52, 2.92, 0.000000, 0, 0, -14, 805, 0 +ATT, 0.00, 1.11, -2.42, 2.24, 0.00, 49.12, 55.40 +DU32, 7, 166140 +CURR, 804, 1724645, 987, 2168, 5051, 1298.715700 +CTUN, 804, 0.50, 2.83, 0.000000, 0, 1, -15, 806, 0 +ATT, 0.00, 1.27, -2.52, 3.73, 0.00, 50.22, 55.40 +CTUN, 805, 0.50, 2.84, 0.000000, 0, 1, -23, 806, 0 +ATT, 0.00, 1.61, -2.61, 3.99, 0.00, 51.34, 55.40 +CTUN, 804, 0.48, 2.89, 0.000000, 0, 1, -24, 806, 0 +ATT, 0.00, 1.50, -2.70, 3.93, 0.00, 52.36, 55.40 +CTUN, 805, 0.48, 2.81, 0.000000, 0, 1, -27, 805, 0 +ATT, 0.00, 0.93, -3.64, 4.01, 0.00, 53.27, 55.40 +CTUN, 804, 0.46, 2.67, 0.000000, 0, 1, -31, 806, 0 +ATT, 0.00, 0.56, -5.04, 3.62, 0.00, 54.02, 55.40 +CTUN, 804, 0.46, 2.70, 0.000000, 0, 1, -31, 805, 0 +ATT, 0.00, 0.96, -6.34, 2.56, 0.00, 54.59, 55.40 +CTUN, 804, 0.41, 2.71, 0.000000, 0, 0, -34, 804, 0 +ATT, 0.00, 1.62, -6.81, 1.21, 0.00, 55.09, 55.40 +CTUN, 805, 0.41, 2.75, 0.000000, 0, 0, -34, 805, 0 +ATT, 0.00, 1.33, -6.81, -0.08, 0.00, 55.59, 55.40 +CTUN, 805, 0.35, 2.54, 0.000000, 0, 0, -34, 805, 0 +ATT, 0.00, 0.33, -6.72, -1.60, 0.00, 56.21, 55.40 +CTUN, 804, 0.35, 2.49, 0.000000, 0, 0, -30, 805, 0 +ATT, 0.00, -0.29, -6.81, -2.53, 0.00, 56.65, 55.40 +DU32, 7, 166140 +CURR, 805, 1732696, 982, 2161, 5051, 1304.756300 +CTUN, 804, 0.30, 2.56, 0.000000, 0, 0, -28, 804, 0 +ATT, 0.00, 0.02, -7.18, -2.91, 0.00, 56.98, 55.40 +CTUN, 804, 0.30, 2.49, 0.000000, 0, 0, -26, 804, 0 +ATT, 0.00, 0.45, -6.90, -2.65, 0.00, 57.04, 55.40 +CTUN, 804, 0.25, 2.52, 0.000000, 0, 0, -23, 804, 0 +ATT, 0.00, -0.45, -6.53, -2.22, 0.00, 56.95, 55.40 +CTUN, 805, 0.25, 2.43, 0.000000, 0, 0, -19, 804, 0 +ATT, 0.00, -0.70, -6.53, -2.10, 0.00, 56.84, 55.40 +CTUN, 805, 0.20, 2.33, 0.000000, 0, 0, -14, 804, 0 +ATT, 0.00, 0.00, -6.62, -1.55, 0.00, 56.65, 55.40 +CTUN, 805, 0.20, 2.38, 0.000000, 0, 0, -12, 805, 0 +ATT, 0.00, 0.29, -6.81, -1.55, 0.00, 56.51, 55.40 +CTUN, 805, 0.20, 2.35, 0.000000, 0, 0, -6, 805, 0 +ATT, 0.00, -0.08, -6.53, -2.03, 0.00, 56.44, 55.40 +CTUN, 804, 0.20, 2.45, 0.000000, 0, 0, 0, 804, 0 +ATT, 0.00, -0.63, -6.53, -2.36, 0.00, 56.33, 55.40 +CTUN, 805, 0.20, 2.28, 0.000000, 0, 0, 6, 804, 0 +ATT, 0.00, -0.10, -6.53, -1.69, 0.00, 56.36, 55.40 +CTUN, 804, 0.20, 2.33, 0.000000, 0, 0, 9, 804, 0 +ATT, 0.00, -0.01, -6.62, -0.77, 0.00, 56.32, 55.40 +DU32, 7, 166140 +CURR, 805, 1740738, 986, 2173, 5051, 1310.781400 +CTUN, 804, 0.20, 2.41, 0.000000, 0, 0, 13, 805, 0 +ATT, 0.00, -0.14, -6.53, -0.73, 0.00, 56.22, 55.40 +CTUN, 804, 0.20, 2.43, 0.000000, 0, 0, 15, 804, 0 +ATT, 0.00, -0.45, -6.44, -1.22, 0.00, 56.24, 55.40 +CTUN, 804, 0.20, 2.57, 0.000000, 0, 0, 17, 804, 0 +ATT, 0.00, -0.53, -6.06, -1.86, 0.00, 56.30, 55.40 +CTUN, 805, 0.21, 2.42, 0.000000, 0, 0, 21, 804, 0 +ATT, 0.00, 0.38, -6.06, -1.34, 0.00, 56.46, 55.40 +CTUN, 804, 0.21, 2.50, 0.000000, 0, 0, 21, 805, 0 +ATT, 0.00, 0.17, -6.16, -0.84, 0.00, 56.85, 55.40 +CTUN, 804, 0.25, 2.61, 0.000000, 0, 0, 16, 804, 0 +ATT, 0.00, -0.45, -6.16, -1.53, 0.00, 57.46, 55.40 +CTUN, 804, 0.25, 2.57, 0.000000, 0, 0, 18, 804, 0 +ATT, 0.00, -0.71, -6.06, -1.64, 0.00, 58.10, 55.40 +CTUN, 805, 0.28, 2.66, 0.000000, 0, 0, 14, 805, 0 +ATT, 0.00, -0.59, -6.25, -1.48, 0.00, 58.81, 55.40 +CTUN, 805, 0.28, 2.68, 0.000000, 0, 0, 14, 804, 0 +ATT, 0.00, -0.41, -6.16, -1.41, 0.00, 59.56, 55.40 +CTUN, 801, 0.31, 2.62, 0.000000, 0, 0, 11, 805, 0 +ATT, 0.00, -0.31, -6.16, -1.21, 0.00, 60.39, 55.40 +DU32, 7, 166140 +CURR, 805, 1748783, 985, 2191, 5051, 1316.841300 +CTUN, 805, 0.31, 2.57, 0.000000, 0, 0, 13, 804, 0 +ATT, 0.00, 0.11, -6.06, -0.52, 0.00, 61.30, 55.40 +CTUN, 805, 0.35, 2.67, 0.000000, 0, 0, 9, 804, 0 +ATT, 0.00, 0.74, -6.06, 0.37, 0.00, 62.21, 55.40 +CTUN, 804, 0.35, 2.76, 0.000000, 0, 0, 8, 805, 0 +ATT, 0.00, 1.37, -6.53, 0.61, 0.00, 62.87, 55.40 +CTUN, 804, 0.36, 2.79, 0.000000, 0, 0, -2, 805, 0 +ATT, 0.00, 0.94, -6.81, 0.27, 0.00, 63.32, 55.40 +CTUN, 804, 0.36, 2.61, 0.000000, 0, 0, -5, 804, 0 +ATT, 0.00, 0.22, -7.65, -0.75, 0.00, 63.43, 55.40 +CTUN, 805, 0.36, 2.59, 0.000000, 0, 0, -7, 804, 0 +ATT, 0.00, 0.00, -8.12, -1.43, 0.00, 63.53, 55.40 +CTUN, 805, 0.35, 2.45, 0.000000, 0, 0, -7, 805, 0 +ATT, 0.00, -0.45, -8.30, -1.93, 0.00, 63.13, 55.40 +CTUN, 805, 0.35, 2.69, 0.000000, 0, 0, -9, 805, 0 +ATT, 0.00, -0.89, -8.21, -1.78, 0.00, 62.54, 55.40 +CTUN, 804, 0.31, 2.67, 0.000000, 0, 0, -10, 805, 0 +ATT, 0.00, -0.60, -8.21, -1.45, 0.00, 61.84, 55.40 +CTUN, 804, 0.31, 2.66, 0.000000, 0, 0, -7, 804, 0 +ATT, 0.00, 0.38, -8.21, -1.40, 0.00, 60.94, 55.40 +DU32, 7, 166140 +CURR, 804, 1756828, 988, 2201, 5051, 1322.861200 +CTUN, 804, 0.30, 2.59, 0.000000, 0, 0, -6, 804, 0 +ATT, 0.00, 0.45, -8.30, -0.97, 0.00, 59.84, 55.40 +CTUN, 805, 0.30, 2.58, 0.000000, 0, 0, -3, 805, 0 +ATT, 0.00, 0.10, -8.21, -0.90, 0.00, 58.76, 55.40 +CTUN, 805, 0.28, 2.64, 0.000000, 0, 0, 0, 804, 0 +ATT, 0.00, -0.51, -8.21, -1.60, 0.00, 57.97, 55.40 +CTUN, 804, 0.28, 2.50, 0.000000, 0, 0, 0, 804, 0 +ATT, 0.00, -0.91, -8.30, -2.47, 0.00, 57.53, 55.40 +CTUN, 805, 0.25, 2.54, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, -1.12, -8.77, -2.85, 0.00, 57.48, 55.40 +CTUN, 805, 0.25, 2.65, 0.000000, 0, 1, 3, 806, 0 +ATT, 0.00, -1.26, -10.64, -2.92, 0.00, 57.99, 55.40 +CTUN, 805, 0.25, 2.49, 0.000000, 0, 0, 4, 804, 0 +ATT, 0.00, -0.52, -10.64, -2.99, 0.00, 58.74, 55.40 +CTUN, 804, 0.25, 2.42, 0.000000, 0, 1, 6, 806, 0 +ATT, 0.00, -0.19, -10.64, -3.89, 0.00, 59.32, 55.40 +CTUN, 804, 0.24, 2.84, 0.000000, 0, 2, 6, 807, 0 +ATT, 0.00, -0.67, -9.33, -5.32, 0.00, 59.73, 55.40 +CTUN, 805, 0.24, 2.63, 0.000000, 0, 3, 8, 808, 0 +ATT, 0.00, -0.96, -9.33, -6.47, 0.00, 60.00, 55.40 +DU32, 7, 166140 +CURR, 804, 1764878, 980, 2189, 5028, 1328.926500 +CTUN, 804, 0.23, 2.53, 0.000000, 0, 4, 10, 809, 0 +ATT, 0.00, -2.12, -9.33, -6.30, 0.00, 60.12, 55.40 +CTUN, 805, 0.24, 2.51, 0.000000, 0, 4, 14, 809, 0 +ATT, 0.00, -1.60, -7.84, -5.16, 0.00, 60.06, 55.40 +CTUN, 804, 0.24, 2.63, 0.000000, 0, 2, 18, 807, 0 +ATT, 0.00, 0.13, -6.81, -3.67, 0.00, 60.03, 55.40 +CTUN, 804, 0.24, 2.57, 0.000000, 0, 1, 21, 805, 0 +ATT, 0.00, 1.52, -5.78, -2.29, 0.00, 59.94, 55.40 +CTUN, 805, 0.24, 2.63, 0.000000, 0, 0, 26, 805, 0 +ATT, 0.00, 2.09, -4.76, -0.69, 0.00, 59.65, 55.40 +CTUN, 804, 0.25, 2.52, 0.000000, 0, 0, 26, 804, 0 +ATT, 0.00, 1.49, -4.01, 0.59, 0.00, 59.12, 55.40 +CTUN, 805, 0.25, 2.68, 0.000000, 0, 0, 29, 804, 0 +ATT, 0.00, 0.97, -2.70, 1.26, 0.00, 58.25, 55.40 +CTUN, 804, 0.27, 2.86, 0.000000, 0, 0, 30, 805, 0 +ATT, 0.00, 1.28, -2.89, 1.91, 0.00, 57.22, 55.40 +CTUN, 804, 0.27, 2.74, 0.000000, 0, 0, 30, 805, 0 +ATT, 0.00, 1.15, -4.48, 2.37, 0.00, 56.17, 55.40 +CTUN, 804, 0.31, 2.73, 0.000000, 0, 0, 30, 805, 0 +ATT, 0.00, 1.04, -4.85, 1.61, 0.00, 55.24, 55.40 +DU32, 7, 166140 +CURR, 805, 1772934, 975, 2187, 5051, 1335.044300 +CTUN, 805, 0.31, 2.68, 0.000000, 0, 0, 27, 804, 0 +ATT, 0.00, 1.14, -5.69, -0.05, 0.00, 54.59, 55.40 +CTUN, 805, 0.34, 2.70, 0.000000, 0, 0, 26, 805, 0 +ATT, 0.00, 2.22, -6.53, -0.67, 0.00, 54.29, 55.40 +CTUN, 805, 0.34, 2.83, 0.000000, 0, 0, 24, 805, 0 +ATT, 0.00, 3.10, -6.72, -0.92, 0.00, 54.24, 55.40 +CTUN, 804, 0.37, 2.84, 0.000000, 0, 1, 23, 805, 0 +ATT, 0.00, 2.48, -6.72, -1.59, 0.00, 54.32, 55.40 +CTUN, 804, 0.37, 2.95, 0.000000, 0, 0, 22, 805, 0 +ATT, 0.00, 1.99, -6.81, -2.51, 0.00, 54.61, 55.40 +CTUN, 805, 0.40, 2.75, 0.000000, 0, 1, 22, 805, 0 +ATT, 0.00, 2.13, -6.72, -3.03, 0.00, 54.89, 55.40 +CTUN, 804, 0.40, 2.86, 0.000000, 0, 1, 19, 805, 0 +ATT, 0.00, 1.69, -6.81, -2.63, 0.00, 55.18, 55.40 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +CTUN, 804, 0.43, 2.96, 0.000000, 0, 0, 20, 804, 0 +ATT, 0.00, 0.86, -6.72, -1.94, 0.00, 55.38, 55.40 +CTUN, 805, 0.43, 2.84, 0.000000, 0, 0, 17, 805, 0 +ATT, 0.00, 0.51, -6.81, -1.93, 0.00, 55.48, 55.40 +CTUN, 804, 0.46, 2.81, 0.000000, 0, 0, 15, 805, 0 +ATT, 0.00, 0.12, -6.81, -2.07, 0.00, 55.39, 55.40 +DU32, 7, 166140 +CURR, 805, 1780985, 980, 2207, 5051, 1341.179300 +CTUN, 805, 0.46, 2.93, 0.000000, 0, 0, 13, 805, 0 +ATT, 0.00, -0.86, -7.74, -2.03, 0.00, 55.41, 55.40 +CTUN, 805, 0.47, 2.96, 0.000000, 0, 0, 12, 804, 0 +ATT, 0.00, -1.34, -7.84, -1.97, 0.00, 55.53, 55.40 +CTUN, 805, 0.47, 2.95, 0.000000, 0, 0, 10, 805, 0 +ATT, 0.00, -0.70, -7.84, -2.49, 0.00, 55.94, 55.40 +CTUN, 804, 0.49, 3.08, 0.000000, 0, 0, 8, 805, 0 +ATT, 0.00, 0.49, -7.65, -3.31, 0.00, 56.52, 55.40 +CTUN, 805, 0.49, 2.86, 0.000000, 0, 1, 8, 805, 0 +ATT, 0.00, 0.83, -6.90, -3.75, 0.00, 57.10, 55.40 +CTUN, 805, 0.49, 2.93, 0.000000, 0, 1, 10, 806, 0 +ATT, 0.00, 0.36, -6.72, -3.41, 0.00, 57.57, 55.40 +CTUN, 804, 0.49, 2.86, 0.000000, 0, 1, 10, 806, 0 +ATT, 0.00, -0.27, -5.97, -2.76, 0.00, 57.73, 55.40 +CTUN, 805, 0.49, 3.03, 0.000000, 0, 0, 10, 805, 0 +ATT, 0.00, -1.17, -4.76, -2.08, 0.00, 57.47, 55.40 +CTUN, 805, 0.49, 3.11, 0.000000, 0, 0, 8, 805, 0 +ATT, 0.00, -1.73, -2.89, -0.92, 0.00, 56.91, 55.40 +CTUN, 805, 0.49, 3.01, 0.000000, 0, 0, 7, 805, 0 +ATT, 0.00, -1.54, -2.61, 0.90, 0.00, 56.09, 55.40 +DU32, 7, 166140 +CURR, 805, 1789034, 989, 2194, 5051, 1347.313600 +CTUN, 805, 0.49, 2.91, 0.000000, 0, 0, 6, 804, 0 +ATT, 0.00, -1.38, -2.80, 2.77, 0.00, 55.24, 55.40 +CTUN, 804, 0.49, 3.12, 0.000000, 0, 1, 1, 805, 0 +ATT, 0.00, -1.70, -2.89, 3.30, 0.00, 54.55, 55.40 +CTUN, 804, 0.49, 2.94, 0.000000, 0, 1, 0, 806, 0 +ATT, 0.00, -1.77, -3.26, 2.71, 0.00, 54.02, 55.40 +CTUN, 804, 0.49, 2.96, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, -1.32, -4.20, 1.90, 0.00, 53.52, 55.40 +CTUN, 804, 0.47, 2.84, 0.000000, 0, 0, 0, 804, 0 +ATT, 0.00, -1.47, -4.76, 1.04, 0.00, 53.18, 55.40 +CTUN, 804, 0.47, 2.91, 0.000000, 0, 0, -4, 805, 0 +ATT, 0.00, -1.88, -4.66, -0.20, 0.00, 53.07, 55.40 +CTUN, 806, 0.44, 2.77, 0.000000, 0, 0, -8, 804, 0 +ATT, 0.00, -1.79, -4.76, -1.37, 0.00, 53.07, 55.40 +CTUN, 804, 0.44, 2.69, 0.000000, 0, 0, -7, 804, 0 +ATT, 0.00, -2.09, -4.85, -1.93, 0.00, 53.14, 55.40 +CTUN, 804, 0.41, 2.68, 0.000000, 0, 0, -8, 804, 0 +ATT, 0.00, -1.73, -4.76, -2.28, 0.00, 53.37, 55.40 +CTUN, 804, 0.41, 2.75, 0.000000, 0, 0, -8, 805, 0 +ATT, 0.00, -0.46, -4.76, -2.16, 0.00, 53.70, 55.40 +DU32, 7, 166140 +CURR, 804, 1797081, 989, 2181, 5051, 1353.370500 +CTUN, 805, 0.37, 2.67, 0.000000, 0, 0, -6, 804, 0 +ATT, 0.00, 0.00, -4.85, -1.54, 0.00, 54.03, 55.40 +CTUN, 804, 0.37, 2.78, 0.000000, 0, 0, -4, 806, 0 +ATT, 0.00, -0.49, -4.76, -1.09, 0.00, 54.43, 55.40 +CTUN, 805, 0.33, 2.62, 0.000000, 0, 0, -4, 805, 0 +ATT, 0.00, -0.80, -4.85, -1.10, 0.00, 55.02, 55.40 +CTUN, 804, 0.33, 2.65, 0.000000, 0, 0, -1, 804, 0 +ATT, 0.00, -0.14, -4.76, -1.48, 0.00, 55.83, 55.40 +CTUN, 805, 0.30, 2.65, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, 0.81, -4.76, -1.81, 0.00, 56.83, 55.40 +CTUN, 805, 0.30, 2.73, 0.000000, 0, 0, 4, 804, 0 +ATT, 0.00, 1.09, -4.76, -2.12, 0.00, 58.06, 55.40 +CTUN, 805, 0.28, 2.72, 0.000000, 0, 0, 8, 804, 0 +ATT, 0.00, 0.95, -4.57, -2.22, 0.00, 59.15, 55.40 +CTUN, 805, 0.28, 2.69, 0.000000, 0, 0, 7, 805, 0 +ATT, 0.00, 1.25, -4.38, -2.28, 0.00, 60.13, 55.40 +CTUN, 804, 0.26, 2.69, 0.000000, 0, 0, 11, 804, 0 +ATT, 0.00, 1.19, -2.98, -1.75, 0.00, 60.81, 55.40 +CTUN, 804, 0.26, 2.68, 0.000000, 0, 0, 15, 804, 0 +ATT, 0.00, 0.15, -2.42, -0.94, 0.00, 61.29, 55.40 +DU32, 7, 166140 +CURR, 804, 1805127, 986, 2214, 5051, 1359.485800 +CTUN, 804, 0.25, 2.61, 0.000000, 0, 0, 13, 804, 0 +ATT, 0.00, -0.16, -2.42, 0.20, 0.00, 61.54, 55.40 +CTUN, 804, 0.26, 2.64, 0.000000, 0, 0, 16, 805, 0 +ATT, 0.00, 0.24, -2.42, 1.02, 0.00, 61.41, 55.40 +CTUN, 805, 0.25, 2.60, 0.000000, 0, 0, 14, 805, 0 +ATT, 0.00, 0.10, -3.08, 1.42, 0.00, 61.00, 55.40 +CTUN, 805, 0.26, 2.68, 0.000000, 0, 0, 14, 804, 0 +ATT, 0.00, -0.57, -4.10, 1.02, 0.00, 60.16, 55.40 +CTUN, 806, 0.25, 2.59, 0.000000, 0, 0, 14, 805, 0 +ATT, 0.00, -0.85, -4.66, 0.01, 0.00, 59.32, 55.40 +CTUN, 805, 0.26, 2.66, 0.000000, 0, 0, 17, 805, 0 +ATT, 0.00, -1.15, -4.76, -1.17, 0.00, 58.42, 55.40 +CTUN, 805, 0.26, 2.70, 0.000000, 0, 0, 19, 805, 0 +ATT, 0.00, -1.20, -4.76, -2.29, 0.00, 57.50, 55.40 +CTUN, 805, 0.26, 2.63, 0.000000, 0, 0, 20, 806, 0 +ATT, 0.00, -1.75, -4.85, -2.64, 0.00, 56.76, 55.40 +CTUN, 805, 0.26, 2.64, 0.000000, 0, 1, 18, 806, 0 +ATT, 0.00, -2.12, -4.85, -2.48, 0.00, 56.18, 55.40 +CTUN, 806, 0.27, 2.69, 0.000000, 0, 0, 19, 806, 0 +ATT, 0.09, -1.89, -4.85, -1.47, 0.00, 55.40, 55.40 +DU32, 7, 166140 +CURR, 805, 1813177, 983, 2190, 5051, 1365.581700 +CTUN, 807, 0.27, 2.64, 0.000000, 0, 0, 19, 805, 0 +ATT, 0.46, -1.18, -4.76, -0.44, 0.00, 54.44, 55.40 +CTUN, 806, 0.28, 2.63, 0.000000, 0, 0, 18, 805, 0 +ATT, 1.31, -0.57, -4.57, -0.48, 0.00, 53.34, 55.40 +CTUN, 805, 0.28, 2.73, 0.000000, 0, 0, 19, 804, 0 +ATT, 1.59, -0.33, -4.57, -0.92, 0.00, 52.17, 55.40 +CTUN, 805, 0.29, 2.80, 0.000000, 0, 0, 15, 805, 0 +ATT, 1.78, -0.11, -4.57, -1.52, 0.00, 51.02, 55.40 +CTUN, 806, 0.29, 2.81, 0.000000, 0, 0, 17, 805, 0 +ATT, 2.34, 0.75, -4.57, -1.53, 0.00, 49.90, 55.40 +CTUN, 804, 0.30, 2.73, 0.000000, 0, 0, 15, 805, 0 +ATT, 2.53, 1.69, -4.57, -1.39, 0.00, 48.68, 55.40 +CTUN, 804, 0.30, 2.92, 0.000000, 0, 0, 15, 804, 0 +ATT, 4.03, 2.43, -4.57, -1.05, 0.00, 47.40, 55.40 +CTUN, 805, 0.31, 2.81, 0.000000, 0, 0, 12, 804, 0 +ATT, 4.96, 2.79, -4.57, -0.65, 0.00, 46.00, 55.40 +CTUN, 804, 0.31, 2.58, 0.000000, 0, 1, 9, 806, 0 +ATT, 4.78, 3.64, -4.38, -0.50, 0.00, 44.78, 54.78 +CTUN, 803, 0.32, 2.78, 0.000000, 0, 1, 5, 806, 0 +ATT, 4.68, 4.47, -4.38, -0.32, 0.00, 43.72, 53.72 +DU32, 7, 166140 +CURR, 805, 1821225, 978, 2180, 5051, 1371.645100 +CTUN, 804, 0.32, 2.78, 0.000000, 0, 2, 5, 806, 0 +ATT, 4.59, 5.28, -4.38, 0.21, 0.00, 42.70, 52.70 +CTUN, 804, 0.32, 2.73, 0.000000, 0, 3, 8, 808, 0 +ATT, 4.31, 4.96, -4.66, 1.40, 0.00, 41.88, 51.88 +CTUN, 805, 0.32, 2.72, 0.000000, 0, 2, 6, 806, 0 +ATT, 3.56, 4.02, -4.48, 2.43, 0.00, 41.33, 51.33 +CTUN, 804, 0.32, 2.78, 0.000000, 0, 1, 5, 806, 0 +ATT, 2.71, 2.82, -4.48, 1.87, 0.00, 41.14, 51.14 +CTUN, 804, 0.32, 2.74, 0.000000, 0, 0, 2, 804, 0 +ATT, 0.28, 1.75, -4.76, 1.39, 0.00, 41.40, 51.14 +CTUN, 804, 0.32, 2.71, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, 0.73, -6.53, 1.08, 0.00, 42.16, 51.14 +CTUN, 805, 0.32, 2.74, 0.000000, 0, 0, 1, 805, 0 +ATT, 0.00, -0.69, -6.53, 0.29, 0.00, 43.31, 51.14 +CTUN, 804, 0.32, 2.66, 0.000000, 0, 0, 1, 804, 0 +ATT, 0.00, -1.70, -6.81, -0.74, 0.00, 44.66, 51.14 +CTUN, 805, 0.30, 2.73, 0.000000, 0, 0, 3, 804, 0 +ATT, 0.00, -1.86, -6.81, -1.62, 0.00, 46.17, 51.14 +CTUN, 805, 0.30, 2.78, 0.000000, 0, 0, 1, 800, 0 +ATT, 0.00, -1.24, -6.81, -2.03, 0.00, 47.40, 51.14 +DU32, 7, 166140 +CURR, 804, 1829279, 979, 2190, 5028, 1377.735600 +CTUN, 805, 0.29, 2.73, 0.000000, 0, 0, 2, 805, 0 +ATT, 0.00, -0.38, -6.81, -1.85, 0.00, 48.56, 51.14 +CTUN, 804, 0.29, 2.64, 0.000000, 0, 0, 5, 804, 0 +ATT, 0.00, -0.51, -6.72, -2.02, 0.00, 49.59, 51.14 +CTUN, 804, 0.29, 2.75, 0.000000, 0, 0, 6, 805, 0 +ATT, 0.00, -0.41, -6.72, -2.98, 0.00, 50.44, 51.14 +CTUN, 804, 0.29, 2.70, 0.000000, 0, 1, 9, 805, 0 +ATT, 0.28, -0.04, -6.90, -3.46, 0.00, 50.98, 51.14 +CTUN, 804, 0.29, 2.78, 0.000000, 0, 1, 10, 805, 0 +ATT, 0.09, 0.53, -6.81, -3.21, 0.00, 51.36, 51.14 +CTUN, 804, 0.29, 2.70, 0.000000, 0, 0, 12, 805, 0 +ATT, 0.65, 0.42, -6.72, -2.77, 0.00, 51.61, 51.14 +CTUN, 804, 0.29, 2.82, 0.000000, 0, 0, 14, 805, 0 +ATT, 1.03, -0.03, -6.81, -2.28, 0.00, 51.81, 51.14 +CTUN, 804, 0.29, 2.78, 0.000000, 0, 0, 15, 804, 0 +ATT, 0.93, 0.00, -6.72, -1.52, 0.00, 51.97, 51.14 +CTUN, 804, 0.29, 2.89, 0.000000, 0, 0, 12, 804, 0 +ATT, 0.84, 0.00, -6.81, -1.22, 0.00, 52.10, 51.14 +CTUN, 805, 0.30, 2.79, 0.000000, 0, 0, 11, 804, 0 +ATT, 0.93, -0.46, -6.72, -1.55, 0.00, 52.31, 51.14 +DU32, 7, 166140 +CURR, 805, 1837325, 980, 2172, 5051, 1383.812300 +CTUN, 804, 0.30, 2.73, 0.000000, 0, 0, 12, 805, 0 +ATT, 1.03, -0.97, -6.81, -2.00, 0.00, 52.42, 51.14 +CTUN, 804, 0.30, 2.83, 0.000000, 0, 0, 11, 804, 0 +ATT, 1.03, -0.35, -6.81, -2.37, 0.00, 52.50, 51.14 +CTUN, 805, 0.30, 2.63, 0.000000, 0, 0, 14, 805, 0 +ATT, 1.03, 0.64, -6.72, -1.82, 0.00, 52.40, 51.14 +CTUN, 804, 0.30, 2.75, 0.000000, 0, 0, 11, 804, 0 +ATT, 1.12, 1.26, -6.72, -1.31, 0.00, 52.39, 51.14 +CTUN, 804, 0.30, 2.85, 0.000000, 0, 0, 9, 806, 0 +ATT, 1.96, 1.69, -6.81, -1.28, 0.00, 52.48, 51.14 +CTUN, 804, 0.31, 2.71, 0.000000, 0, 0, 8, 804, 0 +ATT, 2.34, 1.65, -6.53, -1.62, 0.00, 52.68, 51.14 +CTUN, 804, 0.31, 2.75, 0.000000, 0, 0, 9, 804, 0 +ATT, 2.34, 2.32, -6.53, -1.75, 0.00, 52.86, 51.14 +CTUN, 804, 0.31, 2.82, 0.000000, 0, 1, 7, 805, 0 +ATT, 2.53, 3.18, -6.25, -1.70, 0.00, 53.01, 51.14 +CTUN, 805, 0.31, 2.78, 0.000000, 0, 1, 4, 805, 0 +ATT, 2.53, 3.88, -6.34, -1.11, 0.00, 53.23, 51.14 +CTUN, 804, 0.32, 2.83, 0.000000, 0, 1, 4, 806, 0 +ATT, 2.53, 3.64, -6.16, -0.62, 0.00, 53.61, 51.14 +DU32, 7, 166140 +CURR, 804, 1845373, 984, 2208, 5051, 1389.891400 +CTUN, 805, 0.32, 2.85, 0.000000, 0, 1, 4, 806, 0 +ATT, 1.12, 2.39, -6.06, -1.16, 0.00, 54.20, 51.14 +CTUN, 804, 0.33, 2.82, 0.000000, 0, 0, 2, 805, 0 +ATT, 0.09, 1.31, -5.13, -1.65, 0.00, 54.92, 51.14 +CTUN, 805, 0.33, 2.79, 0.000000, 0, 0, 1, 806, 0 +ATT, 0.00, 0.67, -4.66, -1.90, 0.00, 55.60, 51.14 +CTUN, 805, 0.33, 2.89, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, 0.16, -4.66, -1.66, 0.00, 56.13, 51.14 +CTUN, 806, 0.33, 2.90, 0.000000, 0, 0, 1, 806, 0 +ATT, 0.00, -0.29, -4.29, -0.84, 0.00, 56.54, 51.14 +CTUN, 806, 0.33, 2.96, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, -0.32, -3.92, 0.31, 0.00, 56.91, 51.14 +CTUN, 805, 0.32, 2.89, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, -0.18, -3.92, 0.51, 0.00, 57.03, 51.14 +CTUN, 807, 0.32, 2.84, 0.000000, 0, 0, 0, 807, 0 +ATT, 0.00, -0.11, -4.20, 0.21, 0.00, 56.81, 51.14 +CTUN, 806, 0.32, 2.81, 0.000000, 0, 0, 0, 806, 0 +ATT, 0.00, -0.32, -4.48, -0.14, 0.00, 56.51, 51.14 +CTUN, 805, 0.32, 2.80, 0.000000, 0, 0, -1, 805, 0 +ATT, 0.00, -1.39, -4.38, -0.47, 0.00, 56.23, 51.14 +DU32, 7, 166140 +CURR, 805, 1853428, 979, 2197, 5051, 1396.002900 +CTUN, 806, 0.30, 2.79, 0.000000, 0, 0, -2, 806, 0 +ATT, 0.00, -1.44, -4.29, -0.73, 0.00, 56.02, 51.14 +CTUN, 804, 0.30, 2.86, 0.000000, 0, 0, -1, 805, 0 +ATT, 0.00, -0.94, -3.82, -0.57, 0.00, 55.86, 51.14 +CTUN, 808, 0.29, 2.82, 0.000000, 0, 0, 0, 808, 0 +ATT, 0.00, -0.94, -3.73, -0.36, 0.00, 55.58, 51.14 +CTUN, 804, 0.29, 2.78, 0.000000, 0, 0, 0, 804, 0 +ATT, 0.00, -0.65, -3.82, 0.21, 0.00, 55.09, 51.14 +CTUN, 804, 0.28, 2.71, 0.000000, 0, 0, 1, 805, 0 +ATT, 0.00, -0.31, -3.73, 0.48, 0.00, 54.28, 51.14 +CTUN, 805, 0.28, 2.72, 0.000000, 0, 0, 1, 805, 0 +ATT, 0.00, 0.68, -3.82, 0.31, 0.00, 53.24, 51.14 +CTUN, 804, 0.28, 2.80, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, 1.32, -4.38, -0.02, 0.00, 52.42, 51.14 +PM, 0, 0, 0, 0, 1000, 10468, 0, 0 +CTUN, 805, 0.28, 2.88, 0.000000, 0, 0, 6, 805, 0 +ATT, 0.00, 1.13, -4.20, -0.51, 0.00, 51.98, 51.14 +CTUN, 804, 0.27, 2.80, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, 1.22, -3.92, -0.95, 0.00, 51.98, 51.14 +CTUN, 804, 0.27, 2.80, 0.000000, 0, 0, 3, 804, 0 +ATT, 0.00, 0.84, -4.01, -1.37, 0.00, 52.23, 51.14 +DU32, 7, 166140 +CURR, 805, 1861474, 982, 2167, 5028, 1402.072800 +CTUN, 804, 0.27, 2.76, 0.000000, 0, 0, 2, 804, 0 +ATT, 0.00, 0.15, -4.20, -1.63, 0.00, 52.63, 51.14 +CTUN, 805, 0.27, 2.82, 0.000000, 0, 0, 5, 805, 0 +ATT, 0.00, -0.58, -3.73, -1.04, 0.00, 52.94, 51.14 +CTUN, 804, 0.27, 2.74, 0.000000, 0, 0, 7, 804, 0 +ATT, 0.00, -0.69, -2.80, -0.91, 0.00, 53.40, 51.14 +CTUN, 804, 0.27, 2.80, 0.000000, 0, 0, 8, 804, 0 +ATT, 0.00, -0.17, -2.70, -1.18, 0.00, 53.87, 51.14 +CTUN, 805, 0.27, 2.91, 0.000000, 0, 0, 10, 804, 0 +ATT, 0.00, -0.48, -2.70, -1.52, 0.00, 54.52, 51.14 +CTUN, 804, 0.27, 2.78, 0.000000, 0, 0, 12, 804, 0 +ATT, 0.00, -0.61, -2.61, -1.02, 0.00, 55.28, 51.14 +CTUN, 805, 0.27, 2.81, 0.000000, 0, 0, 14, 805, 0 +ATT, 0.00, 0.53, -2.70, 0.36, 0.00, 55.96, 51.14 +CTUN, 805, 0.27, 2.79, 0.000000, 0, 0, 12, 804, 0 +ATT, 0.00, 0.30, -2.42, 1.32, 0.00, 56.37, 51.14 +CTUN, 804, 0.27, 2.76, 0.000000, 0, 0, 12, 804, 0 +ATT, 0.00, -0.18, -2.70, 0.62, 0.00, 56.82, 51.14 +CTUN, 804, 0.29, 2.77, 0.000000, 0, 0, 11, 804, 0 +ATT, 0.00, 0.00, -2.61, -0.35, 0.00, 57.27, 51.14 +DU32, 7, 166140 +CURR, 805, 1869520, 985, 2210, 5051, 1408.149700 +CTUN, 804, 0.29, 2.94, 0.000000, 0, 0, 14, 804, 0 +ATT, 0.00, 0.51, -2.61, -0.96, 0.00, 57.79, 51.14 +CTUN, 804, 0.29, 2.93, 0.000000, 0, 0, 13, 804, 0 +ATT, 0.00, 0.81, -2.61, -1.20, 0.00, 58.36, 51.14 +CTUN, 804, 0.29, 3.03, 0.000000, 0, 0, 13, 804, 0 +ATT, 0.00, 1.48, -2.52, -0.45, 0.00, 58.84, 51.14 +CTUN, 805, 0.29, 2.80, 0.000000, 0, 0, 15, 805, 0 +ATT, 0.00, 1.97, -2.52, 0.08, 0.00, 59.28, 51.14 +CTUN, 805, 0.29, 2.78, 0.000000, 0, 0, 11, 805, 0 +ATT, 0.00, 1.88, -2.42, 0.19, 0.00, 59.73, 51.14 +CTUN, 805, 0.30, 2.95, 0.000000, 0, 0, 12, 805, 0 +ATT, 0.00, 1.64, -2.52, 0.27, 0.00, 59.81, 51.14 +CTUN, 805, 0.30, 2.90, 0.000000, 0, 0, 8, 804, 0 +ATT, -0.37, 1.21, -2.70, 0.41, 0.00, 59.74, 51.14 +CTUN, 805, 0.30, 2.94, 0.000000, 0, 0, 10, 805, 0 +ATT, -1.61, 0.58, -1.58, 0.29, 0.00, 59.52, 51.14 +CTUN, 805, 0.30, 2.84, 0.000000, 0, 0, 13, 805, 0 +ATT, -2.74, 0.07, -2.70, 0.60, 0.00, 59.18, 51.14 +CTUN, 805, 0.30, 2.95, 0.000000, 0, 0, 9, 805, 0 +ATT, -2.74, 0.60, -2.70, 0.75, 0.00, 58.97, 51.14 +DU32, 7, 166140 +CURR, 804, 1877560, 978, 2153, 5051, 1414.243900 +CTUN, 804, 0.30, 2.79, 0.000000, 0, 0, 8, 804, 0 +ATT, -2.74, 0.41, -2.70, 0.39, 0.00, 58.74, 51.14 +CTUN, 804, 0.30, 2.97, 0.000000, 0, 0, 6, 805, 0 +ATT, -2.74, -0.69, -2.70, -0.22, 0.00, 58.62, 51.14 +CTUN, 805, 0.30, 2.98, 0.000000, 0, 0, 9, 805, 0 +ATT, -2.74, -0.96, -2.70, -1.08, 0.00, 58.57, 51.14 +CTUN, 804, 0.31, 2.90, 0.000000, 0, 0, 11, 804, 0 +ATT, -2.74, 0.28, -2.70, -1.27, 0.00, 58.68, 51.14 +CTUN, 804, 0.30, 2.84, 0.000000, 0, 0, 8, 804, 0 +ATT, -6.25, 0.85, -2.70, -0.48, 0.00, 59.05, 51.14 +CTUN, 805, 0.30, 2.74, 0.000000, 0, 0, 4, 804, 0 +ATT, -6.72, -1.65, -2.52, -0.14, 0.00, 59.23, 51.14 +CTUN, 804, 0.29, 2.78, 0.000000, 0, 0, 5, 804, 0 +ATT, -6.72, -3.59, -2.24, -0.60, 0.00, 59.10, 51.14 +CTUN, 805, 0.29, 2.91, 0.000000, 0, 1, 5, 806, 0 +ATT, -7.48, -3.53, -2.42, -0.38, 0.00, 58.71, 51.14 +CTUN, 805, 0.29, 2.80, 0.000000, 0, 1, 3, 806, 0 +ATT, -7.48, -4.54, -2.52, 0.14, 0.00, 58.13, 51.14 +CTUN, 804, 0.29, 2.64, 0.000000, 0, 3, 6, 807, 0 +ATT, -7.29, -6.49, -2.24, -0.23, 0.00, 57.10, 51.14 +DU32, 7, 166140 +CURR, 806, 1885606, 987, 2266, 5051, 1420.325200 +CTUN, 805, 0.28, 2.80, 0.000000, 0, 4, 3, 809, 0 +ATT, -6.63, -6.46, -2.24, -1.30, 0.00, 55.86, 51.14 +CTUN, 805, 0.28, 2.58, 0.000000, 0, 3, 2, 808, 0 +ATT, -4.16, -4.77, -2.24, -1.02, 0.00, 54.52, 51.14 +CTUN, 805, 0.26, 2.85, 0.000000, 0, 1, 3, 806, 0 +ATT, -2.55, -3.00, -2.42, -0.31, 0.00, 53.44, 51.14 +CTUN, 805, 0.26, 2.74, 0.000000, 0, 0, 3, 805, 0 +ATT, -1.13, -1.71, -1.12, 0.00, 0.00, 52.58, 51.14 +CTUN, 805, 0.25, 2.89, 0.000000, 0, 0, 0, 804, 0 +ATT, 0.00, 1.60, -2.52, -0.55, 0.00, 51.78, 51.14 +CTUN, 805, 0.25, 2.67, 0.000000, 0, 1, 0, 806, 0 +ATT, 0.00, 3.57, -2.52, -0.64, 0.00, 50.95, 51.14 +CTUN, 804, 0.24, 2.78, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, 0.90, -1.96, -0.34, 0.00, 50.84, 51.14 +CTUN, 805, 0.24, 2.92, 0.000000, 0, 0, 9, 805, 0 +ATT, 0.00, -0.76, 0.00, -0.43, 0.00, 51.49, 51.14 +CTUN, 805, 0.24, 2.81, 0.000000, 0, 0, 12, 805, 0 +ATT, 0.00, -0.94, 0.00, -0.40, 0.00, 52.46, 51.14 +CTUN, 805, 0.24, 2.81, 0.000000, 0, 0, 18, 805, 0 +ATT, 0.00, -0.12, 0.00, 1.70, 0.00, 52.90, 51.14 +DU32, 7, 166140 +CURR, 804, 1893664, 977, 2216, 5051, 1426.432100 +CTUN, 805, 0.24, 2.77, 0.000000, 0, 0, 17, 805, 0 +ATT, -0.66, 0.02, 0.00, 4.20, 0.00, 53.07, 51.14 +CTUN, 805, 0.26, 2.74, 0.000000, 0, 2, 12, 807, 0 +ATT, -0.66, -0.11, 0.00, 4.32, 0.00, 53.49, 51.14 +CTUN, 805, 0.26, 2.81, 0.000000, 0, 1, 10, 806, 0 +ATT, 0.00, -0.27, 0.00, 2.74, 0.00, 53.29, 51.14 +CTUN, 806, 0.27, 2.76, 0.000000, 0, 0, 10, 804, 0 +ATT, 0.00, -0.31, -1.21, 2.12, 0.00, 52.61, 51.14 +CTUN, 805, 0.27, 2.99, 0.000000, 0, 0, 9, 805, 0 +ATT, 0.00, -0.41, -2.24, 2.02, 0.00, 51.87, 51.14 +CTUN, 805, 0.29, 2.93, 0.000000, 0, 0, 6, 805, 0 +ATT, 0.00, -0.61, -2.70, 1.10, 0.00, 51.11, 51.14 +CTUN, 805, 0.29, 2.89, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, -0.37, -3.08, -0.68, 0.00, 50.56, 51.14 +CTUN, 805, 0.30, 2.90, 0.000000, 0, 0, 6, 805, 0 +ATT, 0.00, -1.11, -4.20, -1.55, 0.00, 50.19, 51.14 +CTUN, 805, 0.30, 3.02, 0.000000, 0, 0, 6, 805, 0 +ATT, 0.00, -2.21, -4.85, -1.77, 0.00, 49.99, 51.14 +CTUN, 805, 0.30, 2.93, 0.000000, 0, 0, 4, 805, 0 +ATT, 0.00, -1.51, -4.57, -2.80, 0.00, 49.95, 51.14 +DU32, 7, 166140 +CURR, 805, 1901718, 992, 2163, 5051, 1432.476100 +CTUN, 805, 0.30, 2.80, 0.000000, 0, 1, 7, 806, 0 +ATT, 0.00, -0.53, -4.38, -3.45, 0.00, 50.09, 51.14 +CTUN, 805, 0.31, 2.72, 0.000000, 0, 1, 5, 806, 0 +ATT, 0.18, -0.60, -4.10, -3.41, 0.00, 50.58, 51.14 +CTUN, 807, 0.31, 2.78, 0.000000, 0, 1, 3, 808, 0 +ATT, 0.46, -1.00, -3.92, -2.73, 0.00, 51.41, 51.14 +CTUN, 805, 0.31, 3.01, 0.000000, 0, 0, 5, 807, 0 +ATT, 0.84, -1.93, -3.08, -1.96, 0.00, 52.34, 51.14 +CTUN, 807, 0.31, 3.05, 0.000000, 0, 0, 2, 807, 0 +ATT, 1.21, -1.95, -2.42, -1.32, 0.00, 53.20, 51.14 +CTUN, 805, 0.32, 2.98, 0.000000, 0, 0, 2, 804, 0 +ATT, 1.78, -1.15, -2.52, -0.32, 0.00, 53.87, 51.14 +CTUN, 805, 0.32, 2.90, 0.000000, 0, 0, -1, 805, 0 +ATT, 2.90, -0.57, -2.52, 0.83, 0.00, 54.31, 51.14 +CTUN, 804, 0.32, 3.00, 0.000000, 0, 0, -3, 804, 0 +ATT, 6.09, 0.00, -2.52, 1.33, 0.00, 54.38, 51.14 +CTUN, 804, 0.31, 2.87, 0.000000, 0, 0, -2, 804, 0 +ATT, 6.75, 0.88, -2.52, 1.98, 0.00, 54.21, 51.14 +CTUN, 804, 0.31, 2.91, 0.000000, 0, 0, -1, 804, 0 +ATT, 9.18, 2.55, -2.24, 3.28, 0.00, 53.90, 51.14 +DU32, 7, 166140 +CURR, 804, 1909768, 987, 2168, 5051, 1438.520500 +CTUN, 805, 0.29, 2.93, 0.000000, 0, 2, -3, 807, 0 +ATT, 9.56, 6.04, -3.08, 3.26, 0.00, 52.90, 51.14 +CTUN, 804, 0.29, 2.81, 0.000000, 0, 6, -4, 810, 0 +ATT, 9.56, 8.53, -3.08, 2.12, 0.00, 51.48, 51.14 +CTUN, 804, 0.26, 2.83, 0.000000, 0, 7, -10, 811, 0 +ATT, 8.06, 7.66, -4.57, 1.42, 0.00, 50.00, 51.14 +CTUN, 805, 0.26, 2.74, 0.000000, 0, 5, -9, 809, 0 +ATT, 2.62, 6.57, -6.62, 0.79, 0.00, 48.84, 51.14 +CTUN, 805, 0.23, 2.75, 0.000000, 0, 3, -4, 808, 0 +ATT, 0.00, 4.32, -7.56, 0.28, 0.00, 48.23, 51.14 +CTUN, 804, 0.23, 2.57, 0.000000, 0, 0, -7, 804, 0 +ATT, 0.00, -0.82, -6.81, -0.63, 0.00, 48.22, 51.14 +CTUN, 804, 0.22, 2.61, 0.000000, 0, 0, -6, 805, 0 +ATT, 0.46, -3.48, -6.81, -1.50, 0.00, 48.11, 51.14 +CTUN, 804, 0.22, 2.74, 0.000000, 0, 1, -7, 806, 0 +ATT, 2.34, -3.29, -6.72, -1.92, 0.00, 47.63, 51.14 +CTUN, 804, 0.21, 2.69, 0.000000, 0, 0, -3, 804, 0 +ATT, 7.31, -0.20, -6.81, -2.62, 0.00, 47.02, 51.14 +CTUN, 804, 0.21, 2.65, 0.000000, 0, 1, 1, 805, 0 +ATT, 9.28, 3.66, -6.81, -2.99, 0.00, 46.63, 51.14 +DU32, 7, 166140 +CURR, 804, 1917840, 980, 2148, 5051, 1444.571500 +CTUN, 804, 0.20, 2.70, 0.000000, 0, 3, 8, 807, 0 +ATT, 9.09, 7.06, -7.28, -2.74, 0.00, 46.57, 51.14 +CTUN, 804, 0.20, 2.60, 0.000000, 0, 7, 8, 812, 0 +ATT, 8.81, 8.42, -7.93, -2.63, 0.00, 46.86, 51.14 +CTUN, 804, 0.20, 2.69, 0.000000, 0, 8, 7, 812, 0 +ATT, 7.40, 8.12, -8.21, -3.19, 0.00, 47.40, 51.14 +CTUN, 805, 0.20, 2.74, 0.000000, 0, 7, 9, 812, 0 +ATT, 2.25, 6.75, -10.64, -3.46, 0.00, 48.28, 51.14 +CTUN, 804, 0.20, 2.79, 0.000000, 0, 4, 10, 808, 0 +ATT, 0.28, 4.17, -10.82, -3.92, 0.00, 49.58, 51.14 +CTUN, 804, 0.20, 2.64, 0.000000, 0, 2, 5, 806, 0 +ATT, 0.28, 1.37, -10.92, -5.46, 0.00, 51.12, 51.14 +CTUN, 804, 0.20, 2.59, 0.000000, 0, 3, 9, 808, 0 +ATT, 0.09, -0.21, -10.73, -6.37, 0.00, 52.69, 51.14 +CTUN, 804, 0.23, 2.86, 0.000000, 0, 4, 9, 808, 0 +ATT, 0.09, -0.88, -10.64, -6.45, 0.00, 54.31, 51.14 +CTUN, 804, 0.23, 2.90, 0.000000, 0, 4, 9, 812, 0 +ATT, 0.28, -1.33, -9.33, -6.22, 0.00, 55.75, 51.14 +CTUN, 804, 0.26, 2.98, 0.000000, 0, 3, 10, 807, 0 +ATT, 0.00, -1.44, -7.56, -5.68, 0.00, 56.71, 51.14 +DU32, 7, 166140 +CURR, 804, 1925936, 984, 2241, 5051, 1450.672700 +CTUN, 804, 0.26, 3.05, 0.000000, 0, 2, 13, 806, 0 +ATT, 0.09, -0.65, -6.25, -4.30, 0.00, 56.98, 51.14 +CTUN, 804, 0.29, 2.96, 0.000000, 0, 1, 16, 806, 0 +ATT, 0.00, -0.07, -4.85, -2.32, 0.00, 56.50, 51.14 +CTUN, 805, 0.29, 2.98, 0.000000, 0, 0, 19, 805, 0 +ATT, 0.00, 0.38, -4.66, -0.10, 0.00, 55.47, 51.14 +CTUN, 805, 0.32, 3.00, 0.000000, 0, 0, 18, 803, 0 +ATT, 0.00, 0.61, -4.76, 1.37, 0.00, 54.23, 51.14 +CTUN, 804, 0.32, 3.03, 0.000000, 0, 0, 18, 804, 0 +ATT, 0.00, 0.37, -4.76, 1.74, 0.00, 53.01, 51.14 +CTUN, 804, 0.36, 2.94, 0.000000, 0, 0, 20, 804, 0 +ATT, 0.00, -0.06, -5.50, 1.78, 0.00, 52.02, 51.14 +CTUN, 805, 0.36, 3.24, 0.000000, 0, 0, 20, 805, 0 +ATT, 0.00, -0.21, -5.69, 1.53, 0.00, 51.10, 51.14 +CTUN, 805, 0.39, 3.17, 0.000000, 0, 0, 17, 804, 0 +ATT, 0.00, -0.37, -6.06, 0.64, 0.00, 50.06, 51.14 +CTUN, 804, 0.39, 3.18, 0.000000, 0, 0, 14, 804, 0 +ATT, 0.00, -0.18, -6.62, -0.27, 0.00, 48.73, 51.14 +CTUN, 805, 0.41, 2.94, 0.000000, 0, 0, 8, 805, 0 +ATT, 0.00, 0.82, -7.84, -1.20, 0.00, 47.19, 51.14 +DU32, 7, 166140 +CURR, 805, 1933986, 986, 2168, 5028, 1456.755400 +CTUN, 804, 0.41, 2.96, 0.000000, 0, 0, 10, 804, 0 +ATT, 0.00, 1.30, -7.84, -1.71, 0.00, 45.82, 51.14 +CTUN, 805, 0.45, 3.20, 0.000000, 0, 0, 5, 805, 0 +ATT, 0.00, 1.19, -7.84, -1.78, 0.00, 44.58, 51.14 +CTUN, 804, 0.45, 3.18, 0.000000, 0, 0, 3, 805, 0 +ATT, 0.00, 1.05, -7.84, -1.66, 0.00, 43.56, 51.14 +CTUN, 798, 0.46, 3.06, 0.000000, 0, 0, 1, 798, 0 +ATT, 0.00, 0.54, -7.84, -1.70, 0.00, 42.89, 51.14 +CTUN, 799, 0.46, 3.21, 0.000000, 0, 0, -5, 799, 0 +ATT, 0.00, 0.07, -8.40, -2.20, 0.00, 42.62, 51.14 +CTUN, 800, 0.47, 3.17, 0.000000, 0, 0, -11, 800, 0 +ATT, 0.00, 0.02, -10.73, -3.20, 0.00, 42.63, 51.14 +CTUN, 802, 0.46, 3.04, 0.000000, 0, 1, -14, 803, 0 +ATT, 0.00, 0.61, -10.92, -4.42, 0.00, 42.76, 51.14 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 801, 0.46, 3.14, 0.000000, 0, 2, -20, 803, 0 +ATT, 0.00, 1.09, -10.64, -5.09, 0.00, 43.07, 51.14 +CTUN, 800, 0.44, 3.10, 0.000000, 0, 2, -21, 802, 0 +ATT, 0.00, 1.11, -8.02, -5.24, 0.00, 43.57, 51.14 +CTUN, 800, 0.44, 3.03, 0.000000, 0, 2, -23, 802, 0 +ATT, 0.00, 0.73, -5.69, -4.46, 0.00, 43.93, 51.14 +DU32, 7, 166140 +CURR, 800, 1942011, 980, 2131, 5051, 1462.690400 +CTUN, 802, 0.41, 3.10, 0.000000, 0, 1, -27, 803, 0 +ATT, 0.00, 0.39, -3.08, -2.13, 0.00, 44.16, 51.14 +CTUN, 802, 0.41, 3.09, 0.000000, 0, 0, -28, 802, 0 +ATT, 0.00, 0.71, -2.52, 0.88, 0.00, 44.50, 51.14 +CTUN, 802, 0.36, 3.04, 0.000000, 0, 0, -33, 802, 0 +ATT, 0.00, 0.94, -2.52, 2.95, 0.00, 44.98, 51.14 +CTUN, 805, 0.36, 2.94, 0.000000, 0, 1, -33, 806, 0 +ATT, 0.00, 1.19, -2.42, 3.85, 0.00, 45.49, 51.14 +CTUN, 805, 0.30, 2.89, 0.000000, 0, 1, -32, 806, 0 +ATT, 0.00, 1.03, -2.42, 3.71, 0.00, 46.10, 51.14 +CTUN, 804, 0.30, 2.85, 0.000000, 0, 1, -28, 805, 0 +ATT, -0.94, -0.52, -2.70, 3.29, 0.00, 46.90, 51.14 +CTUN, 805, 0.24, 2.90, 0.000000, 0, 1, -24, 806, 0 +ATT, -2.46, -1.97, -2.42, 2.96, 0.00, 47.84, 51.14 +CTUN, 804, 0.24, 2.92, 0.000000, 0, 1, -19, 805, 0 +ATT, -3.31, -2.39, -3.26, 2.53, 0.00, 48.73, 51.14 +CTUN, 804, 0.20, 2.87, 0.000000, 0, 1, -12, 804, 0 +ATT, -3.60, -2.16, -3.73, 2.00, 0.00, 49.48, 51.14 +CTUN, 804, 0.20, 2.47, 0.000000, 0, 0, -6, 804, 0 +ATT, -3.69, -2.87, -3.64, 1.74, 0.00, 50.15, 51.14 +DU32, 7, 166140 +CURR, 804, 1950052, 982, 2162, 5028, 1468.692400 +CTUN, 804, 0.20, 2.66, 0.000000, 0, 1, 0, 805, 0 +ATT, -1.89, -4.60, -4.57, 1.61, 0.00, 50.78, 51.14 +CTUN, 805, 0.20, 2.52, 0.000000, 0, 2, 6, 807, 0 +ATT, 0.00, -4.31, -4.85, 0.94, 0.00, 51.36, 51.14 +CTUN, 804, 0.20, 2.79, 0.000000, 0, 1, 9, 805, 0 +ATT, 0.00, -1.78, -5.78, 0.06, 0.00, 51.55, 51.14 +CTUN, 805, 0.20, 2.81, 0.000000, 0, 0, 15, 805, 0 +ATT, 0.00, 0.70, -7.93, -0.62, 0.00, 51.37, 51.14 +CTUN, 804, 0.20, 2.80, 0.000000, 0, 0, 17, 805, 0 +ATT, 0.00, 2.23, -10.08, -2.05, 0.00, 51.09, 51.14 +CTUN, 805, 0.20, 2.87, 0.000000, 0, 1, 18, 806, 0 +ATT, 0.00, 2.55, -10.17, -3.81, 0.00, 50.96, 51.14 +CTUN, 804, 0.20, 2.86, 0.000000, 0, 3, 16, 807, 0 +ATT, 0.00, 2.54, -9.14, -5.49, 0.00, 51.03, 51.14 +CTUN, 804, 0.22, 2.81, 0.000000, 0, 3, 16, 807, 0 +ATT, 0.00, 1.01, -8.96, -5.74, 0.00, 51.21, 51.14 +CTUN, 804, 0.22, 2.98, 0.000000, 0, 3, 12, 807, 0 +ATT, 0.00, 0.08, -9.14, -4.92, 0.00, 51.12, 51.14 +CTUN, 804, 0.27, 2.93, 0.000000, 0, 2, 8, 807, 0 +ATT, 0.00, 1.15, -9.14, -3.86, 0.00, 50.83, 51.14 +DU32, 7, 166140 +CURR, 804, 1958112, 979, 2159, 5028, 1474.724100 +CTUN, 805, 0.27, 3.00, 0.000000, 0, 1, 3, 806, 0 +ATT, 0.00, 1.61, -8.86, -2.82, 0.00, 50.52, 51.14 +CTUN, 804, 0.30, 2.97, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, 1.89, -8.86, -2.56, 0.00, 50.18, 51.14 +CTUN, 804, 0.30, 3.05, 0.000000, 0, 1, -4, 805, 0 +ATT, 0.00, 1.91, -9.14, -2.90, 0.00, 50.00, 51.14 +CTUN, 804, 0.32, 3.04, 0.000000, 0, 1, -9, 805, 0 +ATT, 0.00, 0.82, -9.42, -3.39, 0.00, 50.17, 51.14 +CTUN, 804, 0.32, 3.01, 0.000000, 0, 1, -11, 805, 0 +ATT, 0.00, 0.23, -9.89, -4.13, 0.00, 50.55, 51.14 +CTUN, 805, 0.32, 3.05, 0.000000, 0, 2, -14, 806, 0 +ATT, 0.00, 0.04, -10.17, -4.91, 0.00, 50.96, 51.14 +CTUN, 804, 0.32, 3.08, 0.000000, 0, 2, -10, 806, 0 +ATT, 0.00, 0.35, -9.52, -5.21, 0.00, 51.44, 51.14 +CTUN, 805, 0.32, 3.06, 0.000000, 0, 2, -14, 807, 0 +ATT, 0.00, 1.12, -8.12, -4.25, 0.00, 51.86, 51.14 +CTUN, 804, 0.32, 2.99, 0.000000, 0, 1, -13, 805, 0 +ATT, 0.00, 0.91, -4.85, -2.45, 0.00, 52.17, 51.14 +CTUN, 805, 0.32, 3.07, 0.000000, 0, 0, -12, 805, 0 +ATT, 0.00, 0.81, -3.73, -0.42, 0.00, 52.39, 51.14 +DU32, 7, 166140 +CURR, 805, 1966164, 978, 2149, 5028, 1480.727500 +CTUN, 805, 0.31, 3.14, 0.000000, 0, 0, -12, 805, 0 +ATT, 0.00, 1.51, -3.92, 1.50, 0.00, 52.50, 51.14 +CTUN, 805, 0.31, 3.17, 0.000000, 0, 0, -12, 804, 0 +ATT, 0.00, 2.09, -4.76, 2.62, 0.00, 52.35, 51.14 +CTUN, 804, 0.29, 3.06, 0.000000, 0, 1, -14, 805, 0 +ATT, 0.00, 1.59, -4.85, 2.36, 0.00, 51.98, 51.14 +CTUN, 805, 0.29, 2.97, 0.000000, 0, 0, -14, 805, 0 +ATT, 0.00, 1.63, -4.85, 1.46, 0.00, 51.78, 51.14 +CTUN, 804, 0.28, 3.11, 0.000000, 0, 0, -14, 804, 0 +ATT, 0.00, 2.05, -4.85, 0.78, 0.00, 51.66, 51.14 +CTUN, 805, 0.28, 3.01, 0.000000, 0, 0, -12, 805, 0 +ATT, -0.18, 1.54, -4.57, 0.68, 0.00, 51.51, 51.14 +CTUN, 804, 0.27, 2.90, 0.000000, 0, 0, -12, 804, 0 +ATT, -0.75, -0.17, -4.57, 0.07, 0.00, 51.26, 51.14 +CTUN, 804, 0.27, 2.91, 0.000000, 0, 0, -9, 804, 0 +ATT, -0.94, -0.66, -4.48, -0.34, 0.00, 51.01, 51.14 +CTUN, 804, 0.25, 2.84, 0.000000, 0, 0, -6, 805, 0 +ATT, -1.32, -0.91, -4.57, -0.15, 0.00, 50.91, 51.14 +CTUN, 805, 0.25, 2.88, 0.000000, 0, 0, -5, 804, 0 +ATT, -1.61, -1.97, -4.48, -0.44, 0.00, 50.97, 51.14 +DU32, 7, 166140 +CURR, 804, 1974209, 978, 2173, 5051, 1486.730200 +CTUN, 805, 0.25, 3.05, 0.000000, 0, 0, -3, 805, 0 +ATT, -1.61, -1.61, -4.57, -0.78, 0.00, 50.94, 51.14 +CTUN, 805, 0.25, 2.86, 0.000000, 0, 0, 1, 805, 0 +ATT, -1.61, -1.16, -4.57, -1.00, 0.00, 50.87, 51.14 +CTUN, 804, 0.25, 2.94, 0.000000, 0, 0, 5, 804, 0 +ATT, -1.61, -1.51, -4.57, -1.27, 0.00, 50.58, 51.14 +CTUN, 805, 0.26, 3.00, 0.000000, 0, 0, 7, 804, 0 +ATT, -1.61, -0.87, -4.57, -1.65, 0.00, 50.00, 51.14 +CTUN, 804, 0.26, 2.99, 0.000000, 0, 0, 10, 804, 0 +ATT, -1.61, -0.09, -4.48, -1.81, 0.00, 49.43, 51.14 +CTUN, 804, 0.27, 2.93, 0.000000, 0, 0, 9, 804, 0 +ATT, -1.42, 0.62, -4.57, -1.88, 0.00, 49.06, 51.14 +CTUN, 804, 0.27, 3.06, 0.000000, 0, 0, 8, 805, 0 +ATT, -1.13, 0.24, -4.48, -1.54, 0.00, 49.04, 51.14 +CTUN, 804, 0.27, 2.97, 0.000000, 0, 0, 4, 804, 0 +ATT, -1.32, -1.18, -4.20, -1.47, 0.00, 49.24, 51.14 +CTUN, 805, 0.27, 2.81, 0.000000, 0, 0, 1, 804, 0 +ATT, -1.32, -1.84, -3.92, -1.79, 0.00, 49.62, 51.14 +CTUN, 805, 0.29, 3.06, 0.000000, 0, 0, 2, 805, 0 +ATT, -1.13, -1.33, -3.08, -1.61, 0.00, 50.12, 51.14 +DU32, 7, 166140 +CURR, 805, 1982253, 984, 2151, 5051, 1492.757800 +CTUN, 804, 0.29, 3.08, 0.000000, 0, 0, 3, 804, 0 +ATT, -1.32, -0.87, -3.08, -0.83, 0.00, 50.69, 51.14 +CTUN, 805, 0.30, 2.88, 0.000000, 0, 0, 1, 805, 0 +ATT, -0.94, -1.10, -3.26, 0.02, 0.00, 51.17, 51.14 +CTUN, 805, 0.30, 3.03, 0.000000, 0, 0, -1, 804, 0 +ATT, -0.85, -2.14, -2.98, 0.04, 0.00, 51.53, 51.14 +CTUN, 804, 0.31, 3.06, 0.000000, 0, 0, 0, 804, 0 +ATT, -0.75, -2.34, -3.08, -0.06, 0.00, 51.82, 51.14 +CTUN, 805, 0.31, 3.05, 0.000000, 0, 0, -1, 805, 0 +ATT, -0.37, -1.65, -3.26, 0.03, 0.00, 52.10, 51.14 +CTUN, 804, 0.31, 3.02, 0.000000, 0, 0, -1, 805, 0 +ATT, 0.00, -0.60, -3.17, 0.83, 0.00, 52.45, 51.14 +CTUN, 805, 0.31, 3.05, 0.000000, 0, 0, -4, 805, 0 +ATT, 0.00, 0.51, -3.26, 1.40, 0.00, 52.85, 51.14 +CTUN, 805, 0.31, 3.11, 0.000000, 0, 0, -3, 804, 0 +ATT, 0.00, 1.10, -3.08, 1.06, 0.00, 53.44, 51.14 +CTUN, 804, 0.29, 3.05, 0.000000, 0, 0, -3, 804, 0 +ATT, 0.00, 0.53, -3.17, 0.09, 0.00, 54.08, 51.14 +CTUN, 805, 0.29, 3.18, 0.000000, 0, 0, -4, 805, 0 +ATT, 0.00, -0.19, -2.61, -1.29, 0.00, 54.88, 51.14 +DU32, 7, 166140 +CURR, 804, 1990299, 983, 2174, 5051, 1498.779300 +CTUN, 805, 0.27, 3.05, 0.000000, 0, 0, 0, 805, 0 +ATT, 0.00, -0.72, -2.42, -1.62, 0.00, 55.62, 51.14 +CTUN, 805, 0.27, 2.96, 0.000000, 0, 0, 2, 804, 0 +ATT, 0.00, -0.22, -2.42, -1.67, 0.00, 56.34, 51.14 +CTUN, 804, 0.27, 3.14, 0.000000, 0, 0, 6, 804, 0 +ATT, 0.00, 1.17, -2.70, -1.55, 0.00, 56.98, 51.14 +CTUN, 804, 0.27, 2.92, 0.000000, 0, 0, 5, 804, 0 +ATT, 0.00, 1.15, -2.42, -1.07, 0.00, 57.50, 51.14 +CTUN, 805, 0.27, 3.05, 0.000000, 0, 0, 6, 804, 0 +ATT, 0.00, 0.66, -2.70, -1.00, 0.00, 57.76, 51.14 +CTUN, 804, 0.27, 3.01, 0.000000, 0, 0, 9, 804, 0 +ATT, 0.00, 1.11, -2.52, -1.39, 0.00, 57.63, 51.14 +CTUN, 804, 0.27, 3.06, 0.000000, 0, 0, 11, 804, 0 +ATT, 0.00, 1.85, 0.00, -1.45, 0.00, 57.18, 51.14 +CTUN, 805, 0.27, 2.98, 0.000000, 0, 0, 11, 805, 0 +ATT, 0.00, 1.89, 0.00, -0.32, 0.00, 56.42, 51.14 +CTUN, 804, 0.26, 3.17, 0.000000, 0, 0, 11, 805, 0 +ATT, 0.00, -0.17, 0.00, 1.32, 0.00, 55.51, 51.14 +CTUN, 804, 0.26, 3.04, 0.000000, 0, 0, 9, 804, 0 +ATT, 0.00, -1.65, 0.00, 2.49, 0.00, 54.58, 51.14 +DU32, 7, 166140 +CURR, 804, 1998342, 980, 2130, 5051, 1504.829000 +CTUN, 804, 0.26, 3.17, 0.000000, 0, 1, 8, 805, 0 +ATT, 0.00, -0.36, 0.00, 3.27, 0.00, 53.76, 51.14 +CTUN, 805, 0.26, 3.04, 0.000000, 0, 1, 6, 805, 0 +ATT, 0.00, 0.70, 0.00, 4.39, 0.00, 52.74, 51.14 +CTUN, 804, 0.26, 2.97, 0.000000, 0, 2, 8, 806, 0 +ATT, 0.00, 0.41, 0.00, 5.15, 0.00, 51.80, 51.14 +CTUN, 804, 0.27, 3.01, 0.000000, 0, 2, 6, 806, 0 +ATT, 0.00, 0.67, 0.00, 4.79, 0.00, 51.04, 51.14 +CTUN, 804, 0.27, 3.08, 0.000000, 0, 2, 8, 806, 0 +ATT, 0.00, 0.81, -0.09, 4.18, 0.00, 50.48, 51.14 +CTUN, 806, 0.27, 3.12, 0.000000, 0, 1, 9, 805, 0 +ATT, 0.00, -0.18, -1.02, 2.63, 0.00, 50.52, 51.14 +CTUN, 813, 0.26, 3.03, 0.000000, 0, 0, 10, 813, 0 +ATT, 0.00, -1.21, -1.86, 0.78, 0.00, 51.07, 51.14 +CTUN, 813, 0.26, 3.01, 0.000000, 0, 0, 10, 813, 0 +ATT, 0.00, -1.28, -2.33, -0.72, 0.00, 52.03, 51.14 +CTUN, 814, 0.26, 3.00, 0.000000, 0, 0, 16, 813, 0 +ATT, 0.00, -0.93, -2.33, -1.29, 0.00, 53.20, 51.14 +CTUN, 815, 0.26, 3.05, 0.000000, 0, 0, 16, 815, 0 +ATT, 0.00, -0.85, -2.42, -1.39, 0.00, 54.24, 51.14 +DU32, 7, 166140 +CURR, 814, 2006432, 977, 2228, 5051, 1510.878800 +CTUN, 815, 0.26, 3.10, 0.000000, 0, 0, 18, 815, 0 +ATT, 0.00, -1.14, -2.33, -1.63, 0.00, 55.33, 51.14 +CTUN, 815, 0.28, 3.01, 0.000000, 0, 0, 19, 815, 0 +ATT, 0.00, -1.92, -2.42, -1.91, 0.00, 56.40, 51.14 +CTUN, 815, 0.28, 3.09, 0.000000, 0, 0, 20, 816, 0 +ATT, 0.00, -1.78, -2.52, -1.25, 0.00, 57.14, 51.14 +CTUN, 816, 0.29, 3.10, 0.000000, 0, 0, 22, 816, 0 +ATT, 0.00, -1.58, -2.61, 0.00, 0.00, 57.78, 51.14 +CTUN, 815, 0.29, 3.06, 0.000000, 0, 0, 19, 815, 0 +ATT, 0.28, -2.14, -2.70, 0.53, 0.00, 58.37, 51.14 +CTUN, 816, 0.31, 3.22, 0.000000, 0, 0, 19, 815, 0 +ATT, 0.46, -1.92, -2.61, 0.40, 0.00, 58.78, 51.14 +CTUN, 814, 0.31, 3.14, 0.000000, 0, 0, 18, 814, 0 +ATT, 0.93, -0.87, -3.26, -0.18, 0.00, 59.04, 51.14 +CTUN, 815, 0.33, 3.23, 0.000000, 0, 0, 17, 815, 0 +ATT, 1.21, -0.73, -3.64, -1.34, 0.00, 59.09, 51.14 +CTUN, 815, 0.33, 3.13, 0.000000, 0, 0, 16, 815, 0 +ATT, 1.50, -0.95, -3.92, -1.91, 0.00, 58.97, 51.14 +CTUN, 816, 0.34, 3.01, 0.000000, 0, 0, 13, 815, 0 +ATT, 1.78, -1.01, -4.01, -1.85, 0.00, 58.63, 51.14 +DU32, 7, 166140 +CURR, 814, 2014585, 974, 2251, 5051, 1517.089400 +CTUN, 815, 0.34, 3.07, 0.000000, 0, 0, 12, 815, 0 +ATT, 2.34, -0.63, -3.82, -1.74, 0.00, 58.20, 51.14 +CTUN, 814, 0.35, 3.21, 0.000000, 0, 0, 14, 814, 0 +ATT, 2.53, -0.31, -4.01, -1.52, 0.00, 57.67, 51.14 +CTUN, 816, 0.35, 3.21, 0.000000, 0, 0, 11, 815, 0 +ATT, 3.28, -0.03, -3.92, -1.23, 0.00, 57.05, 51.14 +CTUN, 816, 0.35, 3.02, 0.000000, 0, 0, 8, 816, 0 +ATT, 4.87, 0.98, -3.92, -1.09, 0.00, 56.25, 51.14 +CTUN, 816, 0.35, 3.30, 0.000000, 0, 0, 10, 816, 0 +ATT, 6.56, 2.79, -3.92, -0.38, 0.00, 55.21, 51.14 +CTUN, 815, 0.35, 3.15, 0.000000, 0, 1, 12, 816, 0 +ATT, 6.56, 4.00, -3.92, 0.56, 0.00, 54.19, 51.14 +CTUN, 815, 0.35, 3.03, 0.000000, 0, 2, 14, 817, 0 +ATT, 6.93, 5.91, -3.92, 0.58, 0.00, 53.38, 51.14 +PM, 0, 0, 0, 0, 1001, 10476, 0, 0 +CTUN, 815, 0.35, 3.12, 0.000000, 0, 4, 10, 819, 0 +ATT, 6.84, 7.14, -4.20, 0.11, 0.00, 52.61, 51.14 +CTUN, 816, 0.34, 3.17, 0.000000, 0, 5, 9, 821, 0 +ATT, 6.37, 7.45, -4.57, -0.45, 0.00, 52.08, 51.14 +CTUN, 816, 0.34, 3.24, 0.000000, 0, 5, 8, 820, 0 +ATT, 3.75, 5.79, -6.25, -1.27, 0.00, 51.86, 51.14 +DU32, 7, 166140 +CURR, 816, 2022752, 977, 2250, 5051, 1523.341100 +CTUN, 814, 0.33, 3.15, 0.000000, 0, 2, 4, 817, 0 +ATT, 3.09, 4.10, -6.53, -2.05, 0.00, 51.71, 51.14 +CTUN, 815, 0.33, 3.14, 0.000000, 0, 1, 6, 816, 0 +ATT, 2.34, 2.97, -6.34, -2.41, 0.00, 51.54, 51.14 +CTUN, 815, 0.32, 3.01, 0.000000, 0, 1, 2, 816, 0 +ATT, 1.78, 0.90, -6.53, -2.82, 0.00, 51.38, 51.14 +CTUN, 815, 0.32, 3.06, 0.000000, 0, 0, 2, 815, 0 +ATT, 0.37, -0.72, -6.62, -2.82, 0.00, 51.32, 51.14 +CTUN, 816, 0.31, 3.08, 0.000000, 0, 0, -3, 816, 0 +ATT, 0.28, -0.74, -6.81, -2.93, 0.00, 51.31, 51.14 +CTUN, 816, 0.31, 3.07, 0.000000, 0, 1, -5, 817, 0 +ATT, 0.28, -0.74, -7.65, -3.10, 0.00, 51.32, 51.14 +CTUN, 816, 0.30, 3.15, 0.000000, 0, 1, -4, 817, 0 +ATT, 0.28, -1.45, -7.84, -3.07, 0.00, 51.25, 51.14 +CTUN, 816, 0.30, 3.11, 0.000000, 0, 1, -2, 817, 0 +ATT, 0.28, -2.06, -7.84, -2.67, 0.00, 51.17, 51.14 +CTUN, 818, 0.28, 3.09, 0.000000, 0, 1, -3, 816, 0 +ATT, 0.28, -2.20, -7.65, -2.26, 0.00, 51.15, 51.14 +CTUN, 815, 0.28, 3.03, 0.000000, 0, 1, 0, 816, 0 +ATT, 0.28, -1.88, -6.72, -2.49, 0.00, 51.21, 51.14 +DU32, 7, 166140 +CURR, 815, 2030914, 981, 2211, 5051, 1529.467800 +CTUN, 815, 0.26, 3.15, 0.000000, 0, 1, 0, 817, 0 +ATT, 0.28, -0.82, -6.81, -3.62, 0.00, 51.27, 51.14 +CTUN, 816, 0.26, 3.12, 0.000000, 0, 1, 5, 817, 0 +ATT, 0.18, -0.37, -6.81, -4.40, 0.00, 51.33, 51.14 +CTUN, 815, 0.24, 3.04, 0.000000, 0, 2, 7, 818, 0 +ATT, 0.65, -0.11, -6.81, -4.30, 0.00, 51.43, 51.14 +CTUN, 815, 0.24, 3.00, 0.000000, 0, 1, 11, 816, 0 +ATT, 1.40, 0.84, -6.81, -3.13, 0.00, 51.71, 51.14 +CTUN, 815, 0.23, 3.06, 0.000000, 0, 0, 14, 815, 0 +ATT, 1.40, 1.59, -4.38, -1.83, 0.00, 52.14, 51.14 +CTUN, 815, 0.23, 3.20, 0.000000, 0, 0, 18, 816, 0 +ATT, 0.46, 1.73, -3.26, -1.10, 0.00, 52.60, 51.14 +CTUN, 815, 0.23, 3.06, 0.000000, 0, 0, 18, 815, 0 +ATT, 0.09, 0.53, -2.61, -0.41, 0.00, 53.05, 51.14 +CTUN, 815, 0.24, 3.02, 0.000000, 0, 0, 21, 815, 0 +ATT, 0.09, -0.62, -2.24, 0.63, 0.00, 53.49, 51.14 +CTUN, 815, 0.24, 3.20, 0.000000, 0, 0, 20, 815, 0 +ATT, 0.00, -0.34, -2.05, 1.80, 0.00, 53.95, 51.14 +CTUN, 815, 0.27, 3.16, 0.000000, 0, 0, 19, 815, 0 +ATT, 0.00, -0.08, -2.24, 2.76, 0.00, 54.46, 51.14 +DU32, 7, 166140 +CURR, 816, 2039074, 973, 2224, 5028, 1535.644800 +CTUN, 815, 0.27, 3.19, 0.000000, 0, 0, 19, 815, 0 +ATT, 0.00, -0.23, -2.14, 2.90, 0.00, 54.95, 51.14 +CTUN, 815, 0.30, 3.21, 0.000000, 0, 0, 18, 815, 0 +ATT, 0.00, -0.43, -2.14, 2.39, 0.00, 55.30, 51.14 +CTUN, 815, 0.30, 3.19, 0.000000, 0, 0, 19, 816, 0 +ATT, 0.00, 0.10, -2.24, 1.87, 0.00, 55.35, 51.14 +CTUN, 815, 0.32, 3.07, 0.000000, 0, 0, 18, 815, 0 +ATT, 0.00, 0.35, -2.24, 1.43, 0.00, 54.95, 51.14 +CTUN, 815, 0.32, 3.23, 0.000000, 0, 0, 18, 815, 0 +ATT, 0.00, 0.21, -4.57, 0.62, 0.00, 54.28, 51.14 +CTUN, 815, 0.35, 3.24, 0.000000, 0, 0, 17, 815, 0 +ATT, 0.00, -0.01, -4.76, -1.10, 0.00, 53.30, 51.14 +CTUN, 816, 0.35, 3.13, 0.000000, 0, 0, 14, 815, 0 +ATT, 0.00, 0.29, -5.04, -2.79, 0.00, 52.02, 51.14 +CTUN, 815, 0.37, 3.25, 0.000000, 0, 0, 16, 815, 0 +ATT, 0.00, 0.76, -5.22, -2.71, 0.00, 50.74, 51.14 +CTUN, 816, 0.37, 3.25, 0.000000, 0, 0, 15, 816, 0 +ATT, 0.00, 0.96, -5.22, -1.72, 0.00, 49.47, 51.14 +CTUN, 815, 0.39, 3.27, 0.000000, 0, 0, 15, 815, 0 +ATT, 0.00, 0.63, -5.22, -0.43, 0.00, 48.39, 51.14 +DU32, 7, 166140 +CURR, 816, 2047227, 979, 2202, 5051, 1541.817400 +CTUN, 816, 0.39, 3.36, 0.000000, 0, 0, 11, 816, 0 +ATT, 0.00, 0.14, -5.50, 0.19, 0.00, 47.58, 51.14 +CTUN, 814, 0.41, 3.39, 0.000000, 0, 0, 7, 814, 0 +ATT, 0.00, 0.86, -6.53, -0.03, 0.00, 47.11, 51.14 +CTUN, 815, 0.41, 3.24, 0.000000, 0, 0, 5, 815, 0 +ATT, 0.00, 1.66, -6.72, -1.05, 0.00, 46.98, 51.14 +CTUN, 815, 0.41, 3.31, 0.000000, 0, 0, 3, 815, 0 +ATT, 0.00, 1.20, -7.84, -2.25, 0.00, 47.28, 51.14 +CTUN, 815, 0.41, 3.22, 0.000000, 0, 0, 0, 815, 0 +ATT, 0.00, 0.30, -7.74, -3.24, 0.00, 47.88, 51.14 +CTUN, 816, 0.41, 3.20, 0.000000, 0, 1, -2, 817, 0 +ATT, 0.00, 0.40, -7.37, -3.94, 0.00, 48.58, 51.14 +CTUN, 816, 0.41, 3.41, 0.000000, 0, 1, -2, 817, 0 +ATT, 0.00, 0.70, -6.81, -3.63, 0.00, 49.21, 51.14 +CTUN, 815, 0.41, 3.28, 0.000000, 0, 1, -5, 816, 0 +ATT, 0.00, 0.40, -6.72, -2.67, 0.00, 49.83, 51.14 +CTUN, 815, 0.41, 3.29, 0.000000, 0, 0, -5, 815, 0 +ATT, 0.00, 0.18, -4.85, -1.84, 0.00, 50.26, 51.14 +CTUN, 815, 0.41, 3.30, 0.000000, 0, 0, -4, 815, 0 +ATT, 0.00, -0.29, -4.38, -0.99, 0.00, 50.52, 51.14 +DU32, 7, 166140 +CURR, 816, 2055380, 976, 2183, 5051, 1547.925400 +CTUN, 816, 0.39, 3.34, 0.000000, 0, 0, -7, 815, 0 +ATT, 0.00, -1.16, -4.48, -0.05, 0.00, 50.86, 51.14 +CTUN, 815, 0.39, 3.34, 0.000000, 0, 0, -6, 815, 0 +ATT, 0.00, -1.53, -4.76, 0.26, 0.00, 51.13, 51.14 +CTUN, 815, 0.36, 3.33, 0.000000, 0, 0, -7, 815, 0 +ATT, 0.00, -1.76, -4.85, -0.42, 0.00, 51.45, 51.14 +CTUN, 816, 0.36, 3.22, 0.000000, 0, 0, -9, 816, 0 +ATT, 0.00, -1.43, -4.76, -0.87, 0.00, 51.64, 51.14 +CTUN, 815, 0.35, 3.23, 0.000000, 0, 0, -8, 816, 0 +ATT, -0.75, -0.18, -4.85, -1.28, 0.00, 51.54, 51.14 +CTUN, 815, 0.35, 3.27, 0.000000, 0, 0, -8, 815, 0 +ATT, -0.75, -0.10, -4.76, -1.11, 0.00, 51.19, 51.14 +CTUN, 815, 0.31, 3.21, 0.000000, 0, 0, -6, 815, 0 +ATT, -0.75, -1.34, -4.38, -0.67, 0.00, 50.89, 51.14 +CTUN, 816, 0.31, 3.10, 0.000000, 0, 0, -5, 816, 0 +ATT, -0.75, -2.16, -3.26, -0.58, 0.00, 50.66, 51.14 +CTUN, 815, 0.29, 3.25, 0.000000, 0, 0, -2, 815, 0 +ATT, -0.75, -0.93, -2.52, -0.26, 0.00, 50.56, 51.14 +CTUN, 815, 0.29, 3.16, 0.000000, 0, 0, -1, 815, 0 +ATT, -0.75, 0.40, -2.70, 0.98, 0.00, 50.58, 51.14 +DU32, 7, 166140 +CURR, 815, 2063534, 976, 2215, 5028, 1554.070100 +CTUN, 815, 0.28, 3.25, 0.000000, 0, 0, 0, 815, 0 +ATT, -0.75, 0.17, -2.52, 1.92, 0.00, 50.76, 51.14 +CTUN, 815, 0.28, 3.33, 0.000000, 0, 0, -1, 816, 0 +ATT, -0.75, -0.25, -2.52, 1.54, 0.00, 51.17, 51.14 +CTUN, 815, 0.27, 3.20, 0.000000, 0, 0, -2, 815, 0 +ATT, -0.85, -0.42, -2.52, 0.79, 0.00, 51.49, 51.14 +CTUN, 815, 0.27, 3.10, 0.000000, 0, 0, -1, 816, 0 +ATT, -0.37, -0.81, -3.26, 0.30, 0.00, 51.66, 51.14 +CTUN, 816, 0.26, 3.19, 0.000000, 0, 0, 0, 816, 0 +ATT, 0.00, -1.03, -3.36, 0.62, 0.00, 51.58, 51.14 +CTUN, 816, 0.26, 3.22, 0.000000, 0, 0, 2, 816, 0 +ATT, 0.00, -1.12, -3.26, 0.09, 0.00, 51.54, 51.14 +CTUN, 815, 0.26, 3.24, 0.000000, 0, 0, 2, 815, 0 +ATT, 0.00, -1.16, -3.92, -1.00, 0.00, 51.31, 51.14 +CTUN, 816, 0.26, 3.14, 0.000000, 0, 0, 7, 816, 0 +ATT, 0.00, -0.40, -3.26, -2.22, 0.00, 50.86, 51.14 +CTUN, 815, 0.26, 3.27, 0.000000, 0, 0, 11, 815, 0 +ATT, 0.00, 0.70, -3.26, -2.54, 0.00, 50.11, 51.14 +CTUN, 815, 0.26, 3.21, 0.000000, 0, 0, 13, 815, 0 +ATT, 0.00, 1.57, -3.26, -2.15, 0.00, 49.31, 51.14 +DU32, 7, 166140 +CURR, 815, 2071688, 976, 2220, 5051, 1560.192000 +CTUN, 816, 0.26, 3.10, 0.000000, 0, 0, 12, 816, 0 +ATT, 0.00, 2.27, -2.52, -1.92, 0.00, 48.59, 51.14 +CTUN, 815, 0.26, 3.17, 0.000000, 0, 0, 13, 815, 0 +ATT, 0.00, 2.46, -2.42, -1.05, 0.00, 48.08, 51.14 +CTUN, 815, 0.26, 3.22, 0.000000, 0, 0, 12, 816, 0 +ATT, 0.00, 2.18, -2.89, 0.39, 0.00, 47.83, 51.14 +CTUN, 816, 0.28, 3.21, 0.000000, 0, 0, 13, 816, 0 +MODE, ALT_HOLD, 815 +ATT, 0.00, 1.68, -2.98, 0.77, 0.00, 47.87, 51.14 +CTUN, 815, 0.28, 3.33, 3.517400, 0, 0, 16, 813, 134 +ATT, 0.00, 1.67, -3.26, 0.47, 0.00, 48.16, 51.14 +CTUN, 815, 0.30, 3.35, 3.672000, 0, 0, 11, 909, 134 +ATT, 0.00, 1.43, -3.45, -0.75, 0.00, 48.71, 51.14 +CTUN, 816, 0.30, 3.22, 3.806000, 0, 0, 17, 945, 134 +ATT, 0.00, 1.20, -3.26, -1.63, 0.00, 49.33, 51.14 +CTUN, 815, 0.31, 3.11, 3.950400, 0, 0, 30, 949, 134 +ATT, 0.00, 1.36, -2.70, -1.46, 0.00, 49.97, 51.14 +CTUN, 815, 0.31, 3.22, 4.094800, 0, 0, 37, 963, 134 +ATT, -2.36, 0.87, -2.33, -0.43, 0.00, 50.83, 51.14 +CTUN, 815, 0.35, 3.38, 4.269200, 0, 0, 44, 1000, 134 +ATT, -5.87, -0.38, -2.52, 0.26, 0.00, 51.80, 51.14 +DU32, 7, 166132 +CURR, 815, 2080512, 965, 2418, 5051, 1566.842900 +CTUN, 816, 0.35, 3.46, 4.403200, 0, 0, 44, 1000, 134 +ATT, -9.09, -1.96, -2.52, 0.20, 0.00, 52.66, 51.14 +CTUN, 815, 0.42, 3.53, 4.587399, 0, 0, 46, 1000, 134 +ATT, -9.56, -4.93, -2.52, 0.14, 0.00, 53.41, 51.14 +CTUN, 815, 0.42, 3.72, 4.691799, 0, 0, 45, 1000, 135 +ATT, -8.62, -8.37, -2.52, 0.14, 0.00, 53.94, 51.14 +CTUN, 816, 0.49, 3.70, 4.886199, 0, 0, 48, 1000, 135 +ATT, -8.24, -9.50, -2.52, 0.02, 0.00, 54.16, 51.14 +CTUN, 815, 0.49, 3.75, 5.010599, 0, 0, 53, 1000, 135 +ATT, -6.63, -8.96, -2.52, 0.30, 0.00, 54.12, 51.14 +CTUN, 816, 0.58, 3.89, 5.204998, 0, 0, 51, 1000, 135 +ATT, -3.12, -8.02, -2.80, 0.62, 0.00, 53.84, 51.14 +CTUN, 816, 0.58, 3.90, 5.309398, 0, 0, 50, 1000, 135 +ATT, 0.00, -6.19, -4.20, 0.44, 0.00, 53.50, 51.14 +CTUN, 814, 0.67, 3.79, 5.503398, 0, 0, 51, 1000, 133 +ATT, 0.00, -3.17, -4.20, 0.02, 0.00, 53.20, 51.14 +CTUN, 813, 0.67, 3.85, 5.595798, 0, 0, 52, 1000, 132 +ATT, 0.00, -1.31, -3.82, 0.14, 0.00, 52.97, 51.14 +CTUN, 813, 0.75, 3.99, 5.778598, 0, 0, 54, 1000, 133 +ATT, 0.00, -0.32, -4.01, 1.27, 0.00, 52.65, 51.14 +DU32, 7, 166132 +CURR, 813, 2091512, 970, 2335, 5051, 1574.340800 +CTUN, 811, 0.75, 3.91, 5.891598, 0, 0, 52, 1000, 133 +ATT, 0.00, 1.18, -4.85, 2.31, 0.00, 52.01, 51.14 +CTUN, 804, 0.85, 3.90, 6.060998, 0, 0, 53, 1000, 127 +ATT, 0.00, 2.96, -4.76, 2.79, 0.00, 51.27, 51.14 +CTUN, 807, 0.85, 4.01, 6.138998, 0, 0, 51, 1000, 129 +ATT, 0.00, 3.36, -5.41, 2.69, 0.00, 50.34, 51.14 +CTUN, 804, 0.95, 3.85, 6.316998, 0, 0, 57, 1000, 127 +ATT, 0.00, 2.05, -6.62, 2.14, 0.00, 49.24, 51.14 +MODE, STABILIZE, 815 +CTUN, 805, 0.95, 4.06, 6.384198, 0, 0, 63, 1000, 0 +ATT, 0.00, 1.40, -7.84, 0.83, 0.00, 48.11, 51.14 +CTUN, 807, 1.06, 4.14, 0.000000, 0, 0, 69, 807, 0 +ATT, 0.00, 1.44, -7.84, -1.38, 0.00, 47.18, 51.14 +CTUN, 809, 1.06, 4.15, 0.000000, 0, 0, 69, 809, 0 +ATT, 0.00, 1.39, -7.84, -3.71, 0.00, 46.65, 51.14 +CTUN, 809, 1.19, 4.18, 0.000000, 0, 2, 66, 811, 0 +ATT, 0.00, 1.09, -8.12, -4.98, 0.00, 46.57, 51.14 +CTUN, 809, 1.19, 4.22, 0.000000, 0, 3, 61, 812, 0 +ATT, 0.00, 0.86, -10.64, -5.50, 0.00, 46.88, 51.14 +CTUN, 809, 1.33, 4.29, 0.000000, 0, 3, 60, 812, 0 +ATT, 0.00, 0.62, -10.26, -6.42, 0.00, 47.53, 51.14 +DU32, 7, 166140 +CURR, 809, 2100373, 977, 2194, 5051, 1580.768300 +CTUN, 806, 1.33, 4.47, 0.000000, 0, 4, 57, 810, 0 +ATT, 0.00, 0.29, -8.21, -7.28, 0.00, 48.47, 51.14 +CTUN, 809, 1.46, 4.51, 0.000000, 0, 5, 54, 814, 0 +ATT, 0.00, -0.12, -5.69, -7.17, 0.00, 49.57, 51.14 +CTUN, 809, 1.46, 4.60, 0.000000, 0, 4, 50, 813, 0 +ATT, 0.00, -0.18, -4.85, -5.80, 0.00, 50.78, 51.14 +CTUN, 805, 1.57, 4.74, 0.000000, 0, 2, 51, 811, 0 +ATT, 0.00, -0.31, -4.76, -3.54, 0.00, 51.98, 51.14 +CTUN, 719, 1.57, 4.86, 0.000000, 0, 0, 50, 719, 0 +ATT, 0.00, -0.29, -5.69, -1.85, 0.00, 53.18, 51.14 +CTUN, 555, 1.69, 5.06, 0.000000, 0, 0, 37, 555, 0 +ATT, 0.00, 2.08, -5.69, -0.16, 0.00, 53.63, 51.14 +CTUN, 517, 1.69, 5.34, 0.000000, 0, 1, -21, 518, 0 +ATT, 0.00, 7.50, -5.41, 2.38, 0.00, 52.40, 51.14 +PM, 0, 0, 0, 0, 1000, 10476, 0, 0 +CTUN, 526, 1.78, 5.26, 0.000000, 0, 4, -54, 530, 0 +ATT, 0.00, 6.31, -6.16, 3.27, 0.00, 51.37, 51.14 +CTUN, 626, 1.76, 5.17, 0.000000, 0, 1, -90, 608, 0 +ATT, 0.00, 1.42, -6.06, 0.90, 0.00, 50.21, 51.14 +CTUN, 802, 1.76, 5.01, 0.000000, 0, 0, -121, 802, 0 +ATT, 0.00, -2.00, -6.81, -2.26, 0.00, 49.09, 51.14 +DU32, 7, 166140 +CURR, 911, 2107461, 948, 2757, 5051, 1585.548700 +CTUN, 925, 1.69, 4.83, 0.000000, 0, 2, -135, 927, 0 +ATT, 0.00, -2.32, -8.12, -3.74, 0.00, 47.87, 51.14 +CTUN, 989, 1.69, 4.55, 0.000000, 0, 2, -126, 991, 0 +ATT, 0.00, -2.02, -6.72, -3.55, 0.00, 46.48, 51.14 +CTUN, 999, 1.47, 4.32, 0.000000, 0, 1, -110, 1000, 0 +ATT, 0.00, -2.55, -6.44, -2.89, 0.00, 45.24, 51.14 +CTUN, 1000, 1.47, 4.16, 0.000000, 0, 0, -91, 1000, 0 +ATT, 0.00, -3.11, -6.81, -2.15, 0.00, 44.23, 51.14 +CTUN, 1000, 1.25, 4.22, 0.000000, 0, 0, -79, 1000, 0 +ATT, 0.00, -3.06, -6.62, -1.88, 0.00, 43.57, 51.14 +CTUN, 1000, 1.25, 4.09, 0.000000, 0, 0, -63, 1000, 0 +ATT, 0.00, -2.73, -6.06, -1.97, 0.00, 43.41, 51.14 +CTUN, 1000, 1.07, 4.16, 0.000000, 0, 0, -46, 1000, 0 +ATT, 0.00, -2.80, -5.13, -1.24, 0.00, 43.60, 51.14 +CTUN, 1000, 1.07, 3.91, 0.000000, 0, 0, -31, 1000, 0 +ATT, 0.00, -3.20, -5.50, -0.06, 0.00, 44.28, 51.14 +CTUN, 1000, 0.96, 3.98, 0.000000, 0, 0, -19, 1000, 0 +ATT, 0.00, -3.23, -4.76, 0.59, 0.00, 45.44, 51.14 +CTUN, 1000, 0.96, 3.97, 0.000000, 0, 0, -5, 1000, 0 +ATT, 0.00, -3.00, -4.76, 1.06, 0.00, 46.88, 51.14 +DU32, 7, 166140 +CURR, 1000, 2117434, 959, 2583, 5051, 1593.265100 +CTUN, 1000, 0.91, 4.00, 0.000000, 0, 0, 3, 1000, 0 +ATT, 0.00, -3.06, -4.76, 1.36, 0.00, 48.45, 51.14 +CTUN, 862, 0.91, 3.94, 0.000000, 0, 1, 8, 885, 0 +ATT, 0.00, -3.28, -4.85, 1.27, 0.00, 50.09, 51.14 +CTUN, 766, 0.91, 3.96, 0.000000, 0, 1, 13, 767, 0 +ATT, 0.00, -2.97, -4.76, 0.58, 0.00, 51.63, 51.14 +CTUN, 753, 0.91, 3.97, 0.000000, 0, 0, 7, 753, 0 +ATT, 0.00, -2.24, -4.76, -0.24, 0.00, 53.03, 51.14 +CTUN, 743, 0.91, 4.06, 0.000000, 0, 0, -4, 743, 0 +ATT, 0.00, -1.46, -4.85, -0.77, 0.00, 54.10, 51.14 +CTUN, 775, 0.91, 4.01, 0.000000, 0, 0, -16, 759, 0 +ATT, 0.18, -0.92, -4.57, -1.24, 0.00, 54.78, 51.14 +CTUN, 842, 0.91, 3.98, 0.000000, 0, 0, -27, 842, 0 +ATT, 1.50, -0.31, -3.26, -2.07, 0.00, 55.13, 51.14 +CTUN, 888, 0.95, 4.02, 0.000000, 0, 0, -28, 888, 0 +ATT, 3.18, 0.39, -2.42, -2.65, 0.00, 55.09, 51.14 +CTUN, 913, 0.91, 4.05, 0.000000, 0, 0, -24, 911, 0 +ATT, 3.56, 1.85, -2.52, -2.40, 0.00, 54.97, 51.14 +CTUN, 911, 0.91, 3.95, 0.000000, 0, 1, -21, 912, 0 +ATT, 3.65, 2.97, -2.42, -2.01, 0.00, 54.81, 51.14 +DU32, 7, 166140 +CURR, 905, 2125818, 961, 2494, 5028, 1599.519300 +CTUN, 906, 0.89, 3.92, 0.000000, 0, 1, -17, 909, 0 +ATT, 3.84, 4.15, -2.52, -1.71, 0.00, 54.49, 51.14 +CTUN, 906, 0.89, 3.75, 0.000000, 0, 2, -9, 908, 0 +ATT, 3.93, 5.14, -2.42, -1.30, 0.00, 54.09, 51.14 +CTUN, 886, 0.86, 3.84, 0.000000, 0, 3, -6, 901, 0 +ATT, 3.46, 5.19, -2.52, -0.68, 0.00, 53.64, 51.14 +CTUN, 876, 0.86, 4.00, 0.000000, 0, 2, 0, 878, 0 +ATT, 2.53, 4.72, -2.52, 0.09, 0.00, 53.01, 51.14 +CTUN, 873, 0.86, 3.90, 0.000000, 0, 2, 7, 875, 0 +ATT, 0.00, 4.23, -2.52, 0.85, 0.00, 52.36, 51.14 +CTUN, 868, 0.86, 3.92, 0.000000, 0, 1, 12, 869, 0 +ATT, 0.00, 2.59, -3.54, 1.51, 0.00, 51.93, 51.14 +CTUN, 835, 0.86, 3.96, 0.000000, 0, 0, 15, 835, 0 +ATT, 0.00, 0.48, -6.25, 1.93, 0.00, 51.61, 51.14 +CTUN, 802, 0.87, 3.95, 0.000000, 0, 0, 19, 809, 0 +ATT, 0.00, -0.41, -7.84, 1.51, 0.00, 51.50, 51.14 +CTUN, 789, 0.87, 3.98, 0.000000, 0, 0, 19, 789, 0 +ATT, 0.00, -0.32, -8.12, -0.07, 0.00, 51.44, 51.14 +CTUN, 787, 0.91, 4.03, 0.000000, 0, 0, 15, 786, 0 +ATT, 0.00, -0.12, -8.02, -2.12, 0.00, 51.50, 51.14 +DU32, 7, 166140 +CURR, 783, 2134283, 983, 2033, 5028, 1606.002100 +CTUN, 783, 0.91, 4.04, 0.000000, 0, 0, 10, 786, 0 +ATT, 0.00, -0.69, -7.56, -3.44, 0.00, 51.64, 51.14 +CTUN, 784, 0.95, 4.08, 0.000000, 0, 1, 1, 784, 0 +ATT, 0.00, -1.01, -6.62, -3.68, 0.00, 51.71, 51.14 +CTUN, 792, 0.95, 4.04, 0.000000, 0, 1, -3, 793, 0 +ATT, 0.00, -1.37, -4.94, -3.15, 0.00, 51.72, 51.14 +CTUN, 802, 0.96, 4.00, 0.000000, 0, 1, -5, 802, 0 +ATT, 0.00, -1.50, -5.50, -2.29, 0.00, 51.82, 51.14 +CTUN, 805, 0.95, 4.03, 0.000000, 0, 0, -12, 805, 0 +ATT, 0.00, -1.28, -5.13, -1.56, 0.00, 52.10, 51.14 +CTUN, 813, 0.95, 4.01, 0.000000, 0, 0, -15, 813, 0 +ATT, 0.00, -0.77, -4.57, -1.24, 0.00, 52.42, 51.14 +CTUN, 813, 0.94, 4.01, 0.000000, 0, 0, -16, 813, 0 +ATT, 0.00, -0.01, -4.48, -1.24, 0.00, 52.68, 51.14 +CTUN, 815, 0.94, 4.12, 0.000000, 0, 0, -17, 813, 0 +ATT, 0.00, 0.61, -4.38, -1.55, 0.00, 52.75, 51.14 +CTUN, 814, 0.91, 3.99, 0.000000, 0, 0, -14, 815, 0 +ATT, 0.00, 0.50, -2.52, -1.70, 0.00, 52.64, 51.14 +CTUN, 814, 0.91, 3.92, 0.000000, 0, 0, -13, 816, 0 +ATT, 0.00, 0.34, -2.52, -0.96, 0.00, 52.41, 51.14 +DU32, 7, 166140 +CURR, 813, 2142349, 979, 2234, 5028, 1612.038800 +CTUN, 813, 0.88, 3.90, 0.000000, 0, 0, -13, 813, 0 +ATT, 0.00, 0.03, -2.42, -0.03, 0.00, 52.08, 51.14 +CTUN, 813, 0.88, 3.96, 0.000000, 0, 0, -13, 813, 0 +ATT, 0.00, -0.37, -2.52, 0.60, 0.00, 51.66, 51.14 +CTUN, 813, 0.85, 4.00, 0.000000, 0, 0, -14, 813, 0 +ATT, 0.00, -0.06, -2.70, 0.74, 0.00, 51.36, 51.14 +CTUN, 813, 0.85, 3.92, 0.000000, 0, 0, -17, 813, 0 +ATT, 0.00, 0.72, -2.80, 0.44, 0.00, 51.25, 51.14 +CTUN, 816, 0.82, 3.94, 0.000000, 0, 0, -19, 815, 0 +ATT, -1.32, 0.27, -3.08, -0.46, 0.00, 51.37, 51.14 +CTUN, 822, 0.82, 3.79, 0.000000, 0, 0, -24, 819, 0 +ATT, -2.74, -1.02, -2.70, -1.57, 0.00, 51.71, 51.14 +CTUN, 824, 0.77, 3.91, 0.000000, 0, 0, -25, 823, 0 +ATT, -2.74, -2.53, -2.70, -2.29, 0.00, 52.11, 51.14 +CTUN, 828, 0.77, 3.95, 0.000000, 0, 1, -26, 829, 0 +ATT, -2.55, -3.14, -2.52, -2.66, 0.00, 52.56, 51.14 +CTUN, 835, 0.74, 3.80, 0.000000, 0, 1, -27, 837, 0 +ATT, -2.55, -2.88, -2.52, -2.17, 0.00, 52.99, 51.14 +CTUN, 836, 0.74, 3.90, 0.000000, 0, 1, -25, 837, 0 +ATT, -1.32, -2.91, -1.40, -1.06, 0.00, 53.52, 51.14 +DU32, 7, 166140 +CURR, 836, 2150582, 968, 2352, 5051, 1618.310700 +CTUN, 836, 0.69, 3.87, 0.000000, 0, 0, -24, 836, 0 +ATT, 0.00, -2.78, -1.77, 0.25, 0.00, 54.15, 51.14 +CTUN, 836, 0.69, 3.88, 0.000000, 0, 0, -25, 836, 0 +ATT, 0.00, -0.99, -1.30, 0.45, 0.00, 55.02, 51.14 +CTUN, 840, 0.63, 3.72, 0.000000, 0, 0, -27, 837, 0 +ATT, 0.00, 1.15, -1.58, 0.06, 0.00, 55.84, 51.14 +CTUN, 840, 0.63, 3.91, 0.000000, 0, 0, -25, 840, 0 +ATT, 0.00, 2.10, -1.68, -0.18, 0.00, 56.46, 51.14 +CTUN, 840, 0.58, 3.68, 0.000000, 0, 0, -31, 840, 0 +ATT, 0.00, 1.33, -2.42, -0.54, 0.00, 57.24, 51.14 +CTUN, 838, 0.58, 3.57, 0.000000, 0, 0, -34, 838, 0 +ATT, 0.00, 0.35, -2.42, -0.16, 0.00, 58.13, 51.14 +CTUN, 838, 0.52, 3.66, 0.000000, 0, 0, -34, 838, 0 +ATT, 0.00, -0.66, -2.42, 0.00, 0.00, 58.93, 51.14 +CTUN, 839, 0.52, 3.61, 0.000000, 0, 0, -36, 838, 0 +ATT, 0.00, -0.52, -2.33, 0.29, 0.00, 59.47, 51.14 +CTUN, 855, 0.47, 3.67, 0.000000, 0, 0, -42, 850, 0 +ATT, -2.17, 0.44, -2.24, 0.08, 0.00, 59.62, 51.14 +CTUN, 857, 0.47, 3.35, 0.000000, 0, 0, -49, 857, 0 +ATT, -4.07, -0.03, -1.58, -1.24, 0.00, 59.40, 51.14 +DU32, 7, 166140 +CURR, 866, 2159016, 968, 2364, 5051, 1624.549600 +CTUN, 870, 0.38, 3.39, 0.000000, 0, 0, -48, 866, 0 +ATT, -5.87, -2.90, -1.49, -0.61, 0.00, 58.66, 51.14 +CTUN, 879, 0.38, 3.45, 0.000000, 0, 1, -44, 880, 0 +ATT, -6.06, -4.97, -1.40, 0.80, 0.00, 57.64, 51.14 +CTUN, 906, 0.30, 3.37, 0.000000, 0, 3, -39, 901, 0 +ATT, -5.87, -5.02, -1.21, 1.62, 0.00, 56.56, 51.14 +CTUN, 909, 0.30, 3.28, 0.000000, 0, 3, -34, 912, 0 +ATT, -2.84, -5.51, -0.93, 1.50, 0.00, 55.43, 51.14 +CTUN, 909, 0.23, 3.33, 0.000000, 0, 3, -21, 912, 0 +ATT, 0.00, -4.56, -2.14, 1.71, 0.00, 54.46, 51.14 +CTUN, 908, 0.23, 3.20, 0.000000, 0, 1, -7, 910, 0 +ATT, 0.00, -1.60, -2.24, 1.89, 0.00, 53.56, 51.14 +CTUN, 904, 0.20, 3.12, 0.000000, 0, 0, 6, 906, 0 +ATT, 0.00, 0.45, -2.52, 1.29, 0.00, 52.91, 51.14 +CTUN, 864, 0.20, 3.17, 0.000000, 0, 0, 19, 880, 0 +ATT, 0.00, 0.70, -2.42, 0.64, 0.00, 52.55, 51.14 +CTUN, 849, 0.20, 3.43, 0.000000, 0, 0, 33, 852, 0 +ATT, 0.00, 0.33, -2.52, 0.43, 0.00, 52.38, 51.14 +CTUN, 827, 0.20, 3.38, 0.000000, 0, 0, 44, 827, 0 +ATT, 0.00, 0.60, -2.61, 0.52, 0.00, 52.38, 51.14 +DU32, 7, 166140 +CURR, 809, 2167810, 968, 2192, 5051, 1631.232900 +CTUN, 809, 0.20, 3.42, 0.000000, 0, 0, 48, 813, 0 +ATT, 0.00, 1.37, -2.70, 0.64, 0.00, 52.66, 51.14 +CTUN, 790, 0.25, 3.58, 0.000000, 0, 0, 45, 795, 0 +ATT, 0.00, 1.51, -3.08, 0.03, 0.00, 53.34, 51.14 +CTUN, 786, 0.25, 3.54, 0.000000, 0, 0, 41, 786, 0 +ATT, 0.00, 0.19, -3.08, -1.06, 0.00, 54.21, 51.14 +CTUN, 780, 0.33, 3.67, 0.000000, 0, 0, 34, 780, 0 +ATT, 0.00, -0.15, -3.26, -1.05, 0.00, 55.25, 51.14 +CTUN, 782, 0.33, 3.45, 0.000000, 0, 0, 25, 781, 0 +ATT, 0.00, 0.44, -3.17, -0.16, 0.00, 56.02, 51.14 +CTUN, 788, 0.42, 3.79, 0.000000, 0, 0, 12, 787, 0 +ATT, 0.00, -0.03, -3.26, 0.16, 0.00, 56.46, 51.14 +CTUN, 796, 0.42, 3.68, 0.000000, 0, 0, 2, 796, 0 +ATT, 0.00, -0.83, -2.89, -0.59, 0.00, 56.53, 51.14 +CTUN, 824, 0.46, 3.56, 0.000000, 0, 0, -3, 822, 0 +ATT, 0.00, -0.77, -3.08, -1.23, 0.00, 56.43, 51.14 +CTUN, 843, 0.46, 3.73, 0.000000, 0, 0, -6, 841, 0 +ATT, 0.00, -0.82, -3.08, -1.09, 0.00, 56.13, 51.14 +CTUN, 857, 0.47, 3.66, 0.000000, 0, 0, -8, 855, 0 +ATT, 0.00, -0.84, -3.08, -1.14, 0.00, 55.67, 51.14 +DU32, 7, 166140 +CURR, 857, 2175896, 952, 2462, 5051, 1637.331400 +CTUN, 857, 0.46, 3.50, 0.000000, 0, 0, -3, 857, 0 +ATT, 0.18, -0.59, -3.08, -1.44, 0.00, 55.13, 51.14 +CTUN, 870, 0.46, 3.54, 0.000000, 0, 0, 2, 868, 0 +ATT, 1.31, 0.11, -2.42, -1.58, 0.00, 54.62, 51.14 +CTUN, 871, 0.46, 3.58, 0.000000, 0, 0, 3, 871, 0 +ATT, 1.50, 0.39, -2.42, -1.49, 0.00, 54.08, 51.14 +CTUN, 867, 0.46, 3.35, 0.000000, 0, 0, 8, 868, 0 +ATT, 1.03, 1.00, -2.42, -1.21, 0.00, 53.45, 51.14 +CTUN, 868, 0.45, 3.51, 0.000000, 0, 0, 15, 867, 0 +ATT, 0.84, 1.63, -2.42, -0.46, 0.00, 52.93, 51.14 +CTUN, 860, 0.46, 3.68, 0.000000, 0, 0, 25, 860, 0 +ATT, 0.84, 1.81, -2.52, 0.62, 0.00, 52.58, 51.14 +CTUN, 856, 0.46, 3.71, 0.000000, 0, 0, 26, 856, 0 +ATT, 0.65, 1.81, -2.89, 0.99, 0.00, 52.58, 51.14 +CTUN, 836, 0.48, 3.70, 0.000000, 0, 0, 29, 837, 0 +ATT, 0.46, 1.10, -4.38, 1.25, 0.00, 52.86, 51.14 +CTUN, 814, 0.48, 3.76, 0.000000, 0, 0, 29, 814, 0 +ATT, 0.46, 0.83, -4.76, 1.24, 0.00, 53.44, 51.14 +CTUN, 812, 0.52, 3.72, 0.000000, 0, 0, 30, 813, 0 +ATT, 0.46, 1.08, -5.13, 0.15, 0.00, 54.18, 51.14 +DU32, 7, 166140 +CURR, 813, 2184374, 973, 2217, 5051, 1643.956300 +CTUN, 813, 0.52, 3.73, 0.000000, 0, 0, 27, 813, 0 +ATT, 0.28, 1.80, -5.22, -1.65, 0.00, 55.04, 51.14 +CTUN, 817, 0.58, 3.80, 0.000000, 0, 0, 30, 816, 0 +ATT, 0.28, 1.80, -5.04, -3.07, 0.00, 55.91, 51.14 +CTUN, 821, 0.58, 3.73, 0.000000, 0, 1, 25, 822, 0 +ATT, 0.09, 1.21, -4.76, -3.53, 0.00, 56.85, 51.14 +CTUN, 821, 0.62, 3.86, 0.000000, 0, 1, 25, 822, 0 +ATT, 0.00, 0.01, -4.38, -3.16, 0.00, 57.77, 51.14 +CTUN, 821, 0.62, 3.91, 0.000000, 0, 0, 25, 821, 0 +ATT, 0.00, -1.25, -3.82, -2.55, 0.00, 58.64, 51.14 +CTUN, 821, 0.66, 3.96, 0.000000, 0, 0, 26, 822, 0 +ATT, 0.00, -2.11, -3.92, -1.86, 0.00, 59.38, 51.14 +CTUN, 821, 0.66, 3.93, 0.000000, 0, 0, 21, 822, 0 +ATT, 0.00, -2.66, -3.45, -1.50, 0.00, 60.12, 51.14 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +CTUN, 821, 0.70, 3.92, 0.000000, 0, 1, 17, 821, 0 +ATT, 0.00, -3.14, -4.57, -1.40, 0.00, 60.81, 51.14 +CTUN, 821, 0.70, 3.90, 0.000000, 0, 1, 15, 822, 0 +ATT, 0.00, -3.15, -4.76, -1.78, 0.00, 61.35, 51.35 +CTUN, 821, 0.72, 3.89, 0.000000, 0, 1, 11, 822, 0 +ATT, 0.00, -2.76, -4.76, -2.57, 0.00, 61.78, 51.78 +DU32, 7, 166140 +CURR, 821, 2192586, 972, 2227, 5051, 1650.209800 +CTUN, 821, 0.72, 3.96, 0.000000, 0, 1, 9, 822, 0 +ATT, 0.00, -1.71, -4.85, -3.13, 0.00, 62.27, 52.27 +CTUN, 822, 0.72, 4.05, 0.000000, 0, 1, 5, 823, 0 +ATT, 0.00, -0.74, -3.73, -3.64, 0.00, 62.89, 52.89 +CTUN, 829, 0.72, 3.92, 0.000000, 0, 1, 0, 828, 0 +ATT, 0.00, 0.18, -3.26, -3.86, 0.00, 63.50, 53.50 +CTUN, 831, 0.72, 4.04, 0.000000, 0, 1, -6, 832, 0 +ATT, 0.00, 1.15, -2.89, -3.18, 0.00, 63.91, 53.91 +CTUN, 834, 0.71, 4.09, 0.000000, 0, 1, -12, 835, 0 +ATT, 0.00, 2.10, -2.70, -2.39, 0.00, 64.24, 54.24 +CTUN, 837, 0.71, 3.99, 0.000000, 0, 1, -17, 837, 0 +ATT, 0.00, 2.45, -2.52, -1.96, 0.00, 64.53, 54.53 +CTUN, 855, 0.68, 3.92, 0.000000, 0, 0, -22, 850, 0 +ATT, 0.00, 1.73, -2.61, -1.61, 0.00, 64.64, 54.65 +CTUN, 857, 0.68, 3.85, 0.000000, 0, 0, -26, 857, 0 +ATT, 0.00, 1.04, -2.61, -1.46, 0.00, 64.54, 54.65 +CTUN, 870, 0.63, 3.87, 0.000000, 0, 0, -29, 868, 0 +ATT, 0.00, 1.34, -2.70, -1.68, 0.00, 64.15, 54.65 +CTUN, 885, 0.63, 3.84, 0.000000, 0, 0, -32, 877, 0 +ATT, 0.00, 1.43, -2.80, -1.70, 0.00, 63.49, 54.65 +DU32, 7, 166140 +CURR, 900, 2201079, 970, 2303, 5051, 1656.208500 +CTUN, 903, 0.56, 3.74, 0.000000, 0, 0, -29, 900, 0 +ATT, 0.00, 1.03, -2.61, -1.22, 0.00, 62.58, 54.65 +CTUN, 907, 0.56, 3.56, 0.000000, 0, 0, -23, 906, 0 +ATT, 0.00, 0.67, -2.70, -0.17, 0.00, 61.57, 54.65 +CTUN, 906, 0.47, 3.81, 0.000000, 0, 0, -22, 906, 0 +ATT, -2.17, 0.87, -2.52, 0.53, 0.00, 60.63, 54.65 +CTUN, 906, 0.47, 3.62, 0.000000, 0, 0, -17, 906, 0 +ATT, -3.97, 1.40, -1.77, 0.97, 0.00, 59.84, 54.65 +CTUN, 906, 0.40, 3.61, 0.000000, 0, 0, -12, 906, 0 +ATT, -6.06, -0.05, -0.93, 1.50, 0.00, 59.24, 54.65 +CTUN, 906, 0.40, 3.78, 0.000000, 0, 0, -13, 905, 0 +ATT, -7.48, -2.11, 0.00, 1.86, 0.00, 58.98, 54.65 +CTUN, 906, 0.35, 3.49, 0.000000, 0, 1, -7, 907, 0 +ATT, -9.47, -3.96, 0.00, 1.96, 0.00, 58.78, 54.65 +CTUN, 906, 0.35, 3.49, 0.000000, 0, 3, 0, 909, 0 +ATT, -9.37, -5.76, 0.00, 2.39, 0.00, 58.75, 54.65 +CTUN, 906, 0.30, 3.48, 0.000000, 0, 5, 5, 911, 0 +ATT, -8.05, -7.17, -0.84, 2.74, 0.00, 58.84, 54.65 +CTUN, 906, 0.30, 3.46, 0.000000, 0, 7, 9, 913, 0 +ATT, -6.15, -7.17, -2.24, 2.67, 0.00, 59.27, 54.65 +CTUN, 906, 0.29, 3.43, 0.000000, 0, 7, 15, 913, 0 +DU32, 7, 166140 +CURR, 906, 2210159, 970, 2242, 5051, 1662.691000 +ATT, -2.55, -7.23, -2.52, 2.43, 0.00, 60.08, 54.65 +CTUN, 906, 0.30, 3.29, 0.000000, 0, 6, 13, 912, 0 +ATT, -0.28, -6.65, -3.64, 1.88, 0.00, 60.75, 54.65 +CTUN, 904, 0.29, 3.47, 0.000000, 0, 4, 13, 909, 0 +ATT, 0.00, -4.31, -4.57, 1.77, 0.00, 61.14, 54.65 +CTUN, 885, 0.29, 3.41, 0.000000, 0, 1, 12, 888, 0 +ATT, 0.00, -0.86, -4.57, 0.93, 0.00, 61.29, 54.65 +CTUN, 879, 0.29, 3.24, 0.000000, 0, 0, 7, 879, 0 +ATT, 0.00, 1.23, -4.76, -0.21, 0.00, 61.07, 54.65 +CTUN, 879, 0.29, 3.31, 0.000000, 0, 0, 7, 880, 0 +ATT, 0.46, 1.38, -4.85, -1.05, 0.00, 60.50, 54.65 +CTUN, 879, 0.28, 3.44, 0.000000, 0, 0, 13, 880, 0 +ATT, 1.78, 0.91, -4.76, -1.29, 0.00, 59.71, 54.65 +CTUN, 879, 0.28, 3.66, 0.000000, 0, 0, 17, 880, 0 +ATT, 1.78, 1.25, -4.76, -1.08, 0.00, 59.03, 54.65 +CTUN, 879, 0.28, 3.68, 0.000000, 0, 0, 24, 879, 0 +ATT, 2.34, 1.65, -4.85, -1.21, 0.00, 58.33, 54.65 +CTUN, 879, 0.28, 3.51, 0.000000, 0, 0, 28, 879, 0 +ATT, 2.34, 3.36, -4.85, -1.78, 0.00, 57.51, 54.65 +CTUN, 879, 0.28, 3.46, 0.000000, 0, 1, 31, 880, 0 +DU32, 7, 166140 +CURR, 879, 2219033, 963, 2371, 5051, 1669.077900 +ATT, 2.34, 3.68, -4.85, -1.69, 0.00, 56.78, 54.65 +CTUN, 880, 0.30, 3.63, 0.000000, 0, 1, 36, 880, 0 +ATT, 2.34, 2.71, -5.04, -1.26, 0.00, 56.21, 54.65 +CTUN, 877, 0.30, 3.64, 0.000000, 0, 0, 43, 877, 0 +ATT, 1.96, 3.16, -6.34, -0.27, 0.00, 55.93, 54.65 +CTUN, 874, 0.34, 3.48, 0.000000, 0, 1, 48, 874, 0 +ATT, 0.00, 3.29, -7.84, 0.58, 0.00, 56.06, 54.65 +CTUN, 871, 0.34, 3.62, 0.000000, 0, 0, 45, 872, 0 +ATT, 0.00, 1.91, -10.82, -0.20, 0.00, 56.55, 54.65 +CTUN, 870, 0.39, 3.84, 0.000000, 0, 0, 41, 871, 0 +ATT, 0.00, 0.02, -10.82, -2.37, 0.00, 57.36, 54.65 +CTUN, 857, 0.39, 3.87, 0.000000, 0, 1, 43, 858, 0 +ATT, 0.00, -1.24, -11.76, -4.85, 0.00, 58.45, 54.65 +CTUN, 855, 0.46, 3.72, 0.000000, 0, 3, 40, 858, 0 +ATT, 0.00, -1.33, -11.95, -6.19, 0.00, 59.47, 54.65 +CTUN, 855, 0.46, 3.85, 0.000000, 0, 4, 39, 859, 0 +ATT, 0.00, -1.50, -11.76, -6.83, 0.00, 60.37, 54.65 +CTUN, 855, 0.53, 3.78, 0.000000, 0, 5, 38, 859, 0 +ATT, 0.00, -1.64, -11.67, -7.45, 0.00, 60.95, 54.65 +CTUN, 855, 0.53, 3.81, 0.000000, 0, 6, 33, 861, 0 +DU32, 7, 166140 +CURR, 855, 2227707, 970, 2243, 5028, 1675.541900 +ATT, 0.00, -1.44, -10.82, -7.71, 0.00, 61.56, 54.65 +CTUN, 854, 0.58, 3.91, 0.000000, 0, 6, 30, 861, 0 +ATT, 0.00, -1.01, -10.92, -7.29, 0.00, 62.02, 54.65 +CTUN, 855, 0.58, 3.95, 0.000000, 0, 5, 29, 860, 0 +ATT, 0.00, -0.30, -10.82, -6.66, 0.00, 62.25, 54.65 +CTUN, 855, 0.62, 3.97, 0.000000, 0, 4, 21, 859, 0 +ATT, 0.00, 0.50, -10.17, -6.34, 0.00, 61.99, 54.65 +CTUN, 855, 0.62, 4.05, 0.000000, 0, 4, 14, 859, 0 +ATT, 0.00, 0.84, -6.44, -6.06, 0.00, 61.25, 54.65 +CTUN, 855, 0.64, 3.92, 0.000000, 0, 3, 18, 858, 0 +ATT, 0.00, 0.93, -2.61, -5.09, 0.00, 60.07, 54.65 +CTUN, 857, 0.64, 3.95, 0.000000, 0, 2, 14, 859, 0 +ATT, 0.00, 0.63, -2.52, -3.11, 0.00, 58.49, 54.65 +CTUN, 857, 0.64, 4.13, 0.000000, 0, 0, 17, 857, 0 +ATT, 0.00, -0.19, -2.05, -0.39, 0.00, 56.53, 54.65 +CTUN, 857, 0.64, 4.05, 0.000000, 0, 0, 20, 857, 0 +ATT, -0.37, -0.13, -0.37, 1.76, 0.00, 54.13, 54.65 +CTUN, 857, 0.64, 3.98, 0.000000, 0, 0, 24, 857, 0 +ATT, -1.13, 0.31, -1.12, 2.83, 0.00, 51.79, 54.65 +CTUN, 857, 0.63, 4.06, 0.000000, 0, 1, 26, 858, 0 +DU32, 7, 166140 +CURR, 857, 2236290, 970, 2406, 5051, 1681.952000 +ATT, -0.75, -0.47, -0.74, 3.86, 0.00, 49.77, 54.65 +CTUN, 857, 0.64, 4.12, 0.000000, 0, 2, 26, 859, 0 +ATT, -0.75, -1.58, -2.52, 4.72, 0.00, 48.25, 54.65 +CTUN, 857, 0.64, 4.14, 0.000000, 0, 2, 29, 859, 0 +ATT, -1.04, -2.06, -1.12, 4.90, 0.00, 47.42, 54.65 +CTUN, 857, 0.65, 4.12, 0.000000, 0, 2, 33, 859, 0 +ATT, -2.55, -1.89, -2.52, 4.14, 0.00, 47.39, 54.65 +CTUN, 857, 0.65, 4.02, 0.000000, 0, 1, 34, 858, 0 +ATT, -4.83, -2.76, -4.76, 2.59, 0.00, 47.99, 54.65 +CTUN, 857, 0.68, 4.16, 0.000000, 0, 2, 37, 859, 0 +ATT, -5.68, -6.07, -5.60, 0.99, 0.00, 49.01, 54.65 +CTUN, 857, 0.68, 4.10, 0.000000, 0, 4, 33, 861, 0 +ATT, -4.64, -6.70, -6.72, -0.71, 0.00, 50.09, 54.65 +CTUN, 857, 0.72, 4.05, 0.000000, 0, 4, 33, 860, 0 +ATT, -4.16, -5.38, -8.12, -2.59, 0.00, 51.15, 54.65 +CTUN, 857, 0.72, 4.12, 0.000000, 0, 3, 35, 860, 0 +ATT, -4.07, -3.94, -8.21, -4.24, 0.00, 52.16, 54.65 +CTUN, 857, 0.76, 4.12, 0.000000, 0, 3, 37, 860, 0 +ATT, -0.28, -3.39, -7.74, -5.27, 0.00, 53.07, 54.65 +CTUN, 857, 0.76, 4.07, 0.000000, 0, 4, 39, 861, 0 +DU32, 7, 166140 +CURR, 857, 2244887, 966, 2423, 5051, 1688.667000 +ATT, 0.00, -3.18, -7.37, -5.36, 0.00, 53.77, 54.65 +CTUN, 860, 0.79, 4.07, 0.000000, 0, 3, 42, 860, 0 +ATT, 0.00, -2.03, -6.81, -4.39, 0.00, 54.40, 54.65 +CTUN, 857, 0.79, 4.02, 0.000000, 0, 1, 47, 858, 0 +ATT, 0.00, -1.06, -6.72, -3.11, 0.00, 54.92, 54.65 +CTUN, 839, 0.84, 4.08, 0.000000, 0, 0, 48, 846, 0 +ATT, 0.00, -0.35, -6.72, -2.91, 0.00, 55.19, 54.65 +CTUN, 818, 0.84, 4.14, 0.000000, 0, 0, 48, 823, 0 +ATT, 0.00, -0.65, -6.81, -3.20, 0.00, 55.27, 54.65 +CTUN, 796, 0.91, 4.26, 0.000000, 0, 1, 47, 799, 0 +ATT, 0.00, -1.40, -6.81, -3.33, 0.00, 55.13, 54.65 +CTUN, 797, 0.91, 4.31, 0.000000, 0, 1, 45, 797, 0 +ATT, 0.00, -1.95, -6.72, -3.21, 0.00, 54.78, 54.65 +CTUN, 796, 0.97, 4.35, 0.000000, 0, 1, 38, 797, 0 +ATT, 0.00, -1.55, -6.72, -3.34, 0.00, 54.37, 54.65 +CTUN, 798, 0.97, 4.24, 0.000000, 0, 1, 33, 799, 0 +ATT, 0.00, -1.00, -6.34, -3.28, 0.00, 53.95, 54.65 +CTUN, 802, 1.03, 4.36, 0.000000, 0, 1, 26, 800, 0 +ATT, 0.00, -1.29, -5.69, -2.95, 0.00, 53.61, 54.65 +CTUN, 804, 1.03, 4.41, 0.000000, 0, 1, 21, 805, 0 +DU32, 7, 166140 +CURR, 804, 2253083, 971, 2151, 5028, 1694.844000 +ATT, 0.00, -1.53, -2.52, -2.61, 0.00, 53.43, 54.65 +CTUN, 804, 1.06, 4.40, 0.000000, 0, 0, 17, 804, 0 +ATT, 0.46, -1.09, -2.42, -1.83, 0.00, 53.52, 54.65 +CTUN, 815, 1.06, 4.22, 0.000000, 0, 0, 10, 813, 0 +ATT, 0.93, -0.50, -2.24, -0.65, 0.00, 53.78, 54.65 +CTUN, 831, 1.09, 4.50, 0.000000, 0, 0, 10, 830, 0 +ATT, 1.40, 0.08, -2.24, -0.01, 0.00, 54.20, 54.65 +CTUN, 836, 1.09, 4.46, 0.000000, 0, 0, 10, 836, 0 +ATT, 1.31, 0.57, -2.33, 0.43, 0.00, 54.82, 54.65 +CTUN, 842, 1.10, 4.55, 0.000000, 0, 0, 11, 842, 0 +ATT, 1.21, 0.48, -2.33, 1.19, 0.00, 55.41, 54.65 +CTUN, 850, 1.10, 4.41, 0.000000, 0, 0, 11, 848, 0 +ATT, 1.21, 0.26, -2.24, 2.12, 0.00, 55.95, 54.65 +CTUN, 855, 1.10, 4.44, 0.000000, 0, 0, 11, 853, 0 +ATT, 1.68, 0.10, -2.42, 2.96, 0.00, 56.45, 54.65 +CTUN, 855, 1.10, 4.52, 0.000000, 0, 1, 11, 856, 0 +ATT, 1.78, 0.53, -2.42, 3.24, 0.00, 56.94, 54.65 +CTUN, 855, 1.10, 4.50, 0.000000, 0, 1, 12, 856, 0 +ATT, 2.06, 1.45, -2.52, 3.17, 0.00, 57.24, 54.65 +CTUN, 855, 1.10, 4.52, 0.000000, 0, 1, 11, 856, 0 +DU32, 7, 166140 +CURR, 855, 2261465, 965, 2317, 5051, 1701.228300 +ATT, 2.81, 2.33, -2.52, 2.81, 0.00, 57.49, 54.65 +CTUN, 852, 1.11, 4.61, 0.000000, 0, 1, 12, 853, 0 +ATT, 3.09, 2.86, -3.26, 2.20, 0.00, 57.57, 54.65 +CTUN, 853, 1.11, 4.55, 0.000000, 0, 1, 13, 854, 0 +ATT, 3.18, 3.79, -3.92, 1.44, 0.00, 57.54, 54.65 +CTUN, 850, 1.12, 4.46, 0.000000, 0, 2, 15, 852, 0 +ATT, 3.09, 4.58, -4.48, 0.68, 0.00, 57.27, 54.65 +CTUN, 849, 1.12, 4.55, 0.000000, 0, 2, 10, 851, 0 +ATT, 2.62, 4.66, -4.57, -0.35, 0.00, 56.75, 54.65 +CTUN, 853, 1.14, 4.56, 0.000000, 0, 2, 12, 854, 0 +ATT, 0.75, 4.17, -4.57, -1.15, 0.00, 56.07, 54.65 +CTUN, 850, 1.14, 4.43, 0.000000, 0, 1, 14, 851, 0 +ATT, 0.18, 3.24, -4.66, -1.92, 0.00, 55.51, 54.65 +CTUN, 837, 1.15, 4.54, 0.000000, 0, 1, 17, 843, 0 +ATT, 0.00, 1.68, -6.06, -2.78, 0.00, 55.17, 54.65 +CTUN, 836, 1.15, 4.64, 0.000000, 0, 1, 16, 837, 0 +ATT, 0.00, 0.85, -6.53, -3.64, 0.00, 55.03, 54.65 +CTUN, 836, 1.18, 4.52, 0.000000, 0, 1, 18, 836, 0 +ATT, 0.00, 0.11, -6.53, -4.18, 0.00, 55.10, 54.65 +CTUN, 836, 1.18, 4.52, 0.000000, 0, 2, 17, 838, 0 +DU32, 7, 166140 +CURR, 836, 2269938, 970, 2309, 5051, 1707.732400 +ATT, 0.00, -0.81, -6.53, -4.40, 0.00, 55.12, 54.65 +CTUN, 835, 1.21, 4.55, 0.000000, 0, 2, 18, 837, 0 +ATT, 0.00, -0.93, -6.06, -4.73, 0.00, 55.15, 54.65 +CTUN, 831, 1.21, 4.61, 0.000000, 0, 2, 20, 833, 0 +ATT, 0.00, -0.57, -5.97, -4.59, 0.00, 54.92, 54.65 +CTUN, 830, 1.24, 4.68, 0.000000, 0, 2, 17, 832, 0 +ATT, 0.00, -0.24, -6.06, -4.28, 0.00, 54.63, 54.65 +CTUN, 809, 1.24, 4.75, 0.000000, 0, 1, 19, 814, 0 +ATT, 0.00, -0.13, -5.88, -3.84, 0.00, 54.27, 54.65 +CTUN, 796, 1.28, 4.69, 0.000000, 0, 1, 16, 797, 0 +ATT, 0.00, 0.15, -5.69, -3.60, 0.00, 53.88, 54.65 +CTUN, 796, 1.28, 4.75, 0.000000, 0, 1, 10, 797, 0 +ATT, 0.00, 0.15, -5.69, -3.55, 0.00, 53.36, 54.65 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 796, 1.31, 4.68, 0.000000, 0, 1, 8, 797, 0 +ATT, 0.00, -0.28, -5.60, -3.27, 0.00, 52.61, 54.65 +CTUN, 798, 1.31, 4.75, 0.000000, 0, 0, 7, 798, 0 +ATT, 0.00, -0.52, -4.85, -2.71, 0.00, 51.84, 54.65 +CTUN, 805, 1.32, 4.77, 0.000000, 0, 0, 2, 805, 0 +ATT, 0.00, -0.64, -4.76, -1.99, 0.00, 51.27, 54.65 +CTUN, 814, 1.31, 4.70, 0.000000, 0, 0, 0, 814, 0 +DU32, 7, 166140 +CURR, 814, 2278070, 974, 2157, 5051, 1713.787000 +ATT, 0.00, -0.46, -4.76, -1.55, 0.00, 50.95, 54.65 +CTUN, 833, 1.31, 4.76, 0.000000, 0, 0, -5, 828, 0 +ATT, 0.00, -0.75, -4.76, -1.51, 0.00, 50.95, 54.65 +CTUN, 836, 1.31, 4.78, 0.000000, 0, 0, -6, 836, 0 +ATT, 0.00, -0.89, -4.76, -1.85, 0.00, 51.19, 54.65 +CTUN, 838, 1.33, 4.72, 0.000000, 0, 0, -5, 836, 0 +ATT, 0.00, -0.50, -4.85, -1.97, 0.00, 51.49, 54.65 +CTUN, 840, 1.32, 4.80, 0.000000, 0, 0, -3, 840, 0 +ATT, 0.00, 0.31, -4.85, -1.61, 0.00, 51.78, 54.65 +CTUN, 843, 1.32, 4.64, 0.000000, 0, 0, -3, 843, 0 +ATT, 0.00, 1.31, -4.76, -0.81, 0.00, 51.90, 54.65 +CTUN, 852, 1.30, 4.68, 0.000000, 0, 0, 0, 852, 0 +ATT, 0.00, 1.34, -4.76, -0.12, 0.00, 52.04, 54.65 +CTUN, 853, 1.30, 4.69, 0.000000, 0, 0, 3, 853, 0 +ATT, 0.00, 0.70, -4.85, -0.18, 0.00, 52.15, 54.65 +CTUN, 853, 1.07, 4.68, 0.000000, 0, 0, 4, 853, 0 +ATT, 0.00, 0.39, -4.85, -0.41, 0.00, 52.24, 54.65 +CTUN, 848, 1.07, 4.66, 0.000000, 0, 0, 11, 848, 0 +ATT, 0.00, 1.09, -4.85, 0.06, 0.00, 52.31, 54.65 +CTUN, 840, 1.02, 4.71, 0.000000, 0, 0, 16, 840, 0 +DU32, 7, 166140 +CURR, 839, 2286493, 967, 2350, 5028, 1720.267300 +ATT, 0.00, 1.79, -4.85, 0.70, 0.00, 52.44, 54.65 +CTUN, 836, 1.03, 4.78, 0.000000, 0, 0, 17, 836, 0 +ATT, 0.00, 1.77, -4.85, 0.84, 0.00, 52.58, 54.65 +CTUN, 816, 1.03, 4.69, 0.000000, 0, 0, 17, 817, 0 +ATT, 0.00, 1.46, -4.85, 0.63, 0.00, 52.68, 54.65 +CTUN, 812, 1.04, 4.71, 0.000000, 0, 0, 18, 812, 0 +ATT, 0.00, 1.22, -4.85, 0.13, 0.00, 52.63, 54.65 +CTUN, 804, 1.04, 4.77, 0.000000, 0, 0, 14, 805, 0 +ATT, 0.00, 0.88, -5.04, -0.14, 0.00, 52.43, 54.65 +CTUN, 805, 1.07, 4.80, 0.000000, 0, 0, 11, 805, 0 +ATT, 0.00, 0.75, -5.60, -0.28, 0.00, 52.31, 54.65 +CTUN, 805, 1.06, 4.78, 0.000000, 0, 0, 7, 805, 0 +ATT, 0.00, 0.14, -5.69, -0.88, 0.00, 52.50, 54.65 +CTUN, 805, 1.07, 4.81, 0.000000, 0, 0, 10, 805, 0 +ATT, 0.00, -0.53, -6.06, -1.79, 0.00, 52.98, 54.65 +CTUN, 806, 1.06, 4.84, 0.000000, 0, 0, 7, 806, 0 +ATT, -0.94, -1.05, -6.53, -2.44, 0.00, 53.68, 54.65 +CTUN, 809, 1.06, 4.88, 0.000000, 0, 0, 6, 808, 0 +ATT, -2.65, -1.74, -6.53, -2.48, 0.00, 54.28, 54.65 +CTUN, 809, 0.92, 4.79, 0.000000, 0, 1, 4, 810, 0 +DU32, 7, 166140 +CURR, 809, 2294604, 971, 2175, 5028, 1726.323500 +ATT, -3.88, -2.86, -6.16, -2.53, 0.00, 54.74, 54.65 +CTUN, 807, 1.06, 4.83, 0.000000, 0, 2, 4, 810, 0 +ATT, -3.88, -4.39, -5.88, -2.64, 0.00, 55.01, 54.65 +CTUN, 806, 0.92, 4.95, 0.000000, 0, 3, 7, 809, 0 +ATT, -3.69, -5.19, -5.69, -2.34, 0.00, 55.10, 54.65 +CTUN, 806, 0.92, 4.88, 0.000000, 0, 3, 6, 809, 0 +ATT, -1.42, -5.46, -5.88, -2.08, 0.00, 55.12, 54.65 +CTUN, 806, 0.90, 4.98, 0.000000, 0, 3, 5, 810, 0 +ATT, 0.00, -5.12, -5.60, -2.16, 0.00, 55.02, 54.65 +CTUN, 807, 0.91, 5.02, 0.000000, 0, 2, 5, 809, 0 +ATT, 0.00, -3.94, -5.69, -2.47, -0.09, 54.84, 54.64 +CTUN, 806, 0.91, 4.91, 0.000000, 0, 1, 4, 808, 0 +ATT, 0.00, -3.02, -5.69, -2.84, -3.01, 54.67, 53.92 +CTUN, 806, 0.91, 4.91, 0.000000, 0, 1, 8, 808, 0 +ATT, 0.00, -3.12, -5.50, -2.96, -4.33, 54.23, 52.23 +CTUN, 806, 0.91, 4.86, 0.000000, 0, 1, 5, 808, 0 +ATT, 0.00, -2.82, -5.32, -2.60, -6.98, 53.41, 49.69 +CTUN, 806, 0.91, 4.91, 0.000000, 0, 1, 5, 808, 0 +ATT, 0.00, -1.97, -4.85, -2.00, -8.11, 52.14, 46.09 +CTUN, 807, 0.91, 4.96, 0.000000, 0, 0, 2, 806, 0 +DU32, 7, 166140 +CURR, 806, 2302687, 977, 2121, 5051, 1732.369000 +ATT, 0.00, -1.76, -4.85, -1.57, -8.01, 50.23, 42.42 +CTUN, 806, 0.94, 4.94, 0.000000, 0, 0, 2, 807, 0 +ATT, 0.00, -2.96, -4.76, -1.45, -7.92, 47.87, 38.76 +CTUN, 805, 0.94, 4.94, 0.000000, 0, 1, 1, 806, 0 +ATT, 0.00, -2.91, -4.20, -1.52, -6.79, 45.18, 35.29 +CTUN, 796, 1.00, 5.07, 0.000000, 0, 0, 0, 798, 0 +ATT, 0.00, -1.42, -3.08, -1.81, -5.94, 42.39, 32.44 +CTUN, 796, 0.99, 5.17, 0.000000, 0, 0, 0, 796, 0 +ATT, 0.00, -0.26, -2.70, -2.09, -5.94, 39.64, 29.73 +CTUN, 796, 0.99, 5.05, 0.000000, 0, 0, -1, 796, 0 +ATT, 0.00, 0.30, -2.70, -2.13, -5.47, 37.08, 27.13 +CTUN, 796, 0.96, 5.05, 0.000000, 0, 0, -2, 796, 0 +ATT, 0.00, 0.61, -2.70, -1.52, -3.39, 34.65, 25.06 +CTUN, 796, 0.99, 5.12, 0.000000, 0, 0, -5, 797, 0 +ATT, 0.00, 0.90, -2.89, -0.70, 0.00, 32.46, 24.31 +CTUN, 796, 0.99, 5.09, 0.000000, 0, 0, -6, 796, 0 +ATT, 0.00, 1.31, -2.70, 0.27, 0.00, 30.93, 24.31 +CTUN, 796, 1.23, 5.06, 0.000000, 0, 0, -7, 796, 0 +ATT, 0.00, 1.65, -2.52, 0.99, 0.00, 29.89, 24.31 +CTUN, 805, 1.22, 5.12, 0.000000, 0, 0, -12, 800, 0 +DU32, 7, 166140 +CURR, 805, 2310678, 969, 2076, 5051, 1738.325100 +ATT, 0.00, 1.33, -2.52, 1.19, 0.00, 29.09, 24.31 +CTUN, 824, 1.22, 5.07, 0.000000, 0, 0, -12, 824, 0 +ATT, 0.00, 0.51, -2.52, 1.13, 0.00, 28.71, 24.31 +CTUN, 846, 1.20, 5.09, 0.000000, 0, 0, -14, 843, 0 +ATT, 0.00, 0.39, -2.52, 0.77, 0.00, 28.83, 24.31 +CTUN, 853, 1.20, 4.98, 0.000000, 0, 0, -10, 850, 0 +ATT, 0.00, 1.05, -2.42, 0.64, 0.00, 29.31, 24.31 +CTUN, 855, 1.18, 5.05, 0.000000, 0, 0, -11, 854, 0 +ATT, 0.00, 1.54, -2.42, 0.70, 0.00, 29.88, 24.31 +CTUN, 857, 1.18, 4.99, 0.000000, 0, 0, -15, 857, 0 +ATT, 0.00, 1.76, -2.52, 0.45, 0.00, 30.30, 24.31 +CTUN, 857, 1.13, 4.95, 0.000000, 0, 0, -16, 857, 0 +ATT, 0.00, 2.24, -2.52, 0.34, 0.00, 30.62, 24.31 +CTUN, 857, 1.13, 4.94, 0.000000, 0, 0, -18, 857, 0 +ATT, 0.00, 2.39, -2.52, 0.68, 0.00, 30.78, 24.31 +CTUN, 867, 1.09, 5.01, 0.000000, 0, 0, -20, 861, 0 +ATT, 0.00, 2.11, -2.33, 1.11, 0.00, 30.58, 24.31 +CTUN, 871, 1.09, 4.89, 0.000000, 0, 0, -23, 871, 0 +ATT, 0.00, 1.81, -2.42, 1.47, 0.00, 29.98, 24.31 +CTUN, 877, 1.03, 5.00, 0.000000, 0, 0, -24, 877, 0 +DU32, 7, 166140 +CURR, 879, 2319217, 968, 2271, 5051, 1744.419400 +ATT, 0.00, 1.65, -2.52, 1.72, 0.00, 29.01, 24.31 +CTUN, 887, 1.03, 4.91, 0.000000, 0, 0, -22, 884, 0 +ATT, -2.55, 1.09, -2.42, 2.04, 0.00, 27.97, 24.31 +CTUN, 898, 0.96, 4.92, 0.000000, 0, 0, -25, 897, 0 +ATT, -4.26, 0.13, -2.52, 1.66, 0.00, 27.11, 24.31 +CTUN, 903, 0.96, 4.95, 0.000000, 0, 0, -22, 903, 0 +ATT, -4.35, -1.44, -2.52, 1.68, 0.00, 26.46, 24.31 +CTUN, 905, 0.90, 4.85, 0.000000, 0, 0, -17, 906, 0 +ATT, -4.45, -2.25, -2.52, 1.55, 0.00, 26.00, 24.31 +CTUN, 905, 0.90, 4.89, 0.000000, 0, 0, -12, 907, 0 +ATT, -4.83, -2.05, -2.42, 1.40, 0.00, 25.81, 24.31 +CTUN, 904, 0.83, 4.90, 0.000000, 0, 0, -12, 904, 0 +ATT, -4.35, -1.94, -2.52, 0.96, 0.00, 26.08, 24.31 +CTUN, 906, 0.83, 4.71, 0.000000, 0, 0, -10, 905, 0 +ATT, -2.74, -2.56, -2.70, 0.17, 0.00, 26.68, 24.31 +CTUN, 907, 0.79, 4.59, 0.000000, 0, 1, -8, 907, 0 +ATT, -4.54, -2.52, -2.70, -0.69, 0.00, 27.54, 24.31 +CTUN, 884, 0.79, 4.71, 0.000000, 0, 0, -10, 889, 0 +ATT, -4.07, -1.40, -4.20, -1.25, 0.00, 28.50, 24.31 +CTUN, 859, 0.76, 4.63, 0.000000, 0, 0, -16, 864, 0 +DU32, 7, 166140 +CURR, 859, 2328195, 962, 2167, 5051, 1750.929700 +ATT, -4.16, -0.59, -4.10, -2.18, 0.00, 29.32, 24.31 +CTUN, 857, 0.76, 4.60, 0.000000, 0, 0, -19, 857, 0 +ATT, -4.16, -0.84, -4.10, -2.84, 0.00, 29.71, 24.31 +CTUN, 857, 0.70, 4.62, 0.000000, 0, 1, -23, 858, 0 +ATT, -4.26, -1.78, -4.20, -2.86, 0.00, 29.95, 24.31 +CTUN, 857, 0.70, 4.56, 0.000000, 0, 1, -28, 854, 0 +ATT, -4.16, -2.40, -4.10, -2.58, 0.00, 29.74, 24.31 +CTUN, 886, 0.64, 4.41, 0.000000, 0, 1, -31, 877, 0 +ATT, -4.26, -3.30, -4.10, -2.60, 0.00, 29.46, 24.31 +CTUN, 910, 0.64, 4.47, 0.000000, 0, 2, -32, 911, 0 +ATT, -4.16, -4.33, -4.10, -2.42, 0.00, 28.95, 24.31 +CTUN, 913, 0.59, 4.36, 0.000000, 0, 3, -33, 916, 0 +ATT, -3.97, -4.90, -3.82, -2.36, 0.00, 28.21, 24.31 +CTUN, 921, 0.59, 4.40, 0.000000, 0, 4, -36, 925, 0 +ATT, -3.69, -5.41, -3.73, -2.79, 0.00, 27.41, 24.31 +CTUN, 921, 0.51, 4.36, 0.000000, 0, 4, -32, 926, 0 +ATT, -1.23, -4.63, -4.76, -3.02, 0.00, 26.69, 24.31 +CTUN, 914, 0.51, 4.28, 0.000000, 0, 2, -30, 916, 0 +ATT, 0.00, -3.00, -5.78, -2.59, 0.00, 26.25, 24.31 +CTUN, 913, 0.47, 4.30, 0.000000, 0, 1, -28, 914, 0 +DU32, 7, 166140 +CURR, 913, 2337150, 968, 2271, 5028, 1757.361100 +ATT, 0.00, -0.69, -6.25, -2.38, 0.00, 26.07, 24.31 +CTUN, 912, 0.47, 4.11, 0.000000, 0, 0, -26, 913, 0 +ATT, 0.00, 0.73, -5.60, -3.00, 0.00, 26.11, 24.31 +CTUN, 914, 0.47, 4.14, 0.000000, 0, 1, -26, 914, 0 +ATT, 0.09, 1.00, -4.66, -3.86, 0.00, 26.35, 24.31 +CTUN, 913, 0.67, 4.19, 0.000000, 0, 1, -25, 914, 0 +ATT, 0.18, 0.82, -3.92, -3.77, 0.00, 26.66, 24.31 +CTUN, 913, 0.65, 3.97, 0.000000, 0, 1, -21, 914, 0 +ATT, 0.18, 0.52, -2.52, -2.75, 0.96, 26.86, 24.47 +CTUN, 913, 0.65, 3.99, 0.000000, 0, 0, -21, 913, 0 +ATT, 0.09, 0.42, -2.52, -1.09, 2.11, 26.98, 25.10 +CTUN, 913, 0.62, 4.03, 0.000000, 0, 0, -18, 913, 0 +ATT, 0.00, 0.16, -2.52, 0.58, 3.26, 27.12, 26.23 +CTUN, 915, 0.62, 3.95, 0.000000, 0, 0, -15, 915, 0 +ATT, 0.00, 0.09, -2.52, 1.94, 3.26, 27.16, 27.64 +CTUN, 920, 0.58, 4.31, 0.000000, 0, 0, -10, 919, 0 +ATT, 0.00, 0.34, -2.42, 2.53, 3.55, 27.08, 29.14 +CTUN, 923, 0.58, 4.13, 0.000000, 0, 0, -6, 923, 0 +ATT, 0.00, 0.34, -2.52, 2.00, 3.55, 27.19, 30.68 +CTUN, 923, 0.54, 3.99, 0.000000, 0, 0, 2, 923, 0 +DU32, 7, 166140 +CURR, 923, 2346308, 924, 2794, 5051, 1764.170200 +ATT, 0.00, -0.21, -3.73, 0.52, 3.55, 27.85, 32.22 +CTUN, 924, 0.54, 3.89, 0.000000, 0, 0, 12, 923, 0 +ATT, 0.00, 0.41, -4.10, -0.35, 3.55, 29.16, 33.75 +CTUN, 923, 0.53, 4.03, 0.000000, 0, 0, 23, 923, 0 +ATT, 0.00, 0.97, -4.38, -0.58, 3.55, 30.88, 35.32 +CTUN, 924, 0.54, 4.17, 0.000000, 0, 0, 28, 923, 0 +ATT, 0.09, 0.66, -4.29, -1.65, 3.75, 32.96, 36.88 +CTUN, 908, 0.54, 4.28, 0.000000, 0, 0, 37, 915, 0 +ATT, 0.28, 0.09, -4.38, -2.43, 3.55, 35.31, 38.45 +CTUN, 877, 0.57, 4.17, 0.000000, 0, 0, 43, 892, 0 +ATT, 0.18, 0.01, -4.29, -2.60, 3.55, 37.83, 39.98 +CTUN, 856, 0.57, 4.24, 0.000000, 0, 0, 46, 856, 0 +ATT, 0.00, 0.26, -4.38, -2.27, 3.36, 40.41, 41.49 +CTUN, 838, 0.64, 4.13, 0.000000, 0, 0, 44, 838, 0 +ATT, 0.00, 0.08, -4.48, -2.39, 1.25, 43.15, 42.41 +CTUN, 806, 0.64, 4.25, 0.000000, 0, 0, 42, 809, 0 +ATT, 0.00, -0.77, -4.48, -3.06, 0.00, 45.61, 42.49 +CTUN, 788, 0.71, 4.21, 0.000000, 0, 1, 39, 789, 0 +ATT, 0.00, -1.62, -4.85, -3.41, 0.00, 47.57, 42.49 +CTUN, 770, 0.71, 4.20, 0.000000, 0, 1, 33, 782, 0 +DU32, 7, 166140 +CURR, 770, 2355015, 975, 2025, 5051, 1770.921400 +ATT, 0.00, -2.37, -6.53, -3.15, 0.00, 48.99, 42.49 +CTUN, 765, 0.80, 4.35, 0.000000, 0, 1, 20, 766, 0 +ATT, 0.00, -2.83, -6.25, -3.08, 0.00, 49.96, 42.49 +CTUN, 770, 0.80, 4.30, 0.000000, 0, 1, 11, 766, 0 +ATT, 0.28, -3.53, -5.22, -3.30, 0.00, 50.41, 42.49 +CTUN, 796, 0.85, 4.39, 0.000000, 0, 2, 0, 788, 0 +ATT, 1.78, -3.62, -4.66, -3.24, 0.00, 50.58, 42.49 +CTUN, 842, 0.85, 4.30, 0.000000, 0, 1, -6, 831, 0 +ATT, 2.34, -2.44, -4.29, -2.31, 0.00, 50.63, 42.49 +CTUN, 876, 0.85, 4.28, 0.000000, 0, 0, -10, 876, 0 +ATT, 3.09, -1.12, -2.89, -1.17, 0.00, 50.77, 42.49 +CTUN, 907, 0.84, 4.27, 0.000000, 0, 0, -18, 906, 0 +ATT, 5.53, 0.00, -2.52, -0.20, 0.00, 50.97, 42.49 +PM, 0, 0, 0, 0, 1000, 10480, 0, 0 +CTUN, 909, 0.84, 4.31, 0.000000, 0, 0, -24, 911, 0 +ATT, 6.28, 1.41, -2.52, 0.88, 0.00, 51.28, 42.49 +CTUN, 906, 0.78, 4.38, 0.000000, 0, 1, -26, 907, 0 +ATT, 6.28, 3.70, -2.42, 2.22, 0.00, 51.56, 42.49 +CTUN, 908, 0.78, 4.31, 0.000000, 0, 3, -37, 909, 0 +ATT, 6.37, 4.82, -2.42, 2.80, 0.00, 51.71, 42.49 +CTUN, 911, 0.75, 4.35, 0.000000, 0, 4, -46, 915, 0 +DU32, 7, 166140 +CURR, 913, 2363560, 970, 2097, 5051, 1776.639800 +ATT, 6.37, 5.60, -2.24, 2.52, 0.00, 51.54, 42.49 +CTUN, 931, 0.75, 4.18, 0.000000, 0, 4, -53, 932, 0 +ATT, 2.90, 6.16, -2.33, 1.71, 0.00, 51.13, 42.49 +CTUN, 965, 0.66, 4.15, 0.000000, 0, 5, -60, 951, 0 +ATT, 0.00, 5.97, -4.76, 1.02, 0.00, 50.64, 42.49 +CTUN, 996, 0.66, 4.11, 0.000000, 0, 3, -65, 993, 0 +ATT, 0.00, 3.71, -4.76, 0.24, 0.00, 50.23, 42.49 +CTUN, 1000, 0.54, 3.85, 0.000000, 0, 0, -67, 1000, 0 +ATT, 0.00, 1.47, -4.66, -0.55, 0.00, 49.84, 42.49 +CTUN, 1000, 0.54, 3.88, 0.000000, 0, 0, -68, 1000, 0 +ATT, -2.74, 0.49, -4.66, -0.77, 0.00, 49.31, 42.49 +CTUN, 1000, 0.40, 3.96, 0.000000, 0, 0, -65, 1000, 0 +ATT, -2.17, -0.63, -5.41, -1.13, 0.00, 48.73, 42.49 +CTUN, 1000, 0.40, 3.60, 0.000000, 0, 0, -63, 1000, 0 +ATT, -0.37, -2.53, -4.85, -2.66, 0.00, 48.30, 42.49 +CTUN, 1000, 0.27, 3.35, 0.000000, 0, 0, -52, 1000, 0 +ATT, -3.69, -2.80, -3.54, -3.22, 0.00, 47.89, 42.49 +CTUN, 1000, 0.27, 2.66, 0.000000, 0, 0, -36, 1000, 0 +ATT, -46.04, -2.04, -4.57, -1.99, 0.00, 47.39, 42.49 +CTUN, 999, 0.20, 1.38, 0.000000, 0, 0, -33, 1000, 0 +DU32, 7, 166140 +CURR, 999, 2373425, 1011, 1357, 5028, 1782.612700 +ATT, 0.00, -9.12, -4.76, -1.94, 0.00, 46.81, 42.49 +CTUN, 1000, 0.27, 0.32, 0.000000, 0, 0, -7, 1000, 0 +ATT, 0.00, -0.42, -4.57, 4.98, 0.00, 43.05, 42.49 +CTUN, 999, 0.27, 0.23, 0.000000, 0, 0, -4, 1000, 0 +ATT, 0.00, 1.49, -4.57, 4.29, 0.00, 41.08, 42.49 +CTUN, 1000, 2.09, 0.13, 0.000000, 0, 0, 13, 1000, 0 +ATT, 0.00, -3.39, -4.85, -1.00, 0.00, 40.29, 42.49 +CTUN, 1000, 2.09, 1.64, 0.000000, 0, 0, 33, 1000, 0 +ATT, 0.00, -3.08, -4.57, -2.71, 0.00, 39.44, 42.49 +CTUN, 1000, 2.09, 2.82, 0.000000, 0, 0, 56, 1000, 0 +ATT, 0.00, -0.98, -4.57, -0.80, 0.00, 38.88, 42.49 +CTUN, 1000, 0.22, 3.37, 0.000000, 0, 0, 67, 1000, 0 +ATT, 0.00, 0.22, -4.76, 1.54, 0.00, 38.85, 42.49 +CTUN, 995, 0.23, 3.59, 0.000000, 0, 0, 69, 1000, 0 +ATT, 0.00, -0.54, -4.76, 1.86, 0.00, 39.27, 42.49 +CTUN, 926, 0.23, 3.83, 0.000000, 0, 0, 72, 926, 0 +ATT, 0.37, -2.67, -4.85, 0.39, 0.00, 39.98, 42.49 +CTUN, 860, 0.30, 3.91, 0.000000, 0, 1, 80, 868, 0 +ATT, 2.43, -3.52, -4.85, -1.25, 0.00, 40.94, 42.49 +CTUN, 836, 0.30, 4.08, 0.000000, 0, 1, 86, 843, 0 +DU32, 7, 166140 +CURR, 836, 2383098, 961, 2386, 5051, 1789.624400 +ATT, 3.37, -2.22, -6.06, -1.42, 0.00, 41.90, 42.49 +CTUN, 824, 0.47, 4.14, 0.000000, 0, 0, 87, 824, 0 +ATT, 3.84, -0.50, -6.06, -1.09, 1.05, 42.63, 42.74 +CTUN, 840, 0.47, 4.23, 0.000000, 0, 0, 84, 838, 0 +ATT, 6.00, 0.53, -6.06, -1.18, 3.65, 43.16, 44.06 +CTUN, 855, 0.66, 4.22, 0.000000, 0, 0, 80, 855, 0 +ATT, 6.56, 1.32, -5.88, -1.72, 5.76, 43.75, 46.27 +CTUN, 816, 0.66, 4.30, 0.000000, 0, 0, 78, 821, 0 +ATT, 6.46, 2.32, -5.78, -2.22, 9.90, 44.63, 50.01 +CTUN, 778, 0.82, 4.45, 0.000000, 0, 1, 75, 787, 0 +ATT, 6.37, 3.63, -5.88, -2.68, 12.30, 45.95, 55.10 +CTUN, 720, 0.82, 4.38, 0.000000, 0, 2, 66, 742, 0 +ATT, 6.28, 5.39, -6.25, -2.74, 12.40, 48.22, 58.22 +CTUN, 700, 0.98, 4.50, 0.000000, 0, 3, 54, 705, 0 +ATT, 3.65, 6.28, -6.25, -2.89, 12.21, 51.10, 61.10 +CTUN, 700, 0.98, 4.65, 0.000000, 0, 4, 34, 703, 0 +ATT, 0.00, 5.59, -5.69, -2.79, 10.48, 54.42, 64.42 +CTUN, 746, 1.10, 4.61, 0.000000, 0, 2, 17, 748, 0 +ATT, 0.00, 3.40, -4.57, -2.47, 5.19, 57.93, 67.66 +CTUN, 839, 1.10, 4.64, 0.000000, 0, 1, 0, 810, 0 +DU32, 7, 166140 +CURR, 839, 2390937, 978, 2001, 5028, 1795.249600 +ATT, 0.00, 1.40, -4.57, -2.12, 3.17, 61.19, 69.38 +CTUN, 913, 1.18, 4.63, 0.000000, 0, 0, -8, 906, 0 +ATT, 0.00, 0.88, -4.48, -1.70, 1.05, 64.00, 70.09 +CTUN, 954, 1.18, 4.65, 0.000000, 0, 0, -5, 943, 0 +ATT, 0.00, 1.05, -4.38, -1.16, 0.09, 66.32, 70.27 +CTUN, 994, 1.19, 4.61, 0.000000, 0, 0, -1, 990, 0 +ATT, 0.00, 0.58, -3.92, -0.75, 0.00, 68.12, 70.27 +CTUN, 1000, 1.19, 4.67, 0.000000, 0, 0, 1, 999, 0 +ATT, 0.00, -0.21, -3.73, -0.92, 0.00, 69.38, 70.27 +CTUN, 999, 1.19, 4.70, 0.000000, 0, 0, 11, 1000, 0 +ATT, 0.00, -0.58, -4.20, -1.21, 0.00, 70.15, 70.27 +CTUN, 980, 1.19, 4.59, 0.000000, 0, 0, 18, 993, 0 +ATT, 0.00, -0.51, -4.76, -1.26, 0.00, 70.47, 70.27 +CTUN, 908, 1.25, 4.75, 0.000000, 0, 0, 22, 909, 0 +ATT, 0.00, -0.51, -5.32, -1.40, 0.00, 70.53, 70.27 +CTUN, 870, 1.25, 4.85, 0.000000, 0, 0, 26, 883, 0 +ATT, 0.00, -0.77, -5.41, -1.91, 0.00, 70.29, 70.27 +CTUN, 795, 1.26, 4.84, 0.000000, 0, 0, 32, 805, 0 +ATT, 0.00, -1.07, -6.16, -2.85, 0.00, 69.87, 70.27 +CTUN, 782, 1.25, 4.87, 0.000000, 0, 1, 32, 788, 0 +DU32, 7, 166140 +CURR, 782, 2400140, 972, 1978, 5028, 1802.078000 +ATT, 0.00, -1.21, -6.25, -3.82, 0.00, 69.20, 70.27 +CTUN, 780, 1.26, 4.78, 0.000000, 0, 1, 25, 780, 0 +ATT, 0.00, -0.95, -6.25, -4.88, 0.00, 68.13, 70.27 +CTUN, 779, 1.26, 4.96, 0.000000, 0, 2, 18, 781, 0 +ATT, 0.00, -0.73, -6.06, -5.53, 0.00, 66.99, 70.27 +CTUN, 767, 1.38, 4.97, 0.000000, 0, 3, 11, 770, 0 +ATT, 0.00, -0.41, -5.69, -5.56, 0.00, 65.74, 70.27 +CTUN, 786, 1.38, 4.98, 0.000000, 0, 2, 3, 778, 0 +ATT, -0.37, -0.24, -4.66, -4.98, 0.00, 64.51, 70.27 +CTUN, 820, 1.42, 4.99, 0.000000, 0, 2, -8, 808, 0 +ATT, -2.84, -0.60, -3.08, -3.95, 0.00, 63.30, 70.27 +CTUN, 852, 1.38, 4.96, 0.000000, 0, 1, -12, 852, 0 +ATT, -3.12, -2.08, -3.08, -2.20, 0.00, 62.17, 70.27 +CTUN, 856, 1.38, 5.10, 0.000000, 0, 1, -10, 856, 0 +ATT, -6.06, -4.18, -3.08, -0.45, 0.00, 61.32, 70.27 +CTUN, 871, 0.93, 4.97, 0.000000, 0, 2, -8, 869, 0 +ATT, -6.06, -6.13, -2.89, 0.48, 0.00, 60.88, 70.27 +CTUN, 884, 0.93, 5.07, 0.000000, 0, 6, -4, 888, 0 +ATT, -5.96, -8.08, -2.80, 0.59, 0.00, 61.14, 70.27 +CTUN, 884, 0.86, 5.18, 0.000000, 0, 8, 2, 892, 0 +DU32, 7, 166140 +CURR, 884, 2408384, 948, 2584, 5051, 1808.237200 +ATT, -2.84, -8.29, -2.89, 0.92, 0.00, 61.94, 70.27 +CTUN, 882, 0.86, 5.29, 0.000000, 0, 7, 15, 890, 0 +ATT, 0.00, -7.11, -3.45, 1.90, 0.00, 62.96, 70.27 +CTUN, 854, 0.85, 5.28, 0.000000, 0, 4, 23, 861, 0 +ATT, 0.00, -4.27, -3.17, 2.29, 0.00, 64.36, 70.27 +CTUN, 816, 0.86, 5.10, 0.000000, 0, 1, 29, 822, 0 +ATT, 0.00, -1.86, -3.26, 1.86, 0.00, 65.55, 70.27 +CTUN, 772, 0.86, 5.26, 0.000000, 0, 0, 31, 780, 0 +ATT, 0.00, -0.97, -3.08, 1.14, 0.00, 66.35, 70.27 +CTUN, 740, 0.92, 5.13, 0.000000, 0, 0, 23, 742, 0 +ATT, 0.00, -0.66, -3.17, 0.24, 0.00, 66.72, 70.27 +CTUN, 736, 0.92, 5.18, 0.000000, 0, 0, 14, 735, 0 +ATT, 0.00, 0.29, -3.26, -1.13, 0.00, 66.92, 70.27 +CTUN, 736, 1.03, 5.21, 0.000000, 0, 0, 0, 736, 0 +ATT, 0.00, 1.66, -3.26, -2.61, 0.00, 67.10, 70.27 +CTUN, 741, 1.03, 5.11, 0.000000, 0, 1, -14, 737, 0 +ATT, 0.00, 2.22, -3.17, -3.65, 0.00, 67.45, 70.27 +CTUN, 789, 1.09, 5.17, 0.000000, 0, 1, -26, 781, 0 +ATT, 0.00, 1.65, -2.89, -4.13, 0.00, 67.86, 70.27 +CTUN, 855, 1.09, 5.19, 0.000000, 0, 2, -37, 843, 0 +DU32, 7, 166140 +CURR, 863, 2416311, 968, 2156, 5051, 1813.939600 +ATT, 0.00, 1.26, -2.98, -3.77, 0.00, 68.10, 70.27 +CTUN, 916, 1.49, 5.08, 0.000000, 0, 1, -36, 912, 0 +ATT, 0.00, 1.31, -2.80, -2.48, 0.00, 68.12, 70.27 +CTUN, 951, 1.44, 5.09, 0.000000, 0, 0, -30, 951, 0 +ATT, 0.00, 1.39, -2.70, -0.85, 0.00, 68.01, 70.27 +CTUN, 973, 1.44, 5.07, 0.000000, 0, 0, -17, 972, 0 +ATT, 0.00, 0.50, -2.70, 0.21, 0.00, 67.77, 70.27 +CTUN, 973, 1.26, 4.98, 0.000000, 0, 0, -9, 973, 0 +ATT, 0.00, -0.34, -2.70, 0.29, 0.00, 67.47, 70.27 +CTUN, 952, 1.26, 5.08, 0.000000, 0, 0, 1, 965, 0 +ATT, 0.00, -0.35, -2.61, -0.06, 0.00, 67.29, 70.27 +CTUN, 882, 1.26, 5.04, 0.000000, 0, 0, 17, 897, 0 +ATT, 0.00, 0.15, -2.70, -0.48, 0.00, 67.21, 70.27 +CTUN, 832, 1.26, 4.97, 0.000000, 0, 0, 28, 850, 0 +ATT, 0.00, 0.42, -2.89, -0.77, 0.00, 67.25, 70.27 +CTUN, 768, 1.26, 4.97, 0.000000, 0, 0, 32, 774, 0 +ATT, 0.00, 0.44, -3.08, -1.18, 0.00, 67.43, 70.27 +CTUN, 761, 1.28, 4.99, 0.000000, 0, 0, 27, 761, 0 +ATT, 0.00, 0.44, -3.17, -1.86, 0.00, 67.64, 70.27 +CTUN, 761, 1.28, 5.10, 0.000000, 0, 0, 16, 761, 0 +DU32, 7, 166140 +CURR, 761, 2425175, 985, 1826, 5051, 1820.760700 +ATT, 0.00, 0.36, -3.26, -2.40, 0.00, 67.83, 70.27 +CTUN, 761, 1.49, 5.14, 0.000000, 0, 0, 8, 761, 0 +ATT, 0.00, 0.27, -3.26, -2.75, 0.00, 67.85, 70.27 +CTUN, 766, 1.49, 5.06, 0.000000, 0, 0, -3, 765, 0 +ATT, 0.00, 0.59, -3.17, -2.92, 0.00, 67.71, 70.27 +CTUN, 801, 1.52, 4.97, 0.000000, 0, 0, -11, 798, 0 +ATT, 0.00, 0.87, -3.17, -2.76, 0.00, 67.49, 70.27 +CTUN, 832, 1.52, 5.06, 0.000000, 0, 0, -17, 825, 0 +ATT, 0.00, 0.89, -3.26, -2.35, 0.00, 67.27, 70.27 +CTUN, 838, 1.52, 5.02, 0.000000, 0, 0, -21, 838, 0 +ATT, 0.00, 0.62, -3.26, -1.88, 0.00, 67.06, 70.27 +CTUN, 838, 1.52, 5.08, 0.000000, 0, 0, -20, 838, 0 +ATT, 0.00, -0.24, -3.08, -1.58, 0.00, 67.05, 70.27 +CTUN, 838, 1.52, 5.03, 0.000000, 0, 0, -21, 838, 0 +ATT, 0.00, -1.23, -3.08, -1.47, 0.00, 67.27, 70.27 +CTUN, 835, 1.47, 5.14, 0.000000, 0, 0, -17, 836, 0 +ATT, 0.00, -1.80, -3.08, -1.58, 0.00, 67.57, 70.27 +CTUN, 836, 1.47, 5.08, 0.000000, 0, 0, -16, 836, 0 +ATT, 0.00, -1.85, -3.08, -1.90, 0.00, 68.07, 70.27 +CTUN, 836, 1.45, 4.97, 0.000000, 0, 0, -18, 836, 0 +DU32, 7, 166140 +CURR, 835, 2433332, 963, 2262, 5051, 1826.762800 +ATT, 0.00, -1.53, -2.89, -2.06, 0.00, 68.68, 70.27 +CTUN, 836, 1.45, 5.04, 0.000000, 0, 0, -13, 836, 0 +ATT, 0.00, -1.08, -2.70, -1.96, 0.00, 69.47, 70.27 +CTUN, 836, 1.15, 5.04, 0.000000, 0, 0, -14, 836, 0 +ATT, 0.00, -0.78, -2.89, -1.75, 0.00, 70.46, 70.27 +CTUN, 836, 1.27, 5.08, 0.000000, 0, 0, -13, 836, 0 +ATT, 0.00, -0.66, -3.08, -1.48, 0.00, 71.51, 70.27 +CTUN, 836, 1.16, 5.04, 0.000000, 0, 0, -12, 836, 0 +ATT, 0.00, -0.65, -2.89, -1.38, 0.00, 72.67, 70.27 +CTUN, 836, 1.23, 5.08, 0.000000, 0, 0, -9, 836, 0 +ATT, 0.00, -0.76, -2.70, -1.43, 0.00, 73.83, 70.27 +CTUN, 836, 1.18, 4.93, 0.000000, 0, 0, -9, 836, 0 +ATT, 0.00, -0.83, -2.80, -1.44, 0.00, 74.97, 70.27 +CTUN, 836, 1.23, 5.14, 0.000000, 0, 0, -5, 836, 0 +ATT, 0.00, -0.83, -2.80, -1.13, 0.00, 76.12, 70.27 +CTUN, 836, 1.19, 5.08, 0.000000, 0, 0, -3, 836, 0 +ATT, 0.00, -0.37, -2.70, -0.69, 0.00, 77.28, 70.27 +CTUN, 836, 1.23, 4.95, 0.000000, 0, 0, -2, 836, 0 +ATT, 0.00, 0.18, -2.61, -0.02, 0.00, 78.39, 70.27 +CTUN, 836, 1.23, 5.05, 0.000000, 0, 0, -5, 835, 0 +DU32, 7, 166140 +CURR, 836, 2441690, 963, 2070, 5028, 1833.006700 +ATT, 0.00, 0.62, -2.70, 0.49, 0.00, 79.39, 70.27 +CTUN, 836, 1.35, 5.13, 0.000000, 0, 0, -8, 835, 0 +ATT, 0.00, 0.95, -2.70, 0.73, 0.00, 80.15, 70.27 +CTUN, 836, 1.35, 5.06, 0.000000, 0, 0, -14, 835, 0 +ATT, 0.00, 1.08, -2.80, 0.46, 0.00, 80.70, 70.70 +CTUN, 836, 1.37, 5.18, 0.000000, 0, 0, -19, 835, 0 +ATT, 0.00, 0.84, -2.61, -0.16, 0.00, 81.12, 71.12 +CTUN, 835, 1.35, 5.17, 0.000000, 0, 0, -23, 836, 0 +ATT, 0.00, 0.68, -2.52, -1.01, 0.00, 81.40, 71.40 +CTUN, 857, 1.35, 5.12, 0.000000, 0, 0, -25, 855, 0 +ATT, 0.00, 0.66, -2.61, -1.57, -3.58, 81.49, 71.49 +CTUN, 882, 1.34, 5.13, 0.000000, 0, 0, -28, 876, 0 +ATT, 0.00, 0.71, -2.70, -2.02, -4.90, 81.00, 71.00 +PM, 0, 0, 0, 0, 1000, 10492, 0, 0 +CTUN, 904, 1.34, 5.09, 0.000000, 0, 0, -35, 904, 0 +ATT, 0.00, 0.58, -2.70, -2.49, -8.11, 79.73, 69.73 +CTUN, 906, 1.31, 5.01, 0.000000, 0, 0, -38, 906, 0 +ATT, 0.00, 0.33, -2.61, -2.59, -8.49, 77.53, 67.53 +CTUN, 906, 1.31, 5.06, 0.000000, 0, 0, -46, 906, 0 +ATT, 0.00, -0.17, -2.70, -2.27, -8.67, 74.59, 64.59 +CTUN, 909, 1.25, 5.07, 0.000000, 0, 0, -51, 909, 0 +DU32, 7, 166140 +CURR, 909, 2450372, 970, 2157, 5051, 1838.877900 +ATT, -0.56, -0.96, -2.61, -1.96, -9.62, 70.92, 60.92 +CTUN, 911, 1.25, 5.04, 0.000000, 0, 0, -52, 911, 0 +ATT, -4.73, -1.70, -2.70, -1.62, -10.66, 66.36, 56.36 +CTUN, 911, 1.17, 4.87, 0.000000, 0, 0, -57, 911, 0 +ATT, -5.49, -2.71, -2.70, -1.37, -10.75, 61.58, 51.62 +CTUN, 925, 1.17, 4.85, 0.000000, 0, 1, -60, 920, 0 +ATT, -2.74, -4.92, -2.70, -1.59, -9.81, 56.58, 46.83 +CTUN, 957, 1.06, 4.85, 0.000000, 0, 4, -59, 952, 0 +ATT, -1.61, -5.63, -1.58, -2.00, -7.73, 51.37, 42.91 +CTUN, 983, 1.06, 4.62, 0.000000, 0, 3, -56, 986, 0 +ATT, 0.00, -4.37, -2.80, -1.67, -4.05, 46.19, 40.59 +CTUN, 1000, 0.95, 4.66, 0.000000, 0, 1, -52, 1000, 0 +ATT, 0.00, -2.98, -2.80, -0.86, -0.94, 41.30, 39.50 +CTUN, 1000, 0.95, 4.68, 0.000000, 0, 0, -44, 1000, 0 +ATT, 0.00, -1.97, -3.08, -0.22, 0.00, 37.09, 39.41 +CTUN, 999, 0.83, 4.62, 0.000000, 0, 0, -31, 1000, 0 +ATT, 0.00, -1.52, -3.08, -0.47, 0.00, 33.84, 39.41 +CTUN, 980, 0.83, 4.42, 0.000000, 0, 0, -19, 980, 0 +ATT, 0.00, -1.23, -4.01, -1.21, 0.00, 31.64, 39.41 +CTUN, 946, 0.76, 4.45, 0.000000, 0, 0, -1, 952, 0 +DU32, 7, 166140 +CURR, 946, 2459980, 939, 2700, 5051, 1845.866100 +ATT, 0.00, -0.84, -4.29, -1.82, 0.00, 30.33, 39.41 +CTUN, 900, 0.76, 4.41, 0.000000, 0, 0, 8, 909, 0 +ATT, 0.00, -0.34, -4.57, -2.07, 0.00, 30.03, 39.41 +CTUN, 857, 0.72, 4.40, 0.000000, 0, 0, 17, 864, 0 +ATT, 0.00, -0.05, -4.48, -1.71, 0.00, 30.45, 39.41 +CTUN, 830, 0.72, 4.35, 0.000000, 0, 0, 20, 838, 0 +ATT, 0.00, 0.28, -2.70, -1.07, 0.00, 31.21, 39.41 +CTUN, 817, 0.72, 4.40, 0.000000, 0, 0, 21, 819, 0 +ATT, 0.00, -0.07, -2.70, -0.48, 0.00, 32.19, 39.41 +CTUN, 807, 0.74, 4.38, 0.000000, 0, 0, 16, 813, 0 +ATT, 0.00, -0.06, -2.52, 0.13, 0.00, 33.32, 39.41 +CTUN, 805, 0.74, 4.44, 0.000000, 0, 0, 12, 805, 0 +ATT, 0.00, 0.11, -2.70, 0.89, 0.00, 34.57, 39.41 +CTUN, 805, 0.77, 4.45, 0.000000, 0, 0, 3, 805, 0 +ATT, 0.18, 0.11, -2.61, 0.91, 0.00, 35.97, 39.41 +CTUN, 830, 0.77, 4.43, 0.000000, 0, 0, -5, 830, 0 +ATT, 0.28, 0.09, -2.42, -0.01, 0.00, 37.33, 39.41 +CTUN, 870, 0.77, 4.52, 0.000000, 0, 0, -6, 859, 0 +ATT, 0.46, 1.03, -2.52, -0.89, 0.00, 38.49, 39.41 +CTUN, 888, 0.77, 4.53, 0.000000, 0, 0, -4, 888, 0 +DU32, 7, 166140 +CURR, 888, 2468422, 949, 2516, 5051, 1852.241200 +ATT, 1.96, 3.26, -2.42, -1.86, 0.00, 39.45, 39.41 +CTUN, 889, 0.77, 4.36, 0.000000, 0, 2, -1, 891, 0 +ATT, 2.53, 4.67, -2.52, -2.35, 0.00, 40.22, 39.41 +CTUN, 889, 0.77, 4.36, 0.000000, 0, 3, 4, 891, 0 +ATT, 3.18, 5.17, -2.52, -2.36, 0.00, 40.76, 39.41 +CTUN, 889, 0.77, 4.45, 0.000000, 0, 4, 4, 892, 0 +ATT, 3.18, 6.08, -2.52, -1.95, 0.00, 41.12, 39.41 +CTUN, 884, 0.76, 4.55, 0.000000, 0, 4, 6, 890, 0 +ATT, 0.46, 6.32, -2.42, -1.05, 0.00, 41.25, 39.41 +CTUN, 870, 0.76, 4.48, 0.000000, 0, 4, 7, 874, 0 +ATT, 0.00, 5.30, -2.61, -0.47, 0.00, 41.20, 39.41 +CTUN, 841, 0.76, 4.42, 0.000000, 0, 1, 7, 848, 0 +ATT, 0.00, 2.73, -3.08, -0.36, 0.00, 41.07, 39.41 +CTUN, 825, 0.76, 4.50, 0.000000, 0, 0, 9, 825, 0 +ATT, -0.09, 0.51, -3.54, -0.34, 0.00, 40.90, 39.41 +CTUN, 822, 0.76, 4.40, 0.000000, 0, 0, 9, 821, 0 +ATT, -0.18, -0.46, -3.54, -0.53, 0.00, 40.85, 39.41 +CTUN, 823, 0.79, 4.45, 0.000000, 0, 0, 11, 821, 0 +ATT, -0.75, -0.37, -3.26, -0.92, 0.00, 40.94, 39.41 +CTUN, 825, 0.79, 4.48, 0.000000, 0, 0, 8, 825, 0 +DU32, 7, 166140 +CURR, 825, 2477016, 963, 2219, 5028, 1858.748200 +ATT, -2.46, 0.26, -2.42, -0.88, 0.00, 41.19, 39.41 +CTUN, 823, 0.81, 4.54, 0.000000, 0, 0, 6, 826, 0 +ATT, -2.84, -0.19, -2.80, -0.36, 0.00, 41.59, 39.41 +CTUN, 823, 0.81, 4.57, 0.000000, 0, 0, 5, 823, 0 +ATT, -3.03, -1.04, -2.98, -0.05, 0.00, 42.13, 39.41 +CTUN, 823, 0.82, 4.62, 0.000000, 0, 0, 3, 823, 0 +ATT, -2.84, -1.22, -2.80, -0.32, 0.00, 42.74, 39.41 +CTUN, 824, 0.82, 4.46, 0.000000, 0, 0, 2, 824, 0 +ATT, -2.93, -1.52, -2.89, -0.51, 0.00, 43.51, 39.41 +CTUN, 825, 0.83, 4.52, 0.000000, 0, 0, 4, 826, 0 +ATT, -2.93, -2.23, -2.89, -0.58, 0.00, 44.53, 39.41 +CTUN, 828, 0.82, 4.46, 0.000000, 0, 0, 3, 828, 0 +ATT, -3.31, -3.23, -3.26, -0.68, 0.00, 45.77, 39.41 +CTUN, 826, 0.82, 4.39, 0.000000, 0, 1, 0, 827, 0 +ATT, -2.36, -3.90, -2.24, -0.75, 0.00, 47.29, 39.41 +CTUN, 826, 0.82, 4.51, 0.000000, 0, 1, -4, 827, 0 +ATT, -1.32, -3.94, -3.17, -0.83, 0.00, 48.96, 39.41 +CTUN, 826, 0.82, 4.46, 0.000000, 0, 1, -8, 827, 0 +ATT, -0.94, -2.80, -3.17, -0.72, 0.00, 50.60, 40.60 +CTUN, 828, 0.81, 4.36, 0.000000, 0, 0, -18, 826, 0 +DU32, 7, 166140 +CURR, 828, 2485270, 977, 1909, 5028, 1864.784100 +ATT, 0.00, -1.40, -3.26, -0.57, 0.00, 52.13, 42.13 +CTUN, 830, 0.81, 4.47, 0.000000, 0, 0, -29, 828, 0 +ATT, 0.00, -0.65, -3.08, -0.70, 0.00, 53.47, 43.47 +CTUN, 836, 0.77, 4.39, 0.000000, 0, 0, -38, 836, 0 +ATT, 0.00, -0.25, -2.98, -0.76, 0.00, 54.74, 44.74 +CTUN, 852, 0.77, 4.39, 0.000000, 0, 0, -46, 853, 0 +ATT, 0.00, -0.12, -2.80, -0.55, 0.00, 56.01, 46.01 +CTUN, 908, 0.70, 4.43, 0.000000, 0, 0, -52, 907, 0 +ATT, 0.00, -0.29, -2.80, -0.10, 0.00, 57.23, 47.23 +CTUN, 932, 0.70, 4.33, 0.000000, 0, 0, -58, 923, 0 +ATT, 0.00, 0.03, -2.70, 0.61, 0.00, 58.40, 48.40 +CTUN, 973, 0.60, 4.33, 0.000000, 0, 0, -67, 959, 0 +ATT, 0.00, 0.55, -2.61, 1.10, 0.00, 59.39, 49.39 +CTUN, 1000, 0.60, 4.18, 0.000000, 0, 0, -73, 1000, 0 +ATT, 0.00, 0.75, -2.70, 1.28, 0.00, 60.15, 50.15 +CTUN, 1000, 0.46, 4.00, 0.000000, 0, 0, -80, 999, 0 +ATT, 0.00, -0.03, -2.89, 1.05, 0.00, 60.76, 50.76 +CTUN, 999, 0.46, 4.13, 0.000000, 0, 0, -85, 999, 0 +ATT, 0.00, -1.12, -2.89, 0.40, 0.00, 61.05, 51.05 +CTUN, 1000, 0.31, 3.83, 0.000000, 0, 0, -81, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2494526, 968, 2202, 5051, 1870.459400 +ATT, 0.00, -1.33, -2.89, -0.08, 0.00, 61.10, 51.10 +CTUN, 1000, 0.31, 2.20, 0.000000, 0, 0, -68, 1000, 0 +ATT, 0.00, -2.19, -2.70, -0.21, 0.00, 60.89, 51.10 +CTUN, 1000, 0.21, -0.33, 0.000000, 0, 0, -45, 1000, 0 +ATT, 0.00, -1.45, -2.70, 0.14, 0.00, 60.32, 51.10 +CTUN, 1000, 0.21, -1.88, 0.000000, 0, 0, 21, 1000, 0 +ATT, 0.00, -0.72, -2.80, 0.42, 0.00, 60.53, 51.10 +CTUN, 1000, 0.21, -0.60, 0.000000, 0, 0, 37, 1000, 0 +ATT, 0.00, -2.10, -2.89, 0.79, 0.00, 60.35, 51.10 +CTUN, 1000, 0.21, 1.17, 0.000000, 0, 0, 41, 1000, 0 +ATT, 0.00, -3.53, -3.17, 2.02, 0.00, 59.61, 51.10 +CTUN, 993, 0.20, 3.41, 0.000000, 0, 0, 46, 1000, 0 +ATT, 0.00, -2.38, -4.66, 2.60, 0.00, 58.83, 51.10 +CTUN, 911, 0.20, 3.96, 0.000000, 0, 1, 46, 921, 0 +ATT, 0.00, -1.15, -6.72, 2.16, 0.00, 58.08, 51.10 +CTUN, 871, 0.20, 3.94, 0.000000, 0, 0, 40, 873, 0 +ATT, 0.00, -0.66, -8.96, 0.18, 0.00, 57.54, 51.10 +CTUN, 857, 0.23, 4.06, 0.000000, 0, 0, 42, 857, 0 +ATT, 0.00, -0.06, -10.64, -2.83, 0.00, 57.02, 51.10 +CTUN, 857, 0.23, 3.97, 0.000000, 0, 1, 41, 858, 0 +DU32, 7, 166140 +CURR, 857, 2504073, 947, 2292, 5028, 1876.595700 +ATT, 0.00, 0.68, -10.82, -4.79, 0.00, 56.54, 51.10 +CTUN, 859, 0.32, 3.99, 0.000000, 0, 3, 37, 862, 0 +ATT, 0.00, 0.71, -11.10, -5.49, 0.00, 56.12, 51.10 +CTUN, 872, 0.32, 4.14, 0.000000, 0, 3, 34, 872, 0 +ATT, 1.03, 0.41, -10.92, -5.99, 0.00, 55.75, 51.10 +CTUN, 902, 0.41, 4.00, 0.000000, 0, 4, 37, 898, 0 +ATT, 1.12, 1.02, -10.82, -6.18, 0.00, 55.76, 51.10 +CTUN, 904, 0.41, 4.16, 0.000000, 0, 4, 36, 908, 0 +ATT, 1.03, 0.96, -10.92, -6.08, 0.00, 56.09, 51.10 +CTUN, 870, 0.48, 4.33, 0.000000, 0, 4, 30, 880, 0 +ATT, 0.84, 0.35, -11.76, -6.12, 0.00, 56.76, 51.10 +CTUN, 864, 0.48, 4.48, 0.000000, 0, 4, 24, 868, 0 +ATT, 0.84, 0.18, -11.76, -6.47, 0.00, 57.51, 51.10 +CTUN, 867, 0.54, 4.50, 0.000000, 0, 4, 16, 869, 0 +ATT, 0.28, 0.07, -10.92, -6.73, 0.00, 58.31, 51.10 +CTUN, 903, 0.54, 4.38, 0.000000, 0, 5, 13, 894, 0 +ATT, 0.00, 0.03, -7.18, -6.46, 0.00, 58.90, 51.10 +CTUN, 923, 0.59, 4.39, 0.000000, 0, 4, 4, 923, 0 +ATT, 0.00, 0.49, -4.85, -5.36, 0.00, 59.32, 51.10 +CTUN, 951, 0.59, 4.43, 0.000000, 0, 2, 2, 950, 0 +DU32, 7, 166140 +CURR, 951, 2512975, 969, 2074, 5051, 1882.644900 +ATT, 0.00, 0.87, -2.52, -3.26, 0.00, 59.49, 51.10 +CTUN, 971, 0.60, 4.39, 0.000000, 0, 0, -4, 961, 0 +ATT, 0.00, 0.82, -2.61, -1.06, 0.00, 59.59, 51.10 +CTUN, 979, 0.59, 4.32, 0.000000, 0, 0, -13, 979, 0 +ATT, 0.00, 0.94, -2.52, 1.00, 0.00, 59.59, 51.10 +CTUN, 982, 0.59, 4.42, 0.000000, 0, 0, -22, 981, 0 +ATT, 0.00, 1.22, -2.61, 2.09, 0.00, 59.54, 51.10 +CTUN, 993, 0.57, 4.34, 0.000000, 0, 1, -29, 992, 0 +ATT, 0.00, 1.93, -2.70, 2.58, 0.00, 59.35, 51.10 +CTUN, 1000, 0.57, 4.31, 0.000000, 0, 0, -38, 1000, 0 +ATT, 0.00, 2.21, -2.52, 2.84, 0.00, 59.28, 51.10 +CTUN, 1000, 0.50, 4.29, 0.000000, 0, 0, -47, 1000, 0 +ATT, 0.00, 2.64, -2.52, 2.61, 0.00, 59.16, 51.10 +CTUN, 1000, 0.50, 4.25, 0.000000, 0, 0, -51, 1000, 0 +ATT, 0.00, 2.48, -2.52, 2.22, 0.00, 58.90, 51.10 +CTUN, 1000, 0.41, 4.22, 0.000000, 0, 0, -56, 1000, 0 +ATT, 0.00, 1.67, -4.29, 1.92, 0.00, 58.58, 51.10 +CTUN, 1000, 0.41, 4.10, 0.000000, 0, 0, -57, 1000, 0 +ATT, 0.00, 0.01, -6.53, 0.76, 0.00, 58.42, 51.10 +CTUN, 1000, 0.29, 3.69, 0.000000, 0, 0, -49, 999, 0 +DU32, 7, 166140 +CURR, 1000, 2522879, 961, 2298, 5051, 1888.454200 +ATT, 0.00, -1.19, -7.84, -0.84, 0.00, 58.15, 51.10 +CTUN, 1000, 0.29, 2.75, 0.000000, 0, 0, -41, 1000, 0 +ATT, 0.00, -1.19, -8.30, -2.29, 0.00, 57.80, 51.10 +CTUN, 1000, 0.20, 0.98, 0.000000, 0, 0, -26, 1000, 0 +ATT, 0.00, -0.05, -8.21, -2.44, 0.00, 57.15, 51.10 +CTUN, 999, 0.21, 0.03, 0.000000, 0, 0, -10, 1000, 0 +ATT, 0.00, 0.12, -8.30, -2.08, 0.00, 56.44, 51.10 +CTUN, 1000, 0.21, -0.25, 0.000000, 0, 0, 5, 1000, 0 +ATT, 0.00, 0.32, -8.12, -1.23, 0.00, 55.44, 51.10 +CTUN, 1000, 0.21, 0.36, 0.000000, 0, 0, 19, 1000, 0 +ATT, 0.00, -0.76, -8.30, -0.58, 0.00, 54.12, 51.10 +CTUN, 1000, 0.21, 0.95, 0.000000, 0, 0, 34, 1000, 0 +ATT, 0.00, -2.09, -8.21, -1.41, 0.00, 52.71, 51.10 +CTUN, 1000, 0.21, 1.55, 0.000000, 0, 0, 53, 1000, 0 +ATT, 0.00, -0.90, -8.86, -2.20, 0.00, 51.67, 51.10 +CTUN, 1000, 0.20, 3.60, 0.000000, 0, 0, 63, 999, 0 +ATT, 0.00, -1.03, -10.92, -2.31, 0.00, 51.15, 51.10 +CTUN, 1000, 0.21, 4.24, 0.000000, 0, 0, 66, 1000, 0 +ATT, 0.00, -2.10, -10.82, -3.68, 0.00, 51.32, 51.10 +CTUN, 986, 0.21, 4.25, 0.000000, 0, 0, 71, 1000, 0 +DU32, 7, 166140 +CURR, 986, 2532879, 944, 2543, 5051, 1895.010900 +ATT, 0.00, -2.21, -9.14, -5.50, 0.00, 51.69, 51.10 +CTUN, 888, 0.29, 4.15, 0.000000, 0, 5, 76, 903, 0 +ATT, 0.00, -1.84, -8.77, -7.02, 0.00, 52.15, 51.10 +CTUN, 858, 0.29, 4.21, 0.000000, 0, 6, 81, 865, 0 +ATT, 0.00, -1.97, -8.21, -7.13, 0.00, 52.47, 51.10 +CTUN, 852, 0.44, 4.29, 0.000000, 0, 5, 84, 857, 0 +ATT, 0.00, -2.69, -8.12, -6.03, 0.00, 52.73, 51.10 +CTUN, 806, 0.44, 4.33, 0.000000, 0, 3, 86, 812, 0 +ATT, 0.00, -2.15, -8.30, -4.74, 0.00, 53.09, 51.10 +CTUN, 797, 0.63, 4.56, 0.000000, 0, 2, 83, 800, 0 +ATT, 0.00, -0.98, -8.12, -3.91, 0.00, 53.67, 51.10 +CTUN, 790, 0.63, 4.72, 0.000000, 0, 1, 77, 792, 0 +ATT, 0.00, 0.12, -8.02, -3.84, 0.00, 54.39, 51.10 +PM, 0, 0, 0, 0, 1000, 10492, 0, 0 +CTUN, 771, 0.79, 4.64, 0.000000, 0, 1, 67, 774, 0 +ATT, 0.00, 0.73, -8.12, -4.17, 0.00, 55.24, 51.10 +CTUN, 769, 0.79, 4.70, 0.000000, 0, 1, 59, 770, 0 +ATT, 0.00, 0.62, -6.81, -4.49, 0.00, 55.94, 51.10 +CTUN, 783, 0.94, 4.77, 0.000000, 0, 1, 51, 779, 0 +ATT, 0.00, 0.26, -5.97, -4.09, 0.00, 56.28, 51.10 +CTUN, 801, 0.94, 4.95, 0.000000, 0, 1, 41, 794, 0 +DU32, 7, 166140 +CURR, 813, 2541047, 965, 2045, 5051, 1901.108000 +ATT, 0.00, -0.16, -4.38, -2.97, 0.00, 56.26, 51.10 +CTUN, 852, 0.94, 4.97, 0.000000, 0, 0, 32, 843, 0 +ATT, 0.00, -0.20, -2.33, -1.17, 0.00, 55.90, 51.10 +CTUN, 874, 0.89, 4.97, 0.000000, 0, 0, 31, 874, 0 +ATT, 0.00, -0.08, -2.42, 1.19, 0.00, 55.26, 51.10 +CTUN, 906, 0.89, 5.06, 0.000000, 0, 0, 29, 904, 0 +ATT, 0.00, 0.00, -2.42, 3.17, 0.00, 54.44, 51.10 +CTUN, 910, 0.88, 5.06, 0.000000, 0, 1, 26, 910, 0 +ATT, 0.00, 0.06, -2.42, 4.28, 0.00, 53.42, 51.10 +CTUN, 911, 0.88, 5.11, 0.000000, 0, 2, 27, 913, 0 +ATT, 0.00, 0.17, -3.73, 4.39, 0.00, 52.31, 51.10 +CTUN, 909, 0.88, 5.20, 0.000000, 0, 2, 28, 910, 0 +ATT, 0.00, 0.17, -3.92, 3.65, 0.00, 51.23, 51.10 +CTUN, 909, 0.89, 5.20, 0.000000, 0, 1, 29, 908, 0 +ATT, 0.00, 0.01, -4.20, 2.50, 0.00, 50.26, 51.10 +CTUN, 857, 0.89, 5.21, 0.000000, 0, 0, 36, 865, 0 +ATT, 0.00, -0.09, -4.29, 1.81, 0.00, 49.40, 51.10 +CTUN, 834, 0.93, 5.19, 0.000000, 0, 0, 40, 840, 0 +ATT, 0.00, 0.12, -4.66, 1.53, 0.00, 48.61, 51.10 +CTUN, 775, 0.93, 5.24, 0.000000, 0, 0, 40, 789, 0 +DU32, 7, 166140 +CURR, 775, 2549818, 958, 2189, 5028, 1907.629300 +ATT, 0.00, 0.14, -4.76, 1.19, 0.00, 47.99, 51.10 +CTUN, 730, 1.00, 5.29, 0.000000, 0, 0, 38, 745, 0 +ATT, 0.00, 0.08, -4.57, 0.48, 0.00, 47.45, 51.10 +CTUN, 702, 1.00, 5.26, 0.000000, 0, 0, 24, 703, 0 +ATT, 0.00, 0.07, -4.57, -0.64, 0.00, 46.95, 51.10 +CTUN, 705, 1.07, 5.32, 0.000000, 0, 0, 10, 704, 0 +ATT, 0.00, 0.07, -4.76, -1.89, 0.00, 46.45, 51.10 +CTUN, 745, 1.07, 5.36, 0.000000, 0, 0, -9, 740, 0 +ATT, 0.00, -0.16, -4.57, -2.65, 0.00, 46.01, 51.10 +CTUN, 850, 1.13, 5.36, 0.000000, 0, 0, -23, 838, 0 +ATT, 0.00, -0.93, -4.48, -2.61, 0.00, 45.80, 51.10 +CTUN, 950, 1.13, 5.46, 0.000000, 0, 0, -26, 913, 0 +ATT, 0.00, -1.53, -4.38, -2.14, 0.00, 45.88, 51.10 +CTUN, 997, 1.13, 5.31, 0.000000, 0, 0, -22, 997, 0 +ATT, 0.00, -1.39, -4.38, -1.77, 0.00, 46.38, 51.10 +CTUN, 1000, 1.07, 5.30, 0.000000, 0, 0, -5, 1000, 0 +ATT, 0.00, -1.34, -4.38, -1.62, 0.00, 47.28, 51.10 +CTUN, 1000, 1.07, 5.34, 0.000000, 0, 0, 3, 1000, 0 +ATT, 0.00, -1.64, -4.20, -1.71, 0.00, 48.67, 51.10 +CTUN, 994, 1.02, 5.24, 0.000000, 0, 0, 10, 1000, 0 +DU32, 7, 166140 +CURR, 993, 2558414, 937, 2524, 5051, 1913.733900 +ATT, 0.00, -1.76, -4.38, -2.06, 0.00, 50.52, 51.10 +CTUN, 967, 1.02, 5.22, 0.000000, 0, 0, 16, 972, 0 +ATT, 0.00, -1.59, -4.20, -2.27, 0.00, 52.57, 51.10 +CTUN, 943, 1.02, 5.14, 0.000000, 0, 0, 21, 946, 0 +ATT, 0.00, -1.83, -3.92, -2.15, 0.00, 54.53, 51.10 +CTUN, 872, 1.02, 5.23, 0.000000, 0, 0, 22, 883, 0 +ATT, 0.28, -1.91, -2.52, -1.79, 0.00, 56.21, 51.10 +CTUN, 804, 1.02, 5.31, 0.000000, 0, 0, 20, 804, 0 +ATT, 1.78, -1.57, -2.52, -1.22, 0.00, 57.47, 51.10 +CTUN, 792, 1.06, 5.37, 0.000000, 0, 0, 17, 792, 0 +ATT, 2.34, -1.02, -2.24, -0.50, 0.00, 58.12, 51.10 +CTUN, 834, 1.06, 5.47, 0.000000, 0, 0, 8, 820, 0 +ATT, 3.46, -0.45, -2.70, 0.05, 0.00, 58.15, 51.10 +CTUN, 871, 1.08, 5.45, 0.000000, 0, 0, -1, 864, 0 +ATT, 6.09, -0.02, -2.24, 0.39, 0.00, 57.89, 51.10 +CTUN, 902, 1.08, 5.50, 0.000000, 0, 0, -7, 893, 0 +ATT, 6.37, 0.95, -2.05, 0.25, 0.00, 57.42, 51.10 +CTUN, 925, 1.08, 5.43, 0.000000, 0, 0, -8, 911, 0 +ATT, 6.37, 2.45, -2.05, 0.07, 0.00, 56.87, 51.10 +CTUN, 966, 1.08, 5.41, 0.000000, 0, 1, -5, 960, 0 +DU32, 7, 166140 +CURR, 966, 2567253, 955, 2319, 5051, 1919.991900 +ATT, 6.37, 3.60, -2.05, 0.15, 0.00, 56.26, 51.10 +CTUN, 980, 1.18, 5.30, 0.000000, 0, 1, -2, 980, 0 +ATT, 6.28, 4.09, -2.05, -0.15, 0.00, 55.66, 51.10 +CTUN, 980, 1.10, 5.44, 0.000000, 0, 2, -3, 984, 0 +ATT, 6.28, 3.85, -2.05, -0.91, 0.00, 54.97, 51.10 +CTUN, 975, 1.10, 5.51, 0.000000, 0, 2, 2, 977, 0 +ATT, 6.09, 3.87, -2.24, -1.79, 0.00, 54.18, 51.10 +CTUN, 973, 1.04, 5.50, 0.000000, 0, 2, 13, 975, 0 +ATT, 5.53, 4.70, -2.24, -1.89, 0.00, 53.30, 51.10 +CTUN, 972, 1.05, 5.44, 0.000000, 0, 3, 19, 976, 0 +ATT, 4.78, 5.61, -2.14, -1.31, 0.00, 52.37, 51.10 +CTUN, 958, 1.05, 5.43, 0.000000, 0, 4, 26, 966, 0 +ATT, 3.84, 5.92, -2.24, -0.67, 0.00, 51.24, 51.10 +CTUN, 890, 1.05, 5.47, 0.000000, 0, 3, 30, 933, 0 +ATT, 3.46, 4.93, -2.24, 0.07, 0.00, 49.98, 51.10 +CTUN, 857, 1.03, 5.49, 0.000000, 0, 1, 37, 864, 0 +ATT, 1.03, 3.60, -2.24, 0.36, 0.00, 48.62, 51.10 +CTUN, 857, 1.03, 5.39, 0.000000, 0, 1, 39, 858, 0 +ATT, 0.00, 2.58, -2.24, 0.33, 0.00, 47.34, 51.10 +CTUN, 857, 1.02, 5.35, 0.000000, 0, 0, 38, 857, 0 +DU32, 7, 166140 +CURR, 857, 2576638, 951, 2294, 5051, 1926.811600 +ATT, 0.00, 1.65, -2.24, 0.11, 0.00, 46.25, 51.10 +CTUN, 857, 1.03, 5.46, 0.000000, 0, 0, 40, 857, 0 +ATT, 0.00, 2.00, -2.42, 0.48, 0.00, 45.05, 51.10 +CTUN, 825, 1.03, 5.43, 0.000000, 0, 0, 38, 825, 0 +ATT, 0.00, 3.59, -3.08, 1.12, 0.00, 43.57, 51.10 +CTUN, 823, 1.04, 5.51, 0.000000, 0, 1, 39, 825, 0 +ATT, 0.00, 4.32, -2.52, 1.31, 0.00, 41.68, 51.10 +CTUN, 824, 1.04, 5.46, 0.000000, 0, 1, 35, 825, 0 +ATT, 0.00, 3.32, -2.42, 0.95, 0.00, 39.85, 49.85 +CTUN, 825, 1.06, 5.36, 0.000000, 0, 0, 30, 825, 0 +ATT, 0.00, 2.11, -3.26, 0.81, 0.00, 37.89, 47.89 +CTUN, 823, 1.06, 5.35, 0.000000, 0, 0, 27, 825, 0 +ATT, 0.00, 0.95, -3.26, 0.36, 0.00, 35.70, 45.70 +CTUN, 815, 1.08, 5.49, 0.000000, 0, 0, 21, 819, 0 +ATT, -1.42, 0.10, -3.26, -0.27, 0.00, 33.49, 43.49 +CTUN, 809, 1.08, 5.44, 0.000000, 0, 0, 15, 809, 0 +ATT, -3.31, 0.18, -3.26, -0.52, 0.00, 31.24, 41.24 +CTUN, 809, 1.10, 5.43, 0.000000, 0, 0, 12, 808, 0 +ATT, -3.22, -0.55, -3.26, -0.30, 0.00, 29.09, 39.09 +CTUN, 809, 1.08, 5.36, 0.000000, 0, 0, 2, 809, 0 +DU32, 7, 166140 +CURR, 809, 2584872, 962, 2092, 5028, 1932.868700 +ATT, -3.03, -1.55, -2.98, -0.52, 0.00, 27.15, 37.15 +CTUN, 809, 1.08, 5.53, 0.000000, 0, 0, -1, 809, 0 +ATT, -2.74, -1.99, -2.70, -1.24, 0.00, 25.49, 35.49 +CTUN, 815, 0.87, 5.33, 0.000000, 0, 0, -9, 809, 0 +ATT, -5.02, -2.13, -2.70, -2.06, 0.00, 24.00, 34.00 +CTUN, 843, 0.87, 5.37, 0.000000, 0, 1, -10, 837, 0 +ATT, -5.87, -2.94, -2.61, -2.68, 0.00, 22.65, 32.65 +CTUN, 880, 0.78, 5.39, 0.000000, 0, 2, -12, 871, 0 +ATT, -5.87, -5.98, -2.61, -2.89, 0.00, 21.54, 31.54 +CTUN, 908, 0.78, 5.36, 0.000000, 0, 7, -9, 914, 0 +ATT, -4.26, -8.36, -2.52, -2.91, 0.00, 20.58, 30.58 +CTUN, 911, 0.70, 5.23, 0.000000, 0, 9, -5, 920, 0 +ATT, -2.55, -7.06, -2.52, -3.25, 0.00, 19.73, 29.73 +CTUN, 910, 0.70, 5.25, 0.000000, 0, 5, 2, 915, 0 +ATT, -2.36, -4.08, -2.33, -3.39, 0.00, 19.19, 29.19 +CTUN, 906, 0.65, 5.09, 0.000000, 0, 2, 8, 909, 0 +ATT, -0.75, -1.87, -3.26, -2.94, 0.00, 19.11, 29.09 +CTUN, 864, 0.65, 5.08, 0.000000, 0, 1, 17, 865, 0 +ATT, 0.00, -0.45, -3.54, -2.37, 0.00, 19.45, 29.09 +CTUN, 853, 0.63, 5.19, 0.000000, 0, 0, 31, 856, 0 +DU32, 7, 166140 +CURR, 850, 2593570, 951, 2262, 5051, 1939.540500 +ATT, 0.00, 0.75, -3.26, -2.14, 0.00, 20.23, 29.09 +CTUN, 848, 0.63, 5.15, 0.000000, 0, 0, 30, 851, 0 +ATT, 0.00, 1.40, -2.98, -2.02, 0.00, 21.27, 29.09 +CTUN, 839, 0.63, 5.33, 0.000000, 0, 0, 29, 840, 0 +ATT, 0.00, 1.81, -3.08, -1.86, 0.00, 22.52, 29.09 +CTUN, 821, 0.63, 5.27, 0.000000, 0, 0, 25, 821, 0 +ATT, 0.00, 1.90, -3.08, -1.98, 0.00, 23.98, 29.09 +CTUN, 824, 0.63, 5.30, 0.000000, 0, 0, 17, 824, 0 +ATT, 0.00, 1.32, -2.80, -2.23, 0.00, 25.69, 29.09 +CTUN, 852, 0.65, 5.30, 0.000000, 0, 0, 15, 843, 0 +ATT, 0.00, 0.50, -2.61, -2.35, 0.00, 27.59, 29.09 +CTUN, 906, 0.65, 5.48, 0.000000, 0, 0, 8, 898, 0 +ATT, 0.00, 0.32, -2.70, -2.35, 0.00, 29.60, 29.09 +CTUN, 910, 0.65, 5.41, 0.000000, 0, 0, 8, 911, 0 +ATT, 0.00, 0.40, -2.70, -2.34, 0.00, 31.70, 29.09 +CTUN, 912, 0.65, 5.38, 0.000000, 0, 0, 8, 912, 0 +ATT, 0.00, 0.06, -2.70, -2.43, 0.00, 33.45, 29.09 +CTUN, 910, 0.65, 5.34, 0.000000, 0, 0, 7, 912, 0 +ATT, 0.00, -0.60, -2.61, -2.31, 0.00, 34.97, 29.09 +CTUN, 907, 0.64, 5.31, 0.000000, 0, 0, 9, 907, 0 +DU32, 7, 166140 +CURR, 904, 2602254, 958, 2247, 5051, 1945.855600 +ATT, 0.00, -0.88, -2.70, -1.77, 0.00, 36.39, 29.09 +CTUN, 888, 0.64, 5.32, 0.000000, 0, 0, 8, 888, 0 +ATT, 0.00, -0.83, -2.52, -1.04, 0.00, 37.68, 29.09 +CTUN, 888, 0.63, 5.37, 0.000000, 0, 0, 2, 888, 0 +ATT, 0.00, -0.47, -2.70, -0.73, 0.00, 38.79, 29.09 +CTUN, 888, 0.63, 5.31, 0.000000, 0, 0, -5, 888, 0 +ATT, 0.00, 0.00, -2.61, -1.28, 0.00, 39.65, 29.65 +CTUN, 888, 0.62, 5.42, 0.000000, 0, 0, -15, 888, 0 +ATT, 0.00, 0.72, -2.61, -2.20, 0.00, 40.26, 30.26 +CTUN, 904, 0.62, 5.41, 0.000000, 0, 0, -17, 904, 0 +ATT, 0.00, 1.28, -2.61, -2.43, 0.00, 40.58, 30.58 +CTUN, 922, 0.60, 5.49, 0.000000, 0, 0, -22, 918, 0 +ATT, 0.00, 1.29, -2.70, -1.92, 0.00, 40.49, 30.59 +CTUN, 959, 0.60, 5.34, 0.000000, 0, 0, -24, 946, 0 +ATT, 0.00, 0.58, -2.52, -1.38, 0.00, 40.02, 30.59 +CTUN, 995, 0.54, 5.17, 0.000000, 0, 0, -28, 980, 0 +ATT, 0.00, 0.46, -2.52, -1.13, 0.00, 39.25, 30.59 +CTUN, 1000, 0.54, 5.16, 0.000000, 0, 0, -29, 1000, 0 +ATT, 0.00, 0.54, -2.42, -0.88, 0.00, 38.12, 30.59 +CTUN, 1000, 0.47, 5.11, 0.000000, 0, 0, -32, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2611534, 942, 2364, 5051, 1951.930900 +ATT, 0.00, 0.48, -2.42, -0.82, 0.00, 36.67, 30.59 +CTUN, 1000, 0.47, 5.11, 0.000000, 0, 0, -31, 1000, 0 +ATT, 0.00, 0.54, -2.52, 0.00, 0.00, 35.05, 30.59 +CTUN, 1000, 0.47, 4.75, 0.000000, 0, 0, -26, 1000, 0 +ATT, 0.00, 0.63, -2.52, 1.43, 0.00, 33.36, 30.59 +CTUN, 1000, 0.53, 4.99, 0.000000, 0, 0, -23, 1000, 0 +ATT, -1.23, 0.83, -2.52, 1.93, 0.00, 31.95, 30.59 +CTUN, 1000, 0.47, 4.91, 0.000000, 0, 0, -16, 1000, 0 +ATT, -4.26, 1.31, -2.42, 2.20, 0.00, 30.60, 30.59 +CTUN, 1000, 0.47, 4.86, 0.000000, 0, 0, -9, 1000, 0 +ATT, -6.91, 0.68, -2.42, 2.91, 0.00, 29.53, 30.59 +CTUN, 1000, 0.43, 4.81, 0.000000, 0, 0, -6, 1000, 0 +ATT, -8.52, -1.98, -2.52, 3.54, 0.00, 28.72, 30.59 +CTUN, 1000, 0.43, 4.81, 0.000000, 0, 0, -1, 1000, 0 +ATT, -11.17, -4.15, -2.80, 3.77, 0.00, 28.11, 30.59 +CTUN, 999, 0.37, 4.90, 0.000000, 0, 0, 3, 1000, 0 +ATT, -10.51, -5.71, -3.17, 3.16, 0.00, 27.57, 30.59 +CTUN, 1000, 0.37, 4.91, 0.000000, 0, 0, 8, 1000, 0 +ATT, -8.81, -7.61, -4.57, 2.26, 0.00, 27.01, 30.59 +CTUN, 1000, 0.34, 4.87, 0.000000, 0, 0, 18, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2621532, 930, 2722, 5028, 1958.944800 +ATT, -7.48, -8.03, -4.85, 1.66, 0.00, 26.39, 30.59 +CTUN, 1000, 0.34, 5.10, 0.000000, 0, 0, 27, 1000, 0 +ATT, -4.26, -7.25, -7.56, 0.81, 0.00, 25.88, 30.59 +CTUN, 1000, 0.34, 5.12, 0.000000, 0, 0, 29, 1000, 0 +ATT, -1.32, -5.35, -10.45, -1.52, 0.00, 25.69, 30.59 +CTUN, 1000, 0.34, 5.11, 0.000000, 0, 0, 38, 1000, 0 +ATT, 0.00, -2.60, -10.64, -4.77, 0.00, 25.82, 30.59 +CTUN, 1000, 0.34, 4.97, 0.000000, 0, 0, 43, 1000, 0 +ATT, 0.00, -0.23, -10.64, -7.82, 0.00, 26.36, 30.59 +CTUN, 952, 0.39, 4.92, 0.000000, 0, 9, 51, 968, 0 +ATT, 0.00, 1.00, -9.61, -9.03, 0.00, 27.37, 30.59 +CTUN, 909, 0.39, 4.88, 0.000000, 0, 9, 57, 931, 0 +ATT, 0.00, 1.32, -7.84, -8.10, 0.00, 28.92, 30.59 +PM, 0, 0, 0, 0, 1000, 10460, 0, 0 +CTUN, 847, 0.48, 4.72, 0.000000, 0, 6, 63, 869, 0 +ATT, 0.00, 0.96, -6.72, -5.63, 0.00, 31.11, 30.59 +CTUN, 801, 0.48, 4.81, 0.000000, 0, 2, 61, 806, 0 +ATT, 0.00, -0.01, -6.53, -3.98, 0.00, 33.06, 30.59 +CTUN, 789, 0.66, 5.00, 0.000000, 0, 1, 57, 790, 0 +ATT, 0.00, -0.83, -6.06, -3.69, 0.00, 34.63, 30.59 +CTUN, 808, 0.66, 4.91, 0.000000, 0, 1, 45, 802, 0 +DU32, 7, 166140 +CURR, 813, 2630769, 965, 2000, 5051, 1965.754800 +ATT, 0.00, -0.84, -6.06, -3.68, 0.00, 35.83, 30.59 +CTUN, 857, 0.70, 4.99, 0.000000, 0, 1, 36, 854, 0 +ATT, 0.00, -0.95, -6.06, -3.05, 0.00, 36.51, 30.59 +CTUN, 909, 0.70, 4.94, 0.000000, 0, 0, 31, 908, 0 +ATT, 0.00, -1.85, -5.97, -1.84, 0.00, 36.75, 30.59 +CTUN, 911, 0.76, 5.04, 0.000000, 0, 0, 24, 910, 0 +ATT, 0.09, -2.08, -4.85, -0.79, 0.00, 36.72, 30.59 +CTUN, 932, 0.76, 5.13, 0.000000, 0, 0, 19, 932, 0 +ATT, 0.46, -1.87, -3.73, -0.63, 0.00, 36.48, 30.59 +CTUN, 946, 0.78, 5.14, 0.000000, 0, 0, 17, 946, 0 +ATT, 0.46, -1.44, -2.70, -0.91, 0.00, 36.35, 30.59 +CTUN, 946, 0.78, 5.26, 0.000000, 0, 0, 14, 948, 0 +ATT, 0.46, -0.85, -2.61, -0.36, 0.00, 36.47, 30.59 +CTUN, 946, 0.78, 5.18, 0.000000, 0, 0, 11, 946, 0 +ATT, 1.03, -0.54, -2.70, 1.16, 0.00, 36.94, 30.59 +CTUN, 946, 0.78, 5.14, 0.000000, 0, 0, 2, 946, 0 +ATT, 3.46, -0.32, -2.52, 2.31, 0.00, 37.70, 30.59 +CTUN, 947, 0.78, 5.19, 0.000000, 0, 0, -1, 945, 0 +ATT, 5.06, 0.53, -2.24, 2.70, 0.00, 38.49, 30.59 +CTUN, 979, 0.78, 5.00, 0.000000, 0, 0, -9, 963, 0 +DU32, 7, 166140 +CURR, 979, 2640044, 962, 2088, 5051, 1971.824000 +ATT, 3.65, 2.40, -2.05, 1.99, 0.00, 39.27, 30.59 +CTUN, 992, 0.79, 4.97, 0.000000, 0, 1, -14, 993, 0 +ATT, 3.37, 4.07, -1.49, 1.48, 0.00, 40.00, 30.59 +CTUN, 1000, 0.79, 5.01, 0.000000, 0, 0, -24, 1000, 0 +ATT, 2.90, 4.89, -1.40, 1.52, 0.00, 40.57, 30.59 +CTUN, 1000, 0.94, 5.03, 0.000000, 0, 0, -36, 1000, 0 +ATT, 2.53, 4.24, -1.40, 1.71, 0.00, 40.57, 30.65 +CTUN, 1000, 0.89, 5.05, 0.000000, 0, 0, -45, 1000, 0 +ATT, 0.09, 3.31, -2.24, 1.12, 0.00, 40.07, 30.65 +CTUN, 1000, 0.89, 5.02, 0.000000, 0, 0, -51, 1000, 0 +ATT, 0.00, 2.67, -2.61, 0.38, 0.00, 39.12, 30.65 +CTUN, 1000, 0.83, 4.92, 0.000000, 0, 0, -58, 1000, 0 +ATT, 0.00, 1.99, -3.26, 0.01, 0.00, 37.90, 30.65 +CTUN, 1000, 0.83, 4.94, 0.000000, 0, 0, -61, 1000, 0 +ATT, 0.00, 1.70, -3.26, 0.15, 0.00, 36.28, 30.65 +CTUN, 1000, 0.68, 4.92, 0.000000, 0, 0, -66, 1000, 0 +ATT, 0.00, 2.35, -3.92, 0.70, 0.00, 34.30, 30.65 +CTUN, 1000, 0.68, 4.96, 0.000000, 0, 0, -63, 1000, 0 +ATT, 0.00, 2.95, -4.85, 1.29, 0.00, 31.99, 30.65 +CTUN, 1000, 0.52, 4.75, 0.000000, 0, 0, -61, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2650031, 943, 2463, 5028, 1977.792600 +ATT, 0.00, 2.71, -5.78, 0.95, 0.00, 29.62, 30.65 +CTUN, 1000, 0.52, 4.39, 0.000000, 0, 0, -58, 1000, 0 +ATT, 0.00, 1.03, -6.16, -0.68, 0.00, 27.54, 30.65 +CTUN, 1000, 0.35, 4.40, 0.000000, 0, 0, -45, 1000, 0 +ATT, -4.35, 0.17, -4.29, -2.77, 0.00, 26.11, 30.65 +CTUN, 1000, 0.35, 4.15, 0.000000, 0, 0, -21, 1000, 0 +ATT, -8.81, 0.21, -4.38, -4.29, 0.00, 25.26, 30.65 +CTUN, 1000, 0.22, 3.78, 0.000000, 0, 0, 0, 1000, 0 +ATT, -9.00, -1.46, -4.20, -4.38, 0.00, 24.93, 30.65 +CTUN, 1000, 0.22, 3.73, 0.000000, 0, 0, 20, 1000, 0 +ATT, -8.05, -2.69, -3.08, -2.98, 0.00, 24.98, 30.65 +CTUN, 1000, 0.20, 3.81, 0.000000, 0, 0, 36, 1000, 0 +ATT, -7.67, -3.66, -2.98, -0.85, 0.00, 25.35, 30.65 +CTUN, 1000, 0.20, 3.75, 0.000000, 0, 0, 46, 1000, 0 +ATT, -6.72, -5.27, -3.08, 0.15, 0.00, 26.03, 30.65 +CTUN, 1000, 0.20, 4.11, 0.000000, 0, 1, 56, 1000, 0 +ATT, -1.51, -6.40, -4.85, 1.00, 0.00, 26.88, 30.65 +CTUN, 986, 0.20, 4.30, 0.000000, 0, 5, 61, 991, 0 +ATT, 0.00, -5.43, -5.69, 1.70, 0.00, 27.85, 30.65 +CTUN, 930, 0.20, 4.34, 0.000000, 0, 2, 60, 934, 0 +DU32, 7, 166140 +CURR, 930, 2659978, 943, 2260, 5028, 1985.000500 +ATT, 0.00, -2.47, -6.53, 1.49, 0.00, 29.09, 30.65 +CTUN, 913, 0.26, 4.19, 0.000000, 0, 0, 55, 913, 0 +ATT, 0.00, -0.54, -6.06, 0.42, 0.00, 30.14, 30.65 +CTUN, 909, 0.26, 4.41, 0.000000, 0, 0, 50, 909, 0 +ATT, 0.00, -0.18, -4.38, -0.77, 0.00, 30.86, 30.65 +CTUN, 938, 0.33, 4.35, 0.000000, 0, 0, 50, 926, 0 +ATT, 0.00, 0.47, -2.52, -1.05, 0.00, 31.19, 30.65 +CTUN, 983, 0.33, 4.53, 0.000000, 0, 0, 52, 979, 0 +ATT, 0.00, 0.99, -2.52, 0.53, 0.00, 31.40, 30.65 +CTUN, 1000, 0.42, 4.58, 0.000000, 0, 0, 47, 1000, 0 +ATT, 0.00, 0.52, -2.52, 2.55, 0.00, 31.76, 30.65 +CTUN, 1000, 0.42, 4.48, 0.000000, 0, 1, 39, 1000, 0 +ATT, 0.00, -0.54, -2.52, 3.52, 0.00, 32.45, 30.65 +CTUN, 1000, 0.49, 4.54, 0.000000, 0, 1, 34, 1000, 0 +ATT, 0.00, -1.30, -2.52, 3.28, 0.00, 33.35, 30.65 +CTUN, 999, 0.49, 4.69, 0.000000, 0, 0, 30, 1000, 0 +ATT, 0.00, -0.83, -2.89, 2.61, 0.00, 34.21, 30.65 +CTUN, 984, 0.55, 4.71, 0.000000, 0, 0, 25, 986, 0 +ATT, 0.00, -0.67, -4.57, 1.98, 0.00, 34.90, 30.65 +CTUN, 979, 0.55, 4.66, 0.000000, 0, 0, 18, 979, 0 +DU32, 7, 166140 +CURR, 980, 2669643, 950, 2175, 5051, 1991.250400 +ATT, 0.00, -1.07, -4.85, 0.84, 0.00, 35.44, 30.65 +CTUN, 982, 0.59, 4.65, 0.000000, 0, 0, 13, 979, 0 +ATT, 0.00, -1.21, -6.81, -0.64, 0.00, 35.89, 30.65 +CTUN, 1000, 0.59, 4.75, 0.000000, 0, 0, 8, 1000, 0 +ATT, 0.00, -1.30, -7.84, -1.89, 0.00, 36.26, 30.65 +CTUN, 1000, 0.59, 4.60, 0.000000, 0, 0, 0, 1000, 0 +ATT, 0.00, -1.55, -8.21, -3.62, 0.00, 36.61, 30.65 +CTUN, 1000, 0.59, 4.68, 0.000000, 0, 0, -7, 1000, 0 +ATT, 0.00, -1.44, -8.30, -5.65, 0.00, 36.93, 30.65 +CTUN, 1000, 0.59, 4.58, 0.000000, 0, 0, -11, 1000, 0 +ATT, 0.00, -1.11, -8.02, -6.65, 0.00, 37.02, 30.65 +CTUN, 1000, 0.56, 4.48, 0.000000, 0, 0, -18, 1000, 0 +ATT, 0.09, -1.01, -7.84, -6.54, 0.00, 37.02, 30.65 +CTUN, 1000, 0.56, 4.48, 0.000000, 0, 0, -23, 1000, 0 +ATT, 0.37, -1.64, -5.32, -5.86, 0.00, 36.85, 30.65 +CTUN, 1000, 0.51, 4.60, 0.000000, 0, 0, -27, 1000, 0 +ATT, 0.28, -2.25, -2.42, -4.63, 0.00, 36.52, 30.65 +CTUN, 1000, 0.51, 4.36, 0.000000, 0, 0, -26, 1000, 0 +ATT, 0.28, -2.04, -2.52, -2.31, 0.00, 36.08, 30.65 +CTUN, 1000, 0.44, 4.25, 0.000000, 0, 0, -27, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2679612, 956, 2137, 5051, 1997.391200 +ATT, 2.34, -1.43, -2.05, 0.55, 0.00, 35.49, 30.65 +CTUN, 1000, 0.44, 4.38, 0.000000, 0, 0, -34, 1000, 0 +ATT, 4.68, -0.12, -2.05, 2.64, 0.00, 34.93, 30.65 +CTUN, 1000, 0.37, 4.39, 0.000000, 0, 0, -35, 1000, 0 +ATT, 4.59, 1.86, -2.05, 3.81, 0.00, 34.36, 30.65 +CTUN, 1000, 0.37, 4.33, 0.000000, 0, 0, -34, 1000, 0 +ATT, 3.93, 3.81, -2.24, 4.23, 0.00, 33.86, 30.65 +CTUN, 1000, 0.27, 4.23, 0.000000, 0, 0, -35, 1000, 0 +ATT, 3.18, 4.46, -2.52, 3.46, 0.00, 33.42, 30.65 +CTUN, 1000, 0.27, 4.18, 0.000000, 0, 1, -32, 1000, 0 +ATT, 0.28, 2.87, -2.52, 2.23, 0.00, 33.15, 30.65 +CTUN, 1000, 0.20, 3.30, 0.000000, 0, 0, -22, 1000, 0 +ATT, 0.00, 0.81, -2.52, 1.90, 0.00, 33.04, 30.65 +CTUN, 1000, 0.20, 2.63, 0.000000, 0, 0, -7, 1000, 0 +ATT, 0.00, -0.68, -2.33, 1.61, 0.00, 33.11, 30.65 +CTUN, 1000, 0.20, 1.91, 0.000000, 0, 0, 4, 1000, 0 +ATT, 0.00, -1.45, -2.42, 1.08, 0.00, 33.33, 30.65 +CTUN, 999, 0.20, 2.46, 0.000000, 0, 0, 18, 1000, 0 +ATT, 0.00, -2.04, -2.24, 0.78, 0.00, 33.50, 30.65 +CTUN, 1000, 0.20, 3.14, 0.000000, 0, 0, 25, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2689612, 937, 2374, 5051, 2003.771500 +ATT, 0.00, -2.28, -2.24, 0.40, 0.00, 33.69, 30.65 +CTUN, 1000, 0.20, 3.43, 0.000000, 0, 0, 33, 1000, 0 +ATT, 0.00, -2.14, -2.52, 0.88, 0.00, 33.97, 30.65 +CTUN, 1000, 0.20, 3.79, 0.000000, 0, 0, 37, 1000, 0 +ATT, 0.65, -1.75, -3.26, 1.26, 0.00, 34.43, 30.65 +CTUN, 1000, 0.20, 4.19, 0.000000, 0, 0, 37, 1000, 0 +ATT, 2.90, -1.39, -3.92, 1.02, 0.00, 35.18, 30.65 +CTUN, 982, 0.20, 4.24, 0.000000, 0, 0, 37, 986, 0 +ATT, 3.18, -0.39, -3.92, -0.50, 0.00, 36.04, 30.65 +CTUN, 982, 0.25, 4.23, 0.000000, 0, 0, 36, 982, 0 +ATT, 3.18, 1.61, -3.92, -1.84, 0.00, 36.84, 30.65 +CTUN, 983, 0.25, 4.33, 0.000000, 0, 1, 28, 983, 0 +ATT, 6.28, 2.83, -3.92, -1.71, 0.00, 37.52, 30.65 +CTUN, 986, 0.33, 4.34, 0.000000, 0, 1, 20, 987, 0 +ATT, 6.56, 3.39, -3.73, -0.96, 0.00, 37.89, 30.65 +CTUN, 994, 0.33, 4.33, 0.000000, 0, 2, 13, 995, 0 +ATT, 6.56, 4.52, -2.52, -0.30, 0.00, 37.99, 30.65 +CTUN, 998, 0.39, 4.49, 0.000000, 0, 3, 5, 999, 0 +ATT, 6.28, 5.49, -2.52, -0.12, 0.00, 37.85, 30.65 +CTUN, 999, 0.39, 4.56, 0.000000, 0, 1, -2, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2699548, 947, 2181, 5051, 2009.879200 +ATT, 3.00, 5.50, -2.80, -0.35, 0.00, 37.55, 30.65 +CTUN, 1000, 0.43, 4.53, 0.000000, 0, 1, -9, 1000, 0 +ATT, 0.00, 4.70, -3.73, -0.64, 0.00, 37.30, 30.65 +CTUN, 1000, 0.43, 4.58, 0.000000, 0, 0, -18, 1000, 0 +ATT, 0.00, 2.36, -4.38, -1.09, 0.00, 37.11, 30.65 +CTUN, 1000, 0.43, 4.38, 0.000000, 0, 0, -22, 1000, 0 +ATT, 0.00, -0.18, -4.85, -1.62, 0.00, 36.93, 30.65 +CTUN, 999, 0.43, 4.50, 0.000000, 0, 0, -24, 999, 0 +ATT, 0.00, -1.58, -4.76, -1.79, 0.00, 36.57, 30.65 +CTUN, 1000, 0.43, 4.42, 0.000000, 0, 0, -26, 1000, 0 +ATT, 0.00, -1.51, -4.76, -1.64, 0.00, 35.98, 30.65 +CTUN, 999, 0.41, 4.38, 0.000000, 0, 0, -27, 999, 0 +ATT, 0.00, -1.23, -4.76, -1.54, 0.00, 35.21, 30.65 +CTUN, 1000, 0.41, 4.46, 0.000000, 0, 0, -24, 1000, 0 +ATT, 0.00, -1.16, -4.85, -1.62, 0.00, 34.31, 30.65 +CTUN, 999, 0.38, 4.40, 0.000000, 0, 0, -22, 999, 0 +ATT, 0.00, -0.93, -4.20, -1.42, 0.00, 33.34, 30.65 +CTUN, 1000, 0.38, 4.54, 0.000000, 0, 0, -19, 1000, 0 +ATT, 0.00, -0.92, -2.24, -1.20, 0.00, 32.38, 30.65 +CTUN, 999, 0.34, 4.45, 0.000000, 0, 0, -14, 1000, 0 +DU32, 7, 166140 +CURR, 999, 2709548, 936, 2532, 5028, 2016.295000 +ATT, 0.00, -1.21, -2.05, -0.26, 0.00, 31.40, 30.65 +CTUN, 1000, 0.34, 4.49, 0.000000, 0, 0, -14, 1000, 0 +ATT, 0.00, -0.88, -2.24, 0.68, 0.00, 30.48, 30.65 +CTUN, 999, 0.32, 4.34, 0.000000, 0, 0, -11, 1000, 0 +ATT, 0.00, -0.10, -2.14, 1.24, 0.00, 29.76, 30.65 +CTUN, 1000, 0.32, 4.53, 0.000000, 0, 0, -7, 1000, 0 +ATT, 0.00, 0.30, -2.24, 1.69, 0.00, 29.11, 30.65 +CTUN, 1000, 0.30, 4.37, 0.000000, 0, 0, -3, 1000, 0 +ATT, 0.00, -0.06, -2.24, 1.58, 0.00, 28.54, 30.65 +CTUN, 1000, 0.30, 4.36, 0.000000, 0, 0, 1, 1000, 0 +ATT, 0.00, -0.46, -3.64, 1.30, 0.00, 28.06, 30.65 +CTUN, 1000, 0.30, 4.33, 0.000000, 0, 0, 9, 1000, 0 +ATT, 0.00, -0.40, -4.76, 0.41, 0.00, 27.64, 30.65 +CTUN, 1000, 0.31, 4.32, 0.000000, 0, 0, 14, 1000, 0 +ATT, 0.00, -0.20, -6.44, -1.56, 0.00, 27.25, 30.65 +CTUN, 1000, 0.31, 4.46, 0.000000, 0, 0, 24, 1000, 0 +ATT, 0.00, 0.00, -6.72, -2.67, 0.00, 26.87, 30.65 +CTUN, 1000, 0.36, 4.39, 0.000000, 0, 0, 30, 1000, 0 +ATT, 0.00, -0.11, -7.84, -3.30, 0.00, 26.53, 30.65 +CTUN, 999, 0.36, 4.44, 0.000000, 0, 0, 37, 1000, 0 +DU32, 7, 166140 +CURR, 999, 2719548, 924, 2655, 5051, 2023.431900 +ATT, 0.00, -0.53, -7.65, -3.53, 0.00, 26.43, 30.65 +CTUN, 1000, 0.42, 4.61, 0.000000, 0, 0, 45, 1000, 0 +ATT, 0.00, -0.92, -6.81, -3.35, 0.00, 26.42, 30.65 +CTUN, 982, 0.42, 4.66, 0.000000, 0, 1, 50, 990, 0 +ATT, 0.00, -0.98, -6.81, -2.90, 0.00, 26.48, 30.65 +CTUN, 977, 0.51, 4.72, 0.000000, 0, 0, 55, 979, 0 +ATT, 0.00, -0.89, -6.81, -2.26, 0.00, 26.56, 30.65 +CTUN, 951, 0.51, 4.82, 0.000000, 0, 0, 56, 953, 0 +ATT, 0.00, -0.73, -6.72, -1.73, 0.00, 26.56, 30.65 +CTUN, 928, 0.63, 4.88, 0.000000, 0, 0, 59, 928, 0 +ATT, 0.00, -0.68, -7.18, -1.71, 0.00, 26.37, 30.65 +CTUN, 902, 0.63, 4.95, 0.000000, 0, 0, 62, 902, 0 +ATT, 0.00, -0.08, -7.56, -1.99, 0.00, 25.96, 30.65 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 860, 0.77, 4.99, 0.000000, 0, 0, 65, 860, 0 +ATT, 0.00, 0.94, -7.84, -2.59, 0.00, 25.52, 30.65 +CTUN, 825, 0.77, 5.13, 0.000000, 0, 1, 66, 835, 0 +ATT, 0.00, 1.70, -7.84, -3.36, 0.00, 25.27, 30.65 +CTUN, 797, 0.92, 5.19, 0.000000, 0, 1, 61, 798, 0 +ATT, 0.00, 1.73, -7.84, -4.15, 0.00, 25.27, 30.65 +CTUN, 746, 0.92, 5.21, 0.000000, 0, 2, 53, 748, 0 +DU32, 7, 166140 +CURR, 746, 2728646, 961, 1949, 5051, 2030.237800 +ATT, 0.00, 1.70, -8.02, -4.68, 0.00, 25.44, 30.65 +CTUN, 735, 1.07, 5.29, 0.000000, 0, 2, 36, 740, 0 +ATT, 0.00, 1.67, -7.93, -5.02, 0.00, 25.72, 30.65 +CTUN, 737, 1.07, 5.35, 0.000000, 0, 2, 23, 739, 0 +ATT, 0.00, 1.40, -7.84, -5.32, 0.00, 26.16, 30.65 +CTUN, 777, 1.20, 5.30, 0.000000, 0, 3, 2, 770, 0 +ATT, 0.00, 1.02, -7.74, -5.46, 0.00, 26.66, 30.65 +CTUN, 877, 1.20, 5.36, 0.000000, 0, 3, -10, 824, 0 +ATT, 0.00, 0.51, -7.37, -5.18, 0.00, 27.25, 30.65 +CTUN, 939, 1.26, 5.34, 0.000000, 0, 2, -21, 941, 0 +ATT, 0.00, -0.13, -6.72, -4.52, 0.00, 28.00, 30.65 +CTUN, 998, 1.26, 5.31, 0.000000, 0, 2, -17, 1000, 0 +ATT, 0.00, -0.61, -6.81, -3.55, 0.00, 28.87, 30.65 +CTUN, 1000, 1.26, 5.52, 0.000000, 0, 0, -15, 1000, 0 +ATT, 0.00, -0.72, -6.72, -2.57, 0.00, 29.80, 30.65 +CTUN, 1000, 1.26, 5.41, 0.000000, 0, 0, -9, 1000, 0 +ATT, 0.00, -0.46, -6.81, -1.98, 0.00, 30.85, 30.65 +CTUN, 1000, 1.26, 5.54, 0.000000, 0, 0, -11, 1000, 0 +ATT, 0.00, -0.42, -6.72, -1.92, 0.00, 31.88, 30.65 +CTUN, 999, 1.26, 5.48, 0.000000, 0, 0, -8, 999, 0 +DU32, 7, 166140 +CURR, 979, 2737595, 946, 2302, 5051, 2036.258400 +ATT, 0.00, -0.51, -6.81, -2.20, 0.00, 32.83, 30.65 +CTUN, 944, 1.26, 5.49, 0.000000, 0, 0, -11, 946, 0 +ATT, 0.00, -0.35, -6.16, -2.59, 0.00, 33.68, 30.65 +CTUN, 954, 1.26, 5.56, 0.000000, 0, 0, -9, 954, 0 +ATT, 1.03, -0.36, -4.57, -2.43, 0.00, 34.45, 30.65 +CTUN, 993, 1.28, 5.58, 0.000000, 0, 0, -12, 984, 0 +ATT, 2.81, -0.49, -3.26, -1.62, 0.00, 35.21, 30.65 +CTUN, 999, 1.28, 5.59, 0.000000, 0, 0, -10, 999, 0 +ATT, 6.37, 0.70, -2.14, -0.44, 0.00, 36.00, 30.65 +CTUN, 1000, 1.28, 5.57, 0.000000, 0, 0, -15, 1000, 0 +ATT, 7.50, 3.10, -2.24, 0.73, 0.00, 36.67, 30.65 +CTUN, 1000, 1.28, 5.66, 0.000000, 0, 0, -20, 1000, 0 +ATT, 7.40, 5.74, -2.24, 1.30, 0.00, 37.27, 30.65 +CTUN, 1000, 1.28, 5.64, 0.000000, 0, 0, -27, 1000, 0 +ATT, 6.28, 7.36, -2.14, 1.25, 0.00, 37.63, 30.65 +CTUN, 1000, 1.27, 5.70, 0.000000, 0, 0, -34, 1000, 0 +ATT, 1.31, 7.44, -2.24, 0.59, 0.00, 37.75, 30.65 +CTUN, 1000, 1.27, 5.52, 0.000000, 0, 0, -41, 1000, 0 +ATT, 0.00, 5.57, -2.05, -0.40, 0.00, 37.59, 30.65 +CTUN, 999, 1.23, 5.61, 0.000000, 0, 0, -46, 1000, 0 +DU32, 7, 166140 +CURR, 999, 2747472, 939, 2316, 5028, 2042.300800 +ATT, 0.00, 2.31, -1.68, -1.19, 0.00, 37.18, 30.65 +CTUN, 999, 1.23, 5.47, 0.000000, 0, 0, -42, 999, 0 +ATT, 0.00, 0.31, -2.52, -0.91, 0.00, 36.58, 30.65 +CTUN, 1000, 1.17, 5.41, 0.000000, 0, 0, -39, 1000, 0 +ATT, -0.94, 0.18, -2.70, 0.04, 0.00, 35.56, 30.65 +CTUN, 1000, 1.17, 5.33, 0.000000, 0, 0, -39, 1000, 0 +ATT, -5.49, 0.28, -2.61, 0.61, 0.00, 34.24, 30.65 +CTUN, 1000, 1.02, 5.24, 0.000000, 0, 0, -38, 1000, 0 +ATT, -6.72, -0.89, -2.70, 0.70, 0.00, 32.82, 30.65 +CTUN, 1000, 1.02, 5.22, 0.000000, 0, 0, -37, 1000, 0 +ATT, -6.72, -3.47, -2.61, 0.36, 0.00, 31.27, 30.65 +CTUN, 1000, 0.94, 5.17, 0.000000, 0, 0, -29, 1000, 0 +ATT, -6.91, -5.51, -2.61, 0.02, 0.00, 29.97, 30.65 +CTUN, 1000, 0.94, 5.16, 0.000000, 0, 0, -23, 1000, 0 +ATT, -6.63, -6.48, -2.70, 0.08, 0.00, 29.03, 30.65 +CTUN, 1000, 0.75, 5.19, 0.000000, 0, 0, -16, 1000, 0 +ATT, -6.25, -6.65, -2.61, 0.39, 0.00, 28.59, 30.65 +CTUN, 1000, 0.75, 5.04, 0.000000, 0, 1, -14, 1000, 0 +ATT, -1.42, -6.40, -3.08, 0.40, 0.00, 28.77, 30.65 +CTUN, 1000, 0.68, 5.16, 0.000000, 0, 1, -6, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2757469, 925, 2566, 5051, 2049.138200 +ATT, 0.00, -4.59, -3.26, 0.30, 0.00, 29.49, 30.65 +CTUN, 1000, 0.68, 5.23, 0.000000, 0, 0, -7, 1000, 0 +ATT, 0.00, -1.06, -2.42, 0.37, 0.00, 30.58, 30.65 +CTUN, 999, 0.68, 5.19, 0.000000, 0, 0, -8, 999, 0 +ATT, 0.00, 1.37, -2.42, 0.14, 4.32, 31.93, 31.57 +CTUN, 999, 0.77, 5.14, 0.000000, 0, 0, -10, 999, 0 +ATT, 0.00, 1.77, -2.52, -0.42, 7.88, 33.64, 34.39 +CTUN, 1000, 0.77, 5.23, 0.000000, 0, 0, -8, 1000, 0 +ATT, 0.00, 1.69, -2.52, -0.90, 9.51, 36.04, 38.41 +CTUN, 1000, 0.89, 5.12, 0.000000, 0, 0, 0, 999, 0 +ATT, 0.00, 1.87, -2.52, -0.89, 10.96, 39.27, 43.04 +CTUN, 1000, 0.89, 5.13, 0.000000, 0, 0, 9, 1000, 0 +ATT, 0.00, 2.00, -2.52, -0.46, 10.96, 43.26, 47.92 +CTUN, 1000, 0.89, 5.00, 0.000000, 0, 0, 17, 999, 0 +ATT, 0.00, 1.96, -2.52, -0.18, 11.15, 48.06, 52.83 +CTUN, 1000, 0.89, 5.05, 0.000000, 0, 0, 24, 1000, 0 +ATT, 0.00, 1.72, -2.52, -0.11, 9.51, 53.42, 57.42 +CTUN, 1000, 0.91, 5.15, 0.000000, 0, 0, 30, 999, 0 +ATT, 0.00, 1.25, -3.26, -0.29, 8.26, 59.24, 61.50 +CTUN, 946, 0.91, 5.17, 0.000000, 0, 0, 30, 977, 0 +DU32, 7, 166140 +CURR, 946, 2767466, 935, 2323, 5051, 2056.042000 +ATT, 0.00, 0.68, -3.26, -0.60, 7.30, 65.17, 64.80 +CTUN, 907, 0.91, 5.22, 0.000000, 0, 0, 29, 909, 0 +ATT, 0.00, 0.77, -3.26, -1.22, 5.09, 70.81, 67.51 +CTUN, 860, 0.91, 5.28, 0.000000, 0, 0, 19, 871, 0 +ATT, 0.00, 1.25, -3.26, -1.67, 0.00, 75.75, 68.13 +CTUN, 832, 0.91, 5.34, 0.000000, 0, 0, 5, 843, 0 +ATT, 0.00, 1.39, -3.08, -2.01, 0.00, 79.60, 69.60 +CTUN, 823, 0.91, 5.23, 0.000000, 0, 0, -11, 823, 0 +ATT, 0.00, 1.32, -2.70, -2.35, 0.00, 82.52, 72.52 +CTUN, 884, 0.93, 5.33, 0.000000, 0, 0, -28, 884, 0 +ATT, 0.00, 0.86, -2.52, -2.18, 0.00, 84.68, 74.68 +CTUN, 973, 0.91, 5.28, 0.000000, 0, 0, -42, 946, 0 +ATT, 0.00, 0.40, -2.52, -1.65, 0.00, 86.43, 76.43 +CTUN, 1000, 0.91, 5.38, 0.000000, 0, 0, -58, 1000, 0 +ATT, 0.00, -0.09, -2.24, -1.02, 0.00, 87.87, 77.87 +CTUN, 1000, 0.85, 5.43, 0.000000, 0, 0, -71, 1000, 0 +ATT, 0.00, -0.48, -2.24, -0.61, 0.00, 89.10, 79.10 +CTUN, 1000, 0.85, 5.38, 0.000000, 0, 0, -80, 1000, 0 +ATT, 0.00, -0.23, -2.24, 0.22, 0.00, 89.94, 79.94 +CTUN, 1000, 0.75, 5.15, 0.000000, 0, 0, -88, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2776727, 962, 1893, 5051, 2061.313500 +ATT, -3.97, 0.03, -1.30, 0.59, 0.00, 90.41, 80.41 +CTUN, 1000, 0.75, 4.94, 0.000000, 0, 0, -100, 1000, 0 +ATT, -7.67, -0.99, 0.00, 0.20, 0.00, 90.52, 80.55 +CTUN, 1000, 0.72, 4.84, 0.000000, 0, 0, -103, 1000, 0 +ATT, -8.81, -3.68, 0.37, 0.50, 0.00, 90.18, 80.55 +CTUN, 1000, 0.72, 4.78, 0.000000, 0, 0, -101, 1000, 0 +ATT, -12.97, -6.19, 8.02, 2.07, 0.00, 89.27, 80.55 +CTUN, 1000, 0.52, 4.75, 0.000000, 0, 0, -101, 1000, 0 +ATT, -12.78, -8.40, 9.14, 5.14, 0.00, 87.78, 80.55 +CTUN, 1000, 0.52, 4.55, 0.000000, 0, 0, -96, 1000, 0 +ATT, -7.48, -9.88, 4.20, 9.06, 0.00, 86.10, 80.55 +CTUN, 1000, 0.31, 4.04, 0.000000, 0, 0, -96, 1000, 0 +ATT, -4.54, -9.00, 0.56, 11.49, 0.00, 84.74, 80.55 +CTUN, 1000, 0.31, 1.15, 0.000000, 0, 0, -47, 1000, 0 +ATT, -1.80, -2.36, 0.00, -4.70, 0.00, 85.43, 80.55 +CTUN, 1000, 0.31, 0.58, 0.000000, 0, 0, 36, 1000, 0 +ATT, 0.00, 1.49, -1.58, 1.29, 0.00, 84.54, 80.55 +CTUN, 1000, 1.97, 2.15, 0.000000, 0, 0, 21, 1000, 0 +ATT, 0.00, 2.02, -3.26, 4.71, 0.00, 83.56, 80.55 +CTUN, 1000, 0.75, 1.83, 0.000000, 0, 1, 15, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2786726, 920, 2549, 5028, 2067.000000 +ATT, 0.00, -0.59, -2.61, 2.61, 0.00, 82.39, 80.55 +CTUN, 1000, 0.75, 2.06, 0.000000, 0, 0, 28, 1000, 0 +ATT, 0.00, -1.98, -2.52, 0.02, 0.00, 81.49, 80.55 +CTUN, 1000, 0.21, 3.26, 0.000000, 0, 0, 45, 1000, 0 +ATT, 0.00, -0.93, 0.00, -0.34, 0.00, 80.86, 80.55 +CTUN, 1000, 0.21, 3.93, 0.000000, 0, 0, 56, 1000, 0 +ATT, -3.97, 0.10, 0.00, 2.56, 0.00, 80.41, 80.55 +CTUN, 1000, 0.21, 4.44, 0.000000, 0, 0, 53, 1000, 0 +ATT, 0.00, -0.63, -2.24, 5.52, 0.00, 80.24, 80.55 +CTUN, 1000, 0.22, 4.38, 0.000000, 0, 0, 48, 1000, 0 +ATT, 0.00, -1.42, -3.26, 5.03, 0.00, 80.57, 80.55 +CTUN, 999, 0.22, 4.65, 0.000000, 0, 1, 41, 1000, 0 +ATT, 0.00, -1.76, -5.69, 2.13, 0.00, 81.23, 80.55 +CTUN, 996, 0.31, 4.60, 0.000000, 0, 0, 37, 998, 0 +ATT, 0.00, -0.70, -6.53, -1.28, 0.00, 81.81, 80.55 +CTUN, 997, 0.31, 4.69, 0.000000, 0, 0, 38, 996, 0 +ATT, 0.00, 0.94, -6.53, -3.35, 0.00, 82.19, 80.55 +CTUN, 1000, 0.41, 4.71, 0.000000, 0, 0, 29, 1000, 0 +ATT, 0.00, 0.68, -6.34, -4.65, 0.00, 82.47, 80.55 +CTUN, 999, 0.41, 4.81, 0.000000, 0, 0, 28, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2796722, 935, 2402, 5051, 2073.595500 +ATT, 0.00, -0.97, -6.81, -5.65, 0.00, 82.67, 80.55 +CTUN, 1000, 0.48, 4.79, 0.000000, 0, 0, 26, 1000, 0 +ATT, 0.00, -2.01, -8.12, -6.17, 0.00, 82.71, 80.55 +CTUN, 999, 0.48, 4.81, 0.000000, 0, 0, 24, 1000, 0 +ATT, -0.85, -1.45, -8.21, -6.05, 0.00, 82.66, 80.55 +CTUN, 1000, 0.54, 4.80, 0.000000, 0, 0, 20, 1000, 0 +ATT, -3.50, -0.51, -7.56, -5.38, 0.00, 82.50, 80.55 +CTUN, 999, 0.54, 5.03, 0.000000, 0, 0, 18, 1000, 0 +ATT, -4.16, -2.23, -4.10, -4.82, 0.00, 82.27, 80.55 +CTUN, 1000, 0.60, 4.84, 0.000000, 0, 1, 16, 1000, 0 +ATT, -5.58, -4.53, -3.36, -4.83, 0.00, 81.93, 80.55 +CTUN, 999, 0.60, 4.93, 0.000000, 0, 0, 18, 1000, 0 +ATT, -6.25, -5.77, -2.42, -3.62, 0.00, 81.42, 80.55 +CTUN, 1000, 0.64, 5.06, 0.000000, 0, 1, 17, 1000, 0 +ATT, -6.53, -6.17, -2.42, -0.49, 0.00, 80.76, 80.55 +CTUN, 999, 0.64, 5.00, 0.000000, 0, 0, 13, 1000, 0 +ATT, -5.11, -6.75, -2.42, 1.96, 0.00, 80.25, 80.55 +CTUN, 1000, 0.69, 4.97, 0.000000, 0, 1, 7, 1000, 0 +ATT, -2.55, -6.64, -2.52, 2.40, 0.00, 80.10, 80.55 +CTUN, 999, 0.69, 5.07, 0.000000, 0, 0, 4, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2806722, 934, 2391, 5028, 2080.121800 +ATT, -0.85, -5.45, -3.26, 2.08, 0.00, 80.29, 80.55 +CTUN, 1000, 0.71, 5.06, 0.000000, 0, 0, 0, 1000, 0 +ATT, 0.00, -3.71, -4.38, 1.87, 0.00, 80.69, 80.55 +CTUN, 1000, 0.71, 5.17, 0.000000, 0, 0, -5, 1000, 0 +ATT, 0.00, -2.30, -4.57, 1.44, 0.00, 81.22, 80.55 +CTUN, 1000, 0.73, 5.09, 0.000000, 0, 0, -15, 1000, 0 +ATT, 0.00, -1.57, -3.45, -0.13, 0.00, 81.86, 80.55 +CTUN, 1000, 0.72, 5.12, 0.000000, 0, 0, -16, 1000, 0 +ATT, 0.00, -1.32, -2.61, -1.35, 0.00, 82.42, 80.55 +CTUN, 1000, 0.72, 5.22, 0.000000, 0, 0, -20, 1000, 0 +ATT, 0.00, -1.59, -2.70, -1.44, 0.00, 83.03, 80.55 +CTUN, 1000, 0.71, 5.03, 0.000000, 0, 0, -23, 1000, 0 +ATT, 0.46, -2.30, -2.42, -1.45, 0.00, 83.83, 80.55 +CTUN, 999, 0.71, 4.98, 0.000000, 0, 0, -26, 1000, 0 +ATT, 1.40, -3.15, -2.42, -1.61, 0.00, 84.66, 80.55 +CTUN, 1000, 0.69, 5.07, 0.000000, 0, 0, -28, 1000, 0 +ATT, 1.78, -3.07, -2.70, -1.86, 0.00, 85.62, 80.55 +CTUN, 1000, 0.69, 5.08, 0.000000, 0, 0, -30, 1000, 0 +ATT, 2.34, -1.95, -2.70, -2.08, -2.73, 86.46, 79.98 +CTUN, 1000, 0.66, 5.02, 0.000000, 0, 0, -36, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2816722, 946, 2039, 5051, 2086.430200 +ATT, 2.90, -0.81, -2.70, -2.24, -3.30, 86.93, 78.54 +CTUN, 1000, 0.66, 4.95, 0.000000, 0, 0, -45, 1000, 0 +ATT, 3.75, 0.11, -2.52, -2.33, -4.33, 86.72, 76.78 +CTUN, 1000, 0.61, 4.88, 0.000000, 0, 0, -55, 1000, 0 +ATT, 5.43, 0.61, -2.70, -2.29, -4.43, 85.81, 75.81 +CTUN, 1000, 0.61, 4.76, 0.000000, 0, 0, -61, 1000, 0 +ATT, 5.34, 1.36, -2.61, -2.02, -4.43, 84.29, 74.29 +CTUN, 1000, 0.53, 4.65, 0.000000, 0, 0, -69, 1000, 0 +ATT, 5.43, 2.55, -3.08, -1.76, -4.52, 82.24, 72.30 +CTUN, 1000, 0.53, 4.78, 0.000000, 0, 0, -77, 1000, 0 +ATT, 5.06, 3.71, -3.92, -0.81, -4.52, 79.75, 70.19 +CTUN, 1000, 0.42, 4.75, 0.000000, 0, 0, -83, 1000, 0 +ATT, 4.96, 4.11, -4.38, 0.20, -4.43, 76.90, 68.13 +PM, 0, 0, 0, 0, 1000, 10480, 0, 0 +CTUN, 1000, 0.42, 4.43, 0.000000, 0, 0, -90, 1000, 0 +ATT, 3.75, 3.86, -5.69, -0.04, -4.33, 73.64, 66.13 +CTUN, 1000, 0.28, 3.93, 0.000000, 0, 1, -85, 1000, 0 +ATT, 3.18, 4.24, -7.65, -0.94, -3.39, 70.19, 64.35 +CTUN, 1000, 0.28, 2.20, 0.000000, 0, 0, -73, 1000, 0 +ATT, 0.65, 4.33, -10.92, -2.50, -2.73, 66.74, 62.96 +CTUN, 1000, 0.21, -0.58, 0.000000, 0, 0, -36, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2826721, 923, 2428, 5028, 2092.365700 +ATT, 0.00, -1.57, -10.82, -0.55, -2.07, 62.73, 61.82 +CTUN, 1000, 0.23, -1.41, 0.000000, 0, 0, 7, 1000, 0 +ATT, 0.09, 0.22, -10.82, -1.58, -1.98, 59.97, 60.91 +CTUN, 1000, 0.21, -0.10, 0.000000, 0, 0, 18, 1000, 0 +ATT, 0.00, -0.18, -10.82, -1.93, -1.79, 57.31, 60.04 +CTUN, 1000, 0.21, 1.38, 0.000000, 0, 0, 33, 1000, 0 +ATT, 0.00, 0.52, -10.64, -3.32, -1.79, 55.06, 59.14 +CTUN, 1000, 0.21, 2.60, 0.000000, 0, 1, 46, 1000, 0 +ATT, 0.00, 2.02, -10.64, -4.19, -1.22, 53.28, 58.37 +CTUN, 1000, 0.21, 4.34, 0.000000, 0, 0, 53, 1000, 0 +ATT, 0.00, 2.24, -10.82, -4.89, 0.00, 51.92, 58.31 +CTUN, 1000, 0.21, 4.51, 0.000000, 0, 1, 62, 1000, 0 +ATT, 0.00, 1.90, -12.88, -5.19, 0.00, 51.24, 58.31 +CTUN, 1000, 0.25, 4.55, 0.000000, 0, 0, 67, 1000, 0 +ATT, 0.00, 1.23, -14.28, -5.66, 0.00, 51.17, 58.31 +CTUN, 989, 0.25, 4.72, 0.000000, 0, 5, 72, 998, 0 +ATT, 0.00, 0.98, -14.56, -6.72, 0.00, 51.79, 58.31 +CTUN, 979, 0.43, 4.95, 0.000000, 0, 7, 73, 986, 0 +ATT, 0.00, 0.69, -14.37, -8.52, 0.00, 52.98, 58.31 +CTUN, 930, 0.43, 5.04, 0.000000, 0, 10, 73, 941, 0 +DU32, 7, 166140 +CURR, 930, 2836657, 911, 2610, 5051, 2099.576900 +ATT, 0.00, 0.53, -12.97, -9.61, 0.00, 54.27, 58.31 +CTUN, 906, 0.64, 5.02, 0.000000, 0, 10, 74, 916, 0 +ATT, 0.00, 0.39, -11.57, -8.91, 0.00, 55.64, 58.31 +CTUN, 804, 0.64, 5.22, 0.000000, 0, 6, 76, 833, 0 +ATT, 0.00, -0.42, -11.01, -7.04, 0.00, 56.79, 58.31 +CTUN, 746, 0.84, 5.28, 0.000000, 0, 3, 68, 758, 0 +ATT, 0.00, -1.12, -8.12, -5.60, 0.00, 57.77, 58.31 +CTUN, 740, 0.84, 5.41, 0.000000, 0, 2, 55, 742, 0 +ATT, 0.00, -1.84, -6.53, -5.31, 0.00, 58.65, 58.31 +CTUN, 740, 1.04, 5.49, 0.000000, 0, 2, 36, 741, 0 +ATT, 0.00, -1.30, -5.32, -5.08, 0.00, 59.58, 58.31 +CTUN, 759, 1.04, 5.62, 0.000000, 0, 1, 16, 760, 0 +ATT, 0.00, -0.53, -3.73, -3.73, 0.00, 60.59, 58.31 +CTUN, 828, 1.19, 5.61, 0.000000, 0, 0, 6, 821, 0 +ATT, 0.00, -0.02, -2.70, -2.27, 0.00, 61.48, 58.31 +CTUN, 855, 1.19, 5.87, 0.000000, 0, 0, 0, 855, 0 +ATT, 0.00, 0.96, -2.42, -0.80, 0.00, 62.16, 58.31 +CTUN, 898, 1.27, 5.82, 0.000000, 0, 0, -5, 892, 0 +ATT, 0.00, 1.64, -2.70, 0.61, 0.00, 62.60, 58.31 +CTUN, 911, 1.27, 5.86, 0.000000, 0, 0, -11, 911, 0 +DU32, 7, 166140 +CURR, 911, 2844885, 942, 2141, 5051, 2105.249000 +ATT, 0.00, 1.76, -2.61, 1.39, 0.00, 62.79, 58.31 +CTUN, 918, 1.31, 5.87, 0.000000, 0, 0, -15, 915, 0 +ATT, -0.18, 1.70, -2.52, 1.66, 0.00, 62.63, 58.31 +CTUN, 925, 1.27, 5.83, 0.000000, 0, 0, -15, 924, 0 +ATT, -0.94, 1.85, -2.70, 1.93, 0.00, 62.20, 58.31 +CTUN, 925, 1.27, 5.72, 0.000000, 0, 0, -21, 923, 0 +ATT, -2.46, 1.73, -2.42, 2.17, 0.00, 61.66, 58.31 +CTUN, 936, 1.26, 5.78, 0.000000, 0, 0, -23, 932, 0 +ATT, -4.35, 0.82, -2.52, 2.36, 0.00, 61.02, 58.31 +CTUN, 965, 1.26, 5.82, 0.000000, 0, 0, -23, 955, 0 +ATT, -4.73, -0.62, -2.42, 2.27, 0.00, 60.34, 58.31 +CTUN, 990, 1.18, 5.72, 0.000000, 0, 0, -23, 989, 0 +ATT, -5.87, -1.71, -2.70, 1.95, 0.00, 59.65, 58.31 +CTUN, 1000, 1.18, 5.77, 0.000000, 0, 0, -26, 1000, 0 +ATT, -46.04, -3.02, -2.42, 1.69, 0.00, 58.95, 58.31 +CTUN, 1000, 1.06, 5.77, 0.000000, 0, 0, -23, 1000, 0 +ATT, -1.13, -4.46, -1.12, 1.32, 0.00, 58.38, 58.31 +CTUN, 1000, 1.06, 5.81, 0.000000, 0, 0, -25, 1000, 0 +ATT, 0.00, -3.22, -2.70, 0.90, 0.00, 57.96, 58.31 +CTUN, 1000, 1.05, 5.81, 0.000000, 0, 0, -22, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2854495, 932, 2316, 5051, 2111.657200 +ATT, 0.00, -0.41, -3.17, 0.78, 0.00, 57.68, 58.31 +CTUN, 996, 1.05, 5.82, 0.000000, 0, 0, -22, 996, 0 +ATT, 0.00, 0.64, -3.26, 0.41, 0.00, 57.69, 58.31 +CTUN, 999, 1.04, 5.83, 0.000000, 0, 0, -21, 999, 0 +ATT, 0.00, 0.62, -3.45, -0.48, 0.00, 57.89, 58.31 +CTUN, 998, 1.05, 5.81, 0.000000, 0, 0, -17, 1000, 0 +ATT, 0.00, 1.07, -3.92, -1.62, 0.00, 58.41, 58.31 +CTUN, 997, 1.05, 5.79, 0.000000, 0, 0, -16, 997, 0 +ATT, 0.00, 1.35, -4.20, -2.21, 0.00, 59.28, 58.31 +CTUN, 997, 1.05, 5.75, 0.000000, 0, 0, -14, 997, 0 +ATT, 0.00, 0.86, -4.38, -2.37, 0.00, 60.45, 58.31 +CTUN, 992, 1.05, 5.88, 0.000000, 0, 0, -16, 993, 0 +ATT, 0.00, 0.03, -4.20, -2.28, 0.00, 61.54, 58.31 +CTUN, 990, 1.14, 5.84, 0.000000, 0, 0, -19, 990, 0 +ATT, 0.00, -0.48, -2.52, -2.18, 0.00, 62.67, 58.31 +CTUN, 990, 1.14, 5.93, 0.000000, 0, 0, -24, 990, 0 +ATT, 0.00, -0.95, -2.52, -2.03, 0.00, 63.63, 58.31 +CTUN, 990, 1.15, 5.84, 0.000000, 0, 0, -25, 990, 0 +ATT, 0.00, -1.15, -2.42, -1.46, 0.00, 64.33, 58.31 +CTUN, 990, 1.15, 5.79, 0.000000, 0, 0, -32, 990, 0 +DU32, 7, 166140 +CURR, 990, 2864437, 945, 2069, 5028, 2117.890100 +ATT, 0.00, -0.95, -2.70, -0.97, 0.00, 64.78, 58.31 +CTUN, 1000, 1.21, 5.65, 0.000000, 0, 0, -37, 1000, 0 +ATT, -3.31, -1.12, -3.26, -1.16, 0.00, 64.94, 58.31 +CTUN, 1000, 1.18, 5.60, 0.000000, 0, 0, -47, 999, 0 +ATT, -6.91, -2.04, -4.10, -1.81, 0.00, 64.87, 58.31 +CTUN, 1000, 1.18, 5.66, 0.000000, 0, 0, -51, 1000, 0 +ATT, -6.63, -4.34, -6.53, -2.46, 0.00, 64.72, 58.31 +CTUN, 1000, 1.14, 5.58, 0.000000, 0, 1, -59, 1000, 0 +ATT, -6.63, -6.62, -6.53, -3.46, 0.00, 64.52, 58.31 +CTUN, 1000, 1.14, 5.46, 0.000000, 0, 0, -64, 1000, 0 +ATT, -6.44, -7.12, -7.74, -4.66, 0.00, 64.21, 58.31 +CTUN, 1000, 1.04, 5.46, 0.000000, 0, 1, -65, 1000, 0 +ATT, -4.26, -6.37, -7.65, -5.35, 0.00, 63.75, 58.31 +CTUN, 1000, 1.04, 5.33, 0.000000, 0, 0, -70, 1000, 0 +ATT, -1.23, -5.03, -7.84, -5.27, 0.00, 63.03, 58.31 +CTUN, 1000, 0.90, 5.19, 0.000000, 0, 1, -76, 1000, 0 +ATT, -0.18, -2.45, -7.84, -4.42, 0.00, 62.19, 58.31 +CTUN, 1000, 0.90, 5.19, 0.000000, 0, 0, -80, 1000, 0 +ATT, 0.00, 0.37, -7.56, -3.50, 0.00, 61.25, 58.31 +CTUN, 1000, 0.73, 5.00, 0.000000, 0, 1, -87, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2874437, 949, 2056, 5051, 2123.841100 +ATT, 0.00, 2.40, -6.81, -2.37, 0.00, 60.28, 58.31 +CTUN, 1000, 0.73, 4.94, 0.000000, 0, 0, -90, 1000, 0 +ATT, 0.00, 2.99, -5.88, -1.47, 0.00, 59.45, 58.31 +CTUN, 1000, 0.55, 4.67, 0.000000, 0, 1, -94, 1000, 0 +ATT, 0.00, 2.39, -5.69, -0.68, 0.00, 58.80, 58.31 +CTUN, 999, 0.55, 4.79, 0.000000, 0, 0, -95, 1000, 0 +ATT, 0.00, 1.06, -6.16, 0.24, 0.00, 58.19, 58.31 +CTUN, 1000, 0.35, 4.28, 0.000000, 0, 0, -92, 999, 0 +ATT, 0.00, 0.69, -6.81, 0.36, 0.00, 57.75, 58.31 +CTUN, 1000, 0.35, 2.04, 0.000000, 0, 0, -85, 1000, 0 +ATT, -0.85, 1.79, -7.46, -0.67, 0.00, 57.44, 58.31 +CTUN, 999, 0.20, -1.20, 0.000000, 0, 0, 15, 1000, 0 +ATT, -0.85, 0.50, -7.84, -1.28, 0.00, 57.02, 58.31 +CTUN, 1000, 0.35, -0.07, 0.000000, 0, 0, 52, 1000, 0 +ATT, -0.94, -1.00, -7.84, -2.02, 0.00, 56.27, 58.31 +CTUN, 1000, 0.26, 2.13, 0.000000, 0, 0, 65, 1000, 0 +ATT, -0.85, -3.15, -7.56, -1.93, 0.00, 55.65, 58.31 +CTUN, 1000, 0.26, 4.41, 0.000000, 0, 0, 72, 1000, 0 +ATT, -1.23, -3.54, -7.56, -2.19, 0.00, 55.50, 58.31 +CTUN, 999, 0.22, 4.65, 0.000000, 0, 0, 78, 1000, 0 +DU32, 7, 166140 +CURR, 999, 2884437, 916, 2473, 5051, 2130.398200 +ATT, -1.23, -3.17, -7.18, -3.12, 0.00, 55.55, 58.31 +CTUN, 1000, 0.26, 4.68, 0.000000, 0, 0, 81, 1000, 0 +ATT, -1.23, -3.87, -6.81, -4.39, 0.00, 55.55, 58.31 +CTUN, 999, 0.26, 4.94, 0.000000, 0, 0, 84, 1000, 0 +ATT, 0.00, -4.85, -7.09, -4.29, 0.00, 55.40, 58.31 +CTUN, 1000, 0.37, 4.84, 0.000000, 0, 0, 88, 1000, 0 +ATT, 0.00, -4.94, -6.25, -3.63, 0.00, 55.11, 58.31 +CTUN, 942, 0.37, 5.08, 0.000000, 0, 4, 86, 976, 0 +ATT, 0.00, -3.45, -5.78, -3.45, 0.00, 54.66, 58.31 +CTUN, 889, 0.56, 5.16, 0.000000, 0, 2, 85, 891, 0 +ATT, 0.00, -2.05, -4.76, -3.56, 0.00, 54.25, 58.31 +CTUN, 846, 0.56, 5.34, 0.000000, 0, 1, 88, 847, 0 +ATT, 0.00, -2.57, -2.52, -3.72, 0.00, 53.98, 58.31 +CTUN, 870, 0.73, 5.33, 0.000000, 0, 2, 83, 857, 0 +ATT, 0.09, -2.48, -2.42, -3.48, 0.00, 54.28, 58.31 +CTUN, 877, 0.73, 5.41, 0.000000, 0, 1, 77, 880, 0 +ATT, 2.81, -1.70, -2.42, -2.51, 0.00, 55.01, 58.31 +CTUN, 821, 0.93, 5.58, 0.000000, 0, 0, 77, 830, 0 +ATT, 6.28, -0.78, -2.52, -1.10, 0.00, 56.22, 58.31 +CTUN, 798, 0.93, 5.59, 0.000000, 0, 0, 70, 802, 0 +DU32, 7, 166140 +CURR, 798, 2893559, 937, 2055, 5051, 2137.215600 +ATT, 7.40, 1.12, -2.42, 0.15, 0.00, 57.77, 58.31 +CTUN, 796, 1.07, 5.59, 0.000000, 0, 0, 60, 798, 0 +ATT, 7.40, 3.66, -2.52, 0.26, 0.00, 59.77, 58.31 +CTUN, 798, 1.07, 5.65, 0.000000, 0, 2, 49, 800, 0 +ATT, 7.68, 5.26, -2.52, -0.26, 0.00, 61.92, 58.31 +CTUN, 800, 1.22, 5.65, 0.000000, 0, 3, 38, 801, 0 +ATT, 7.31, 6.15, -2.52, -0.77, 0.00, 63.72, 58.31 +CTUN, 816, 1.22, 5.69, 0.000000, 0, 4, 31, 813, 0 +ATT, 6.75, 6.77, -2.52, -1.12, 0.00, 65.09, 58.31 +CTUN, 864, 1.23, 5.67, 0.000000, 0, 5, 20, 860, 0 +ATT, 6.09, 6.89, -2.52, -1.35, 0.00, 66.12, 58.31 +CTUN, 918, 1.23, 5.82, 0.000000, 0, 5, 10, 923, 0 +ATT, 6.37, 6.24, -2.52, -1.63, 0.00, 66.77, 58.31 +CTUN, 946, 1.23, 5.78, 0.000000, 0, 4, 2, 949, 0 +ATT, 5.90, 5.70, -2.42, -1.92, 0.00, 67.13, 58.31 +CTUN, 946, 1.23, 5.79, 0.000000, 0, 4, -3, 950, 0 +ATT, 1.87, 5.30, -2.42, -2.07, 0.00, 67.31, 58.31 +CTUN, 947, 1.23, 5.72, 0.000000, 0, 3, -7, 950, 0 +ATT, 0.09, 3.51, -2.42, -1.95, 0.00, 67.37, 58.31 +CTUN, 957, 1.23, 5.86, 0.000000, 0, 0, -16, 950, 0 +DU32, 7, 166140 +CURR, 957, 2902293, 933, 2170, 5051, 2142.997100 +ATT, 0.00, 0.45, -2.52, -1.65, 0.00, 67.32, 58.31 +CTUN, 982, 1.29, 5.89, 0.000000, 0, 0, -18, 982, 0 +ATT, 0.00, -1.59, -2.42, -1.16, 0.00, 67.02, 58.31 +CTUN, 1000, 1.29, 5.92, 0.000000, 0, 0, -19, 1000, 0 +ATT, 0.00, -1.80, -2.52, -0.51, 0.00, 66.49, 58.31 +CTUN, 1000, 1.34, 5.87, 0.000000, 0, 0, -23, 1000, 0 +ATT, 0.00, -1.65, -2.42, -0.14, 0.00, 65.87, 58.31 +CTUN, 999, 1.32, 5.84, 0.000000, 0, 0, -28, 1000, 0 +ATT, 0.00, -1.49, -2.42, -0.25, 0.00, 65.23, 58.31 +CTUN, 1000, 1.32, 5.86, 0.000000, 0, 0, -27, 999, 0 +ATT, 0.00, -0.95, -2.52, -0.61, 0.00, 64.57, 58.31 +CTUN, 1000, 1.29, 5.79, 0.000000, 0, 0, -26, 999, 0 +ATT, 0.00, -0.30, -2.52, -0.80, 0.00, 63.90, 58.31 +CTUN, 1000, 1.29, 5.65, 0.000000, 0, 0, -28, 1000, 0 +ATT, 0.00, -0.46, -2.42, -0.91, 0.00, 63.35, 58.31 +CTUN, 999, 1.26, 5.76, 0.000000, 0, 0, -29, 1000, 0 +ATT, 0.00, -1.48, -2.52, -1.53, 0.00, 63.01, 58.31 +CTUN, 1000, 1.26, 5.72, 0.000000, 0, 0, -27, 1000, 0 +ATT, 0.00, -1.88, -2.52, -2.19, 0.00, 62.79, 58.31 +CTUN, 1000, 1.20, 5.77, 0.000000, 0, 0, -24, 1000, 0 +DU32, 7, 166140 +CURR, 999, 2912262, 922, 2391, 5028, 2149.382800 +ATT, 0.00, -1.63, -2.52, -2.49, 0.00, 62.73, 58.31 +CTUN, 1000, 1.20, 5.71, 0.000000, 0, 1, -21, 1000, 0 +ATT, 0.00, -1.32, -2.52, -2.60, 0.00, 62.75, 58.31 +CTUN, 999, 1.15, 5.66, 0.000000, 0, 0, -19, 1000, 0 +ATT, 0.00, -0.96, -2.52, -2.66, 0.00, 62.83, 58.31 +CTUN, 1000, 1.15, 5.59, 0.000000, 0, 1, -19, 1000, 0 +ATT, 2.43, -0.78, -2.70, -2.63, 0.00, 62.89, 58.31 +CTUN, 1000, 1.09, 5.61, 0.000000, 0, 0, -21, 1000, 0 +ATT, 3.18, 0.21, -2.61, -2.50, 0.00, 62.96, 58.31 +CTUN, 1000, 1.09, 5.53, 0.000000, 0, 0, -20, 1000, 0 +ATT, 4.50, 2.22, -2.42, -2.31, 0.00, 62.99, 58.31 +CTUN, 1000, 1.03, 5.54, 0.000000, 0, 0, -23, 1000, 0 +ATT, 7.12, 4.09, -2.24, -2.34, 0.00, 63.04, 58.31 +PM, 0, 0, 0, 0, 1000, 10496, 0, 0 +CTUN, 1000, 1.03, 5.55, 0.000000, 0, 0, -25, 1000, 0 +ATT, 7.31, 5.60, -2.52, -2.46, 0.00, 63.04, 58.31 +CTUN, 1000, 0.95, 5.49, 0.000000, 0, 0, -25, 1000, 0 +ATT, 7.21, 6.80, -2.24, -2.56, 0.00, 62.92, 58.31 +CTUN, 1000, 0.95, 5.55, 0.000000, 0, 0, -27, 1000, 0 +ATT, 3.93, 7.34, -2.24, -2.64, 0.00, 62.69, 58.31 +CTUN, 1000, 0.91, 5.50, 0.000000, 0, 0, -28, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2922261, 926, 2249, 5051, 2155.775600 +ATT, 0.00, 6.95, -2.33, -2.63, 0.00, 62.35, 58.31 +CTUN, 1000, 0.91, 5.43, 0.000000, 0, 0, -36, 1000, 0 +ATT, 0.00, 4.60, -2.52, -2.66, 0.00, 61.92, 58.31 +CTUN, 1000, 0.83, 5.34, 0.000000, 0, 0, -34, 1000, 0 +ATT, 0.00, 1.17, -2.05, -2.43, 0.00, 61.30, 58.31 +CTUN, 999, 0.83, 5.25, 0.000000, 0, 0, -32, 1000, 0 +ATT, -1.42, -0.97, -1.40, -1.90, 0.00, 60.65, 58.31 +CTUN, 1000, 0.76, 5.22, 0.000000, 0, 0, -28, 1000, 0 +ATT, -3.12, -1.74, -1.40, -1.16, 0.00, 60.03, 58.31 +CTUN, 1000, 0.76, 5.14, 0.000000, 0, 0, -24, 1000, 0 +ATT, -3.22, -2.43, -1.40, -0.52, 0.00, 59.39, 58.31 +CTUN, 1000, 0.70, 5.32, 0.000000, 0, 0, -17, 1000, 0 +ATT, -1.61, -3.65, -1.58, 0.14, 0.00, 58.76, 58.31 +CTUN, 1000, 0.70, 5.25, 0.000000, 0, 0, -14, 1000, 0 +ATT, 0.00, -4.17, -2.52, 0.68, 0.00, 58.18, 58.31 +CTUN, 1000, 0.64, 5.09, 0.000000, 0, 1, -11, 1000, 0 +ATT, 0.00, -3.51, -2.52, 0.75, 0.00, 57.56, 58.31 +CTUN, 1000, 0.64, 5.14, 0.000000, 0, 0, -8, 1000, 0 +ATT, 0.00, -2.68, -2.52, 0.51, 0.00, 56.87, 58.31 +CTUN, 1000, 0.59, 5.08, 0.000000, 0, 0, -6, 999, 0 +DU32, 7, 166140 +CURR, 1000, 2932261, 910, 2616, 5051, 2162.749000 +ATT, 0.00, -2.33, -2.42, 0.20, 0.00, 56.14, 58.31 +CTUN, 1000, 0.59, 5.15, 0.000000, 0, 0, -1, 1000, 0 +ATT, 0.46, -1.92, -2.52, -0.10, 0.00, 55.44, 58.31 +CTUN, 999, 0.56, 5.04, 0.000000, 0, 0, 6, 1000, 0 +ATT, 1.68, -0.91, -2.42, -0.11, 0.00, 54.87, 58.31 +CTUN, 1000, 0.56, 5.14, 0.000000, 0, 0, 15, 999, 0 +ATT, 2.15, 0.47, -2.61, 0.19, 0.00, 54.34, 58.31 +CTUN, 1000, 0.56, 5.16, 0.000000, 0, 0, 20, 1000, 0 +ATT, 2.34, 1.46, -2.61, 0.57, 0.00, 53.84, 58.31 +CTUN, 1000, 0.57, 5.03, 0.000000, 0, 0, 28, 1000, 0 +ATT, 2.53, 1.96, -2.61, 0.82, 0.00, 53.40, 58.31 +CTUN, 1000, 0.57, 5.17, 0.000000, 0, 0, 34, 1000, 0 +ATT, 2.53, 2.43, -3.26, 0.54, 0.00, 53.02, 58.31 +CTUN, 1000, 0.58, 5.13, 0.000000, 0, 0, 38, 1000, 0 +ATT, 0.75, 2.65, -4.48, -0.03, 0.00, 52.89, 58.31 +CTUN, 1000, 0.58, 5.27, 0.000000, 0, 0, 44, 1000, 0 +ATT, 0.09, 2.24, -6.81, -1.10, 0.00, 52.88, 58.31 +CTUN, 1000, 0.64, 5.14, 0.000000, 0, 0, 49, 1000, 0 +ATT, 0.09, 1.50, -7.84, -3.00, 0.00, 52.93, 58.31 +CTUN, 986, 0.64, 5.25, 0.000000, 0, 2, 54, 992, 0 +DU32, 7, 166140 +CURR, 986, 2942258, 899, 2774, 5028, 2170.217500 +ATT, 0.09, 0.92, -8.30, -5.01, 0.00, 53.19, 58.31 +CTUN, 977, 0.72, 5.12, 0.000000, 0, 4, 62, 981, 0 +ATT, 0.09, 0.50, -7.93, -6.56, 0.00, 53.63, 58.31 +CTUN, 966, 0.72, 5.31, 0.000000, 0, 6, 68, 972, 0 +ATT, 0.00, 0.44, -7.28, -7.53, 0.00, 54.18, 58.31 +CTUN, 958, 0.82, 5.37, 0.000000, 0, 7, 74, 965, 0 +ATT, 0.09, 0.47, -3.17, -7.60, 0.00, 54.84, 58.31 +CTUN, 930, 0.82, 5.35, 0.000000, 0, 5, 80, 935, 0 +ATT, 0.00, 0.46, -2.42, -5.99, 0.00, 55.50, 58.31 +CTUN, 858, 0.95, 5.50, 0.000000, 0, 2, 84, 892, 0 +ATT, 0.00, 0.65, -2.14, -2.76, 0.00, 56.07, 58.31 +CTUN, 788, 0.95, 5.66, 0.000000, 0, 0, 85, 788, 0 +ATT, 0.00, 0.72, -2.24, -0.12, 0.00, 56.61, 58.31 +CTUN, 759, 1.11, 5.70, 0.000000, 0, 0, 78, 761, 0 +ATT, 0.00, 1.09, -2.52, 0.78, 0.00, 57.01, 58.31 +CTUN, 759, 1.11, 5.84, 0.000000, 0, 0, 61, 759, 0 +ATT, 0.00, 1.59, -3.08, 1.06, 0.00, 57.16, 58.31 +CTUN, 746, 1.26, 5.93, 0.000000, 0, 0, 44, 746, 0 +ATT, 0.00, 1.76, -3.26, 0.75, 0.00, 56.94, 58.31 +CTUN, 759, 1.26, 5.93, 0.000000, 0, 0, 26, 759, 0 +DU32, 7, 166140 +CURR, 791, 2950893, 947, 1739, 5051, 2176.537100 +ATT, 0.00, 1.46, -2.70, 0.01, 0.00, 56.26, 58.31 +CTUN, 871, 1.37, 5.97, 0.000000, 0, 0, 12, 871, 0 +ATT, 0.00, 0.86, -2.61, -1.07, 0.00, 55.28, 58.31 +CTUN, 946, 1.37, 6.07, 0.000000, 0, 0, 4, 938, 0 +ATT, 0.00, 0.39, -2.61, -1.52, 0.00, 54.20, 58.31 +CTUN, 982, 1.40, 6.02, 0.000000, 0, 0, 7, 982, 0 +ATT, 0.00, 0.61, -2.80, -0.93, 0.00, 53.25, 58.31 +CTUN, 979, 1.37, 6.07, 0.000000, 0, 0, 14, 979, 0 +ATT, 0.00, 1.10, -2.80, -0.01, 0.00, 52.53, 58.31 +CTUN, 953, 1.40, 5.92, 0.000000, 0, 0, 25, 965, 0 +ATT, 0.00, 1.34, -2.89, 0.57, 0.00, 52.14, 58.31 +CTUN, 870, 1.40, 6.07, 0.000000, 0, 0, 35, 908, 0 +ATT, 0.00, 1.08, -2.61, 1.08, 0.00, 52.01, 58.31 +CTUN, 753, 1.48, 6.17, 0.000000, 0, 0, 49, 764, 0 +ATT, 0.00, 0.93, -3.08, 1.45, 0.00, 52.11, 58.31 +CTUN, 680, 1.48, 6.20, 0.000000, 0, 0, 40, 681, 0 +ATT, 0.00, 1.06, -3.08, 1.01, 0.00, 52.52, 58.31 +CTUN, 700, 1.54, 6.14, 0.000000, 0, 0, 19, 700, 0 +ATT, 0.00, 1.41, -3.08, -0.54, 0.00, 53.19, 58.31 +CTUN, 779, 1.48, 6.19, 0.000000, 0, 0, -3, 761, 0 +DU32, 7, 166140 +CURR, 779, 2959356, 961, 1577, 5051, 2182.645300 +ATT, 0.00, 1.92, -3.08, -2.10, 0.00, 53.97, 58.31 +CTUN, 855, 1.54, 6.01, 0.000000, 0, 1, -17, 848, 0 +ATT, 0.00, 2.15, -2.89, -2.73, 0.00, 54.73, 58.31 +CTUN, 908, 1.54, 6.27, 0.000000, 0, 1, -29, 906, 0 +ATT, 0.00, 1.60, -2.98, -2.35, 0.00, 55.45, 58.31 +CTUN, 940, 1.54, 6.06, 0.000000, 0, 0, -27, 938, 0 +ATT, 0.00, 0.78, -3.08, -1.56, 0.00, 55.97, 58.31 +CTUN, 946, 1.50, 5.99, 0.000000, 0, 0, -24, 946, 0 +ATT, 0.00, 0.32, -3.08, -1.05, 0.00, 56.33, 58.31 +CTUN, 938, 1.50, 6.13, 0.000000, 0, 0, -17, 943, 0 +ATT, 0.00, -0.24, -2.70, -1.03, 0.00, 56.45, 58.31 +CTUN, 921, 1.40, 6.03, 0.000000, 0, 0, -9, 923, 0 +ATT, -0.94, -0.61, -2.70, -1.12, 0.00, 56.45, 58.31 +CTUN, 903, 1.40, 6.05, 0.000000, 0, 0, -1, 903, 0 +ATT, -2.17, -1.10, -2.14, -1.21, 0.00, 56.39, 58.31 +CTUN, 864, 1.37, 6.03, 0.000000, 0, 0, 4, 872, 0 +ATT, -2.36, -2.28, -2.33, -1.06, 0.00, 56.35, 58.31 +CTUN, 855, 1.37, 5.89, 0.000000, 0, 0, 8, 854, 0 +ATT, -2.36, -2.88, -2.33, -0.79, 0.00, 56.33, 58.31 +CTUN, 871, 1.37, 6.01, 0.000000, 0, 0, 10, 864, 0 +DU32, 7, 166140 +CURR, 871, 2968318, 930, 2210, 5051, 2189.400900 +ATT, -2.36, -2.71, -2.33, -0.35, 0.00, 56.19, 58.31 +CTUN, 882, 1.42, 6.00, 0.000000, 0, 0, 11, 881, 0 +ATT, -2.93, -2.18, -2.89, -0.04, 0.00, 56.15, 58.31 +CTUN, 882, 1.42, 5.94, 0.000000, 0, 0, 10, 882, 0 +ATT, -3.22, -2.21, -3.26, 0.33, 0.00, 56.20, 58.31 +CTUN, 858, 1.42, 6.03, 0.000000, 0, 0, 11, 867, 0 +ATT, -2.84, -2.92, -2.98, 0.67, 0.00, 56.18, 58.31 +CTUN, 844, 1.38, 6.03, 0.000000, 0, 1, 12, 851, 0 +ATT, -2.36, -3.58, -4.10, 0.52, 0.00, 56.19, 58.31 +CTUN, 836, 1.40, 6.00, 0.000000, 0, 1, 12, 839, 0 +ATT, -1.13, -3.50, -4.85, -0.26, 0.00, 56.15, 58.31 +CTUN, 819, 1.38, 6.11, 0.000000, 0, 1, 8, 820, 0 +ATT, 0.00, -3.07, -6.25, -1.46, 0.00, 56.14, 58.31 +CTUN, 835, 1.38, 5.94, 0.000000, 0, 1, 0, 829, 0 +ATT, 0.00, -2.64, -6.81, -2.55, 0.00, 55.97, 58.31 +CTUN, 876, 1.38, 6.04, 0.000000, 0, 1, -2, 874, 0 +ATT, 0.00, -1.89, -6.34, -3.77, 0.00, 55.71, 58.31 +CTUN, 906, 1.47, 5.96, 0.000000, 0, 2, -4, 904, 0 +ATT, 0.00, -0.84, -5.13, -4.66, 0.00, 55.37, 58.31 +CTUN, 915, 1.47, 5.91, 0.000000, 0, 2, 0, 916, 0 +DU32, 7, 166140 +CURR, 915, 2976973, 908, 2595, 5028, 2195.807900 +ATT, 0.00, -0.13, -4.57, -4.38, 0.00, 55.09, 58.31 +CTUN, 912, 1.47, 6.00, 0.000000, 0, 1, 5, 913, 0 +ATT, 0.00, -0.55, -4.29, -2.89, 0.00, 54.80, 58.31 +CTUN, 871, 1.47, 6.05, 0.000000, 0, 0, 12, 890, 0 +ATT, 0.00, -0.82, -4.38, -1.62, 0.00, 54.71, 58.31 +CTUN, 829, 1.47, 6.03, 0.000000, 0, 0, 15, 829, 0 +ATT, 0.00, -0.81, -4.38, -1.06, 0.00, 54.93, 58.31 +CTUN, 773, 1.47, 6.00, 0.000000, 0, 0, 12, 780, 0 +ATT, 0.00, 0.05, -4.38, -0.98, 0.00, 55.39, 58.31 +CTUN, 764, 1.50, 6.09, 0.000000, 0, 0, 6, 765, 0 +ATT, 0.00, 1.00, -4.29, -1.41, 0.00, 56.00, 58.31 +CTUN, 765, 1.50, 6.11, 0.000000, 0, 0, -9, 766, 0 +ATT, 0.00, 0.95, -4.38, -2.60, 0.00, 56.78, 58.31 +CTUN, 819, 1.53, 6.19, 0.000000, 0, 1, -26, 800, 0 +ATT, 0.00, 0.02, -4.38, -4.05, 0.00, 57.86, 58.31 +CTUN, 881, 1.51, 6.14, 0.000000, 0, 2, -36, 867, 0 +ATT, 1.59, -0.52, -4.29, -5.28, 0.00, 59.45, 58.31 +CTUN, 932, 1.51, 6.26, 0.000000, 0, 3, -38, 928, 0 +ATT, 2.90, 0.20, -4.38, -5.72, 0.00, 61.32, 58.31 +CTUN, 961, 1.49, 6.09, 0.000000, 0, 4, -38, 958, 0 +DU32, 7, 166140 +CURR, 966, 2985447, 923, 2320, 5051, 2201.886700 +ATT, 3.93, 1.65, -4.38, -5.49, 0.00, 63.31, 58.31 +CTUN, 976, 1.49, 6.21, 0.000000, 0, 4, -41, 982, 0 +ATT, 5.90, 3.15, -4.38, -5.09, 0.00, 65.20, 58.31 +CTUN, 975, 1.43, 6.18, 0.000000, 0, 4, -40, 979, 0 +ATT, 6.00, 4.13, -3.92, -4.52, 0.00, 66.75, 58.31 +CTUN, 966, 1.43, 6.18, 0.000000, 0, 4, -46, 973, 0 +ATT, 4.12, 4.28, -2.42, -3.86, 0.00, 67.83, 58.31 +CTUN, 965, 1.36, 6.02, 0.000000, 0, 3, -54, 967, 0 +ATT, 0.46, 3.70, -2.05, -2.97, 0.00, 68.49, 58.49 +CTUN, 986, 1.36, 6.10, 0.000000, 0, 1, -61, 980, 0 +ATT, 0.00, 1.66, -1.21, -2.00, 0.00, 68.83, 58.83 +CTUN, 1000, 1.27, 6.03, 0.000000, 0, 0, -65, 1000, 0 +ATT, 0.00, -0.84, -0.18, -0.68, 0.00, 68.86, 58.89 +CTUN, 1000, 1.27, 5.97, 0.000000, 0, 0, -66, 1000, 0 +ATT, 0.00, -1.84, 0.00, 0.85, 0.00, 68.57, 58.89 +CTUN, 1000, 1.18, 5.78, 0.000000, 0, 0, -68, 1000, 0 +ATT, 0.00, -1.21, 0.00, 2.57, 0.00, 68.12, 58.89 +CTUN, 1000, 1.18, 5.77, 0.000000, 0, 0, -71, 1000, 0 +ATT, 0.00, 0.17, 0.00, 3.94, 0.00, 67.50, 58.89 +CTUN, 1000, 1.05, 5.72, 0.000000, 0, 0, -80, 1000, 0 +DU32, 7, 166140 +CURR, 1000, 2995322, 934, 2018, 5051, 2207.724600 +ATT, 0.00, 0.21, 0.00, 4.47, 0.00, 66.65, 58.89 +CTUN, 1000, 1.05, 5.81, 0.000000, 0, 0, -91, 1000, 0 +ATT, 0.00, -1.40, 0.00, 3.95, 0.00, 65.60, 58.89 +CTUN, 1000, 0.89, 5.68, 0.000000, 0, 0, -93, 1000, 0 +ATT, 0.00, -0.91, 0.00, 3.09, 0.00, 64.29, 58.89 +CTUN, 999, 0.89, 5.56, 0.000000, 0, 1, -98, 1000, 0 +ATT, 0.00, -0.81, 0.00, 2.62, 0.00, 62.98, 58.89 +CTUN, 1000, 0.71, 5.43, 0.000000, 0, 0, -97, 1000, 0 +ATT, 1.78, -1.14, 0.00, 2.35, 0.00, 61.75, 58.89 +CTUN, 999, 0.71, 5.25, 0.000000, 0, 0, -92, 1000, 0 +ATT, 3.37, -0.50, -1.02, 2.05, 0.00, 60.42, 58.89 +CTUN, 1000, 0.53, 5.06, 0.000000, 0, 0, -87, 1000, 0 +ATT, 4.50, 2.03, -1.21, 1.88, 0.00, 58.96, 58.89 +CTUN, 999, 0.53, 4.85, 0.000000, 0, 1, -80, 1000, 0 +ATT, 4.68, 4.54, -1.68, 0.82, 0.00, 57.61, 58.89 +CTUN, 1000, 0.36, 4.79, 0.000000, 0, 0, -69, 1000, 0 +ATT, 4.03, 5.29, -1.96, -0.75, 0.00, 56.06, 58.89 +CTUN, 999, 0.36, 4.51, 0.000000, 0, 0, -49, 1000, 0 +ATT, 3.18, 4.25, -2.05, -1.34, 0.00, 55.13, 58.89 +CTUN, 1000, 0.22, 4.27, 0.000000, 0, 1, -27, 997, 0 +DU32, 7, 166140 +CURR, 1000, 3005322, 900, 2736, 5051, 2214.745800 +ATT, 0.18, 2.23, -2.05, -0.90, 0.00, 54.79, 58.89 +CTUN, 1000, 0.22, 3.29, 0.000000, 0, 0, -4, 1000, 0 +ATT, 0.00, 0.97, -1.30, 0.34, 0.00, 54.92, 58.89 +CTUN, 999, 0.20, 3.49, 0.000000, 0, 0, 12, 1000, 0 +ATT, 0.00, 0.18, -1.58, 1.26, 0.00, 55.39, 58.89 +CTUN, 946, 0.20, 3.95, 0.000000, 0, 0, 27, 979, 0 +ATT, 0.00, -0.35, -2.42, 1.19, 0.00, 55.95, 58.89 +CTUN, 906, 0.20, 4.46, 0.000000, 0, 0, 36, 911, 0 +ATT, 0.00, -0.64, -2.70, 0.54, 0.00, 56.67, 58.89 +CTUN, 880, 0.20, 4.77, 0.000000, 0, 0, 47, 885, 0 +ATT, 0.00, -0.72, -4.29, 0.62, 0.00, 57.41, 58.89 +CTUN, 856, 0.20, 4.65, 0.000000, 0, 0, 48, 854, 0 +ATT, 0.00, -0.92, -5.88, 0.44, 0.00, 58.05, 58.89 +PM, 0, 0, 0, 0, 1000, 10472, 0, 0 +CTUN, 857, 0.25, 5.06, 0.000000, 0, 0, 45, 856, 0 +ATT, 0.00, -0.95, -6.72, -0.64, 0.00, 58.63, 58.89 +CTUN, 870, 0.25, 4.96, 0.000000, 0, 0, 38, 869, 0 +ATT, 0.00, -1.38, -7.28, -2.65, 0.00, 59.31, 58.89 +CTUN, 883, 0.34, 5.13, 0.000000, 0, 1, 31, 880, 0 +ATT, 0.18, -1.34, -7.93, -4.66, 0.00, 59.78, 58.89 +CTUN, 886, 0.34, 5.09, 0.000000, 0, 3, 29, 889, 0 +DU32, 7, 166140 +CURR, 885, 3014485, 910, 2438, 5051, 2221.523400 +ATT, 0.37, -0.02, -8.21, -5.55, 0.00, 59.89, 58.89 +CTUN, 890, 0.44, 5.10, 0.000000, 0, 3, 28, 889, 0 +ATT, 1.59, 0.14, -8.30, -6.03, 0.00, 59.52, 58.89 +CTUN, 900, 0.44, 5.19, 0.000000, 0, 4, 25, 902, 0 +ATT, 1.96, -0.02, -7.84, -6.59, 0.00, 58.78, 58.89 +CTUN, 904, 0.52, 5.34, 0.000000, 0, 5, 27, 908, 0 +ATT, 1.78, 0.84, -7.84, -6.56, 0.00, 57.91, 58.89 +CTUN, 911, 0.52, 5.22, 0.000000, 0, 4, 29, 912, 0 +ATT, 0.75, 1.79, -7.84, -5.84, 0.00, 56.97, 58.89 +CTUN, 909, 0.59, 5.24, 0.000000, 0, 4, 30, 913, 0 +ATT, 0.00, 1.66, -7.84, -5.24, 0.00, 56.16, 58.89 +CTUN, 909, 0.59, 5.30, 0.000000, 0, 3, 33, 912, 0 +ATT, 0.00, 0.88, -7.84, -4.69, 0.00, 55.44, 58.89 +CTUN, 902, 0.65, 5.28, 0.000000, 0, 2, 35, 906, 0 +ATT, 0.00, 0.53, -7.84, -4.18, 0.00, 54.97, 58.89 +CTUN, 888, 0.65, 5.38, 0.000000, 0, 1, 38, 889, 0 +ATT, 0.00, 0.85, -7.37, -3.79, 0.00, 54.68, 58.89 +CTUN, 876, 0.73, 5.29, 0.000000, 0, 1, 40, 877, 0 +ATT, 0.00, 1.35, -5.13, -3.56, 0.00, 54.68, 58.89 +CTUN, 876, 0.73, 5.39, 0.000000, 0, 1, 36, 876, 0 +DU32, 7, 166140 +CURR, 876, 3023470, 903, 2326, 5028, 2228.397500 +ATT, 0.00, 1.82, -2.52, -3.08, 0.00, 54.90, 58.89 +CTUN, 879, 0.83, 5.44, 0.000000, 0, 1, 34, 880, 0 +ATT, 0.00, 2.13, -2.42, -1.59, 0.00, 55.34, 58.89 +CTUN, 879, 0.83, 5.58, 0.000000, 0, 0, 33, 879, 0 +ATT, 0.00, 1.75, -2.52, 0.35, 0.00, 55.99, 58.89 +CTUN, 854, 0.90, 5.67, 0.000000, 0, 0, 31, 854, 0 +ATT, 0.00, 1.02, -2.33, 1.53, 0.00, 56.76, 58.89 +CTUN, 827, 0.90, 5.57, 0.000000, 0, 0, 25, 828, 0 +ATT, 0.00, 0.66, -2.52, 1.43, 0.00, 57.58, 58.89 +CTUN, 836, 0.99, 5.64, 0.000000, 0, 0, 16, 831, 0 +ATT, 0.00, 0.95, -2.52, 0.80, 0.00, 58.32, 58.89 +CTUN, 857, 0.99, 5.69, 0.000000, 0, 0, 7, 847, 0 +ATT, 0.00, 1.11, -2.24, 0.70, 0.00, 58.84, 58.89 +CTUN, 870, 1.06, 5.75, 0.000000, 0, 0, 0, 870, 0 +ATT, 0.00, 1.22, -2.33, 1.20, 0.00, 59.11, 58.89 +CTUN, 871, 1.06, 5.83, 0.000000, 0, 0, -4, 870, 0 +ATT, 0.00, 1.09, -2.33, 1.65, 0.00, 59.17, 58.89 +CTUN, 892, 1.10, 5.75, 0.000000, 0, 0, -4, 892, 0 +ATT, -0.94, 0.75, -0.93, 1.93, 0.00, 59.04, 58.89 +CTUN, 892, 1.06, 5.66, 0.000000, 0, 0, -6, 894, 0 +DU32, 7, 166140 +CURR, 892, 3032111, 902, 2412, 5028, 2234.753400 +ATT, -0.94, 0.25, -1.02, 2.22, 0.00, 58.76, 58.89 +CTUN, 888, 1.06, 5.82, 0.000000, 0, 0, -6, 888, 0 +ATT, -0.75, -0.46, -2.52, 2.75, 0.00, 58.34, 58.89 +CTUN, 879, 1.06, 5.84, 0.000000, 0, 0, -6, 879, 0 +ATT, -0.66, -0.71, -2.70, 2.72, 0.00, 57.89, 58.89 +CTUN, 879, 1.07, 5.77, 0.000000, 0, 0, -9, 880, 0 +ATT, -0.94, -0.74, -3.73, 2.23, 0.00, 57.48, 58.89 +CTUN, 880, 1.07, 5.86, 0.000000, 0, 0, -8, 880, 0 +ATT, 0.00, -0.82, -4.85, 1.62, 0.00, 57.02, 58.89 +CTUN, 879, 1.07, 5.93, 0.000000, 0, 0, -11, 879, 0 +ATT, 0.00, -0.55, -4.76, 0.84, 0.00, 56.63, 58.89 +CTUN, 880, 1.07, 5.95, 0.000000, 0, 0, -12, 879, 0 +ATT, 0.00, -0.15, -6.25, 0.32, 0.00, 56.24, 58.89 +CTUN, 880, 1.07, 5.91, 0.000000, 0, 0, -14, 879, 0 +ATT, 0.00, -0.32, -6.81, 0.11, 0.00, 56.00, 58.89 +CTUN, 880, 1.03, 5.79, 0.000000, 0, 0, -13, 880, 0 +ATT, 0.00, -1.08, -6.72, -0.20, 0.00, 55.94, 58.89 +CTUN, 879, 1.07, 5.89, 0.000000, 0, 0, -12, 879, 0 +ATT, 0.00, -1.27, -6.81, -0.65, 0.00, 56.05, 58.89 +CTUN, 879, 1.07, 5.82, 0.000000, 0, 0, -14, 879, 0 +DU32, 7, 166140 +CURR, 879, 3040919, 911, 2360, 5051, 2241.282200 +ATT, 0.00, -0.74, -6.72, -1.02, 0.00, 56.33, 58.89 +CTUN, 879, 1.10, 5.82, 0.000000, 0, 0, -16, 879, 0 +ATT, 0.00, 0.13, -6.72, -1.23, 0.00, 56.70, 58.89 +CTUN, 879, 1.10, 5.83, 0.000000, 0, 0, -16, 879, 0 +ATT, 0.00, 0.27, -6.53, -1.36, 0.00, 57.12, 58.89 +CTUN, 879, 1.14, 5.84, 0.000000, 0, 0, -13, 880, 0 +ATT, 0.00, -0.33, -6.53, -1.53, 0.00, 57.64, 58.89 +CTUN, 880, 1.14, 5.77, 0.000000, 0, 0, -15, 880, 0 +ATT, 0.00, -0.74, -6.53, -1.94, 0.00, 58.22, 58.89 +CTUN, 879, 1.14, 5.87, 0.000000, 0, 0, -15, 879, 0 +ATT, 0.00, -0.66, -6.53, -2.27, 0.00, 58.77, 58.89 +CTUN, 880, 1.13, 5.76, 0.000000, 0, 0, -15, 880, 0 +ATT, 0.00, -0.61, -6.62, -2.52, 0.00, 59.30, 58.89 +CTUN, 886, 1.13, 5.74, 0.000000, 0, 0, -15, 886, 0 +ATT, 0.00, -0.75, -6.81, -2.79, 0.00, 59.73, 58.89 +CTUN, 890, 1.13, 5.85, 0.000000, 0, 1, -14, 891, 0 +ATT, 0.00, -0.85, -6.53, -3.10, 0.00, 59.99, 58.89 +CTUN, 890, 1.13, 5.75, 0.000000, 0, 1, -12, 891, 0 +ATT, 0.00, -0.81, -6.53, -3.46, 0.00, 60.08, 58.89 +CTUN, 889, 1.12, 5.71, 0.000000, 0, 1, -11, 890, 0 +DU32, 7, 166140 +CURR, 888, 3049748, 904, 2409, 5051, 2247.876500 +ATT, 0.00, -0.72, -6.53, -3.64, 0.00, 59.94, 58.89 +CTUN, 888, 1.12, 5.81, 0.000000, 0, 1, -10, 889, 0 +ATT, 0.00, -0.01, -6.53, -3.62, 0.00, 59.58, 58.89 +CTUN, 885, 1.12, 5.91, 0.000000, 0, 1, -5, 886, 0 +ATT, 0.00, 0.62, -5.88, -3.45, 0.00, 59.03, 58.89 +CTUN, 886, 1.13, 5.79, 0.000000, 0, 1, -7, 887, 0 +ATT, 0.00, 1.03, -4.85, -2.92, 0.00, 58.35, 58.89 +CTUN, 885, 1.13, 5.91, 0.000000, 0, 0, -4, 886, 0 +ATT, 0.00, 1.20, -4.29, -1.66, 0.00, 57.70, 58.89 +CTUN, 886, 1.13, 5.72, 0.000000, 0, 0, -2, 886, 0 +ATT, 0.00, 0.79, -3.92, -0.17, 0.00, 57.16, 58.89 +CTUN, 884, 1.13, 5.80, 0.000000, 0, 0, -3, 885, 0 +ATT, -0.94, 0.07, -2.61, 1.17, 0.00, 56.60, 58.89 +CTUN, 885, 1.14, 5.77, 0.000000, 0, 0, -4, 885, 0 +ATT, -1.32, -0.34, -33.14, 2.14, 0.00, 56.09, 58.89 +CTUN, 885, 1.14, 5.77, 0.000000, 0, 0, -11, 885, 0 +ATT, -1.13, -0.68, -2.80, -1.94, 0.00, 55.71, 58.89 +CTUN, 885, 1.15, 5.97, 0.000000, 0, 2, -18, 888, 0 +ATT, -0.94, -1.48, -3.26, -6.31, 0.00, 55.37, 58.89 +CTUN, 886, 1.14, 5.73, 0.000000, 0, 5, -17, 890, 0 +DU32, 7, 166140 +CURR, 885, 3058615, 908, 2470, 5028, 2254.451200 +ATT, -0.94, -2.04, -3.45, -5.85, 0.00, 54.92, 58.89 +CTUN, 882, 1.14, 5.79, 0.000000, 0, 2, -17, 886, 0 +ATT, -0.37, -1.93, -3.73, -2.93, 0.00, 54.49, 58.89 +CTUN, 884, 1.14, 5.79, 0.000000, 0, 0, -17, 884, 0 +ATT, 0.00, -1.62, -3.08, 0.07, 0.00, 54.47, 58.89 +CTUN, 884, 1.14, 5.66, 0.000000, 0, 0, -21, 884, 0 +ATT, 0.00, -1.23, -2.98, 2.05, 0.00, 54.79, 58.89 +CTUN, 884, 1.12, 5.80, 0.000000, 0, 0, -21, 884, 0 +ATT, 0.00, -0.12, -2.80, 2.62, 0.00, 55.36, 58.89 +CTUN, 884, 1.12, 6.04, 0.000000, 0, 0, -20, 883, 0 +ATT, 0.00, 0.85, -2.70, 2.47, 0.00, 55.99, 58.89 +CTUN, 884, 1.10, 5.88, 0.000000, 0, 0, -21, 884, 0 +ATT, 0.00, 0.79, -2.70, 2.02, 0.00, 56.74, 58.89 +CTUN, 883, 1.10, 5.78, 0.000000, 0, 0, -23, 884, 0 +ATT, 0.00, 0.27, -2.80, 1.49, 0.00, 57.50, 58.89 +CTUN, 884, 1.07, 5.73, 0.000000, 0, 0, -25, 884, 0 +ATT, 0.00, 0.28, -3.08, 1.19, 0.00, 58.13, 58.89 +CTUN, 884, 1.07, 5.75, 0.000000, 0, 0, -25, 884, 0 +ATT, 0.00, 0.32, -2.98, 0.80, 0.00, 58.65, 58.89 +CTUN, 884, 1.04, 5.75, 0.000000, 0, 0, -26, 884, 0 +DU32, 7, 166140 +CURR, 884, 3067457, 894, 2358, 5051, 2261.026600 +ATT, 0.00, 0.03, -3.08, -0.17, 0.00, 59.19, 58.89 +CTUN, 883, 1.04, 5.78, 0.000000, 0, 0, -21, 884, 0 +ATT, 0.00, -0.19, -3.08, -1.26, 0.00, 59.76, 58.89 +CTUN, 884, 1.00, 5.66, 0.000000, 0, 0, -24, 883, 0 +ATT, 0.00, -0.16, -2.98, -2.56, 0.00, 60.43, 58.89 +CTUN, 884, 1.00, 5.67, 0.000000, 0, 1, -27, 885, 0 +ATT, 0.00, 0.02, -3.08, -3.27, 0.00, 61.23, 58.89 +CTUN, 884, 0.96, 5.72, 0.000000, 0, 1, -28, 885, 0 +ATT, 0.00, 0.07, -3.08, -3.04, 0.00, 62.02, 58.89 +CTUN, 884, 0.96, 5.71, 0.000000, 0, 1, -32, 885, 0 +ATT, 0.00, 0.35, -3.08, -2.78, 0.00, 62.75, 58.89 +CTUN, 884, 0.91, 5.76, 0.000000, 0, 0, -37, 884, 0 +ATT, 0.00, 0.91, -2.61, -2.63, 0.00, 63.45, 58.89 +ERR, 6, 1 +CTUN, 884, 0.91, 5.70, 0.000000, 0, 0, -43, 884, 0 +ATT, 0.00, 0.92, -2.42, -1.74, 0.00, 64.09, 58.89 +CTUN, 884, 0.86, 5.67, 0.000000, 0, 0, -50, 884, 0 +ATT, 0.00, 0.03, -2.42, -0.74, 0.00, 64.70, 58.89 +CTUN, 885, 0.86, 5.68, 0.000000, 0, 0, -55, 886, 0 +ATT, 0.00, -1.07, -2.52, -0.02, 0.00, 65.17, 58.89 +CTUN, 899, 0.77, 5.50, 0.000000, 0, 0, -62, 898, 0 +DU32, 7, 166396 +CURR, 899, 3076313, 911, 2183, 5051, 2267.302500 +ATT, 0.00, -1.43, -2.42, 0.32, 0.00, 65.37, 58.89 +CTUN, 902, 0.77, 5.45, 0.000000, 0, 0, -67, 900, 0 +ATT, 0.00, -1.59, -2.52, 0.56, 0.00, 65.49, 58.89 +CTUN, 904, 0.67, 5.62, 0.000000, 0, 0, -73, 903, 0 +ATT, 0.00, -1.44, -2.52, 0.80, 0.00, 65.40, 58.89 +CTUN, 904, 0.67, 5.43, 0.000000, 0, 0, -82, 904, 0 +ATT, 0.00, -1.13, -2.70, 0.16, 0.00, 65.26, 58.89 +CTUN, 904, 0.53, 5.13, 0.000000, 0, 0, -85, 904, 0 +ATT, 0.00, -1.09, -2.42, -0.77, 0.00, 65.01, 58.89 +CTUN, 904, 0.53, 5.13, 0.000000, 0, 0, -83, 904, 0 +ATT, 0.09, -1.10, -3.26, -1.63, 0.00, 64.69, 58.89 +CTUN, 904, 0.37, 4.85, 0.000000, 0, 0, -81, 904, 0 +ATT, 1.50, -0.59, -3.92, -1.68, 0.00, 64.18, 58.89 +CTUN, 904, 0.37, 4.59, 0.000000, 0, 0, -75, 904, 0 +ATT, 2.81, 0.63, -4.10, -1.47, 0.00, 63.36, 58.89 +CTUN, 904, 0.23, 2.69, 0.000000, 0, 0, -62, 904, 0 +ATT, 3.28, 2.09, -4.10, -2.48, 0.00, 62.25, 58.89 +CTUN, 905, 0.23, 0.58, 0.000000, 0, 1, -40, 905, 0 +ATT, 3.37, 0.93, -3.73, -1.07, 0.00, 62.15, 58.89 +CTUN, 871, 0.23, -0.45, 0.000000, 0, 0, 2, 889, 0 +DU32, 7, 166396 +CURR, 871, 3085348, 913, 1999, 5028, 2273.562300 +ATT, 3.37, 1.79, -3.26, 2.71, 0.00, 62.52, 58.89 +CTUN, 780, 5.20, 0.55, 0.000000, 0, 2, 7, 822, 0 +ATT, 3.09, 3.37, -2.42, 4.07, 0.00, 61.79, 58.89 +CTUN, 659, 5.20, 1.33, 0.000000, 0, 2, 5, 687, 0 +ATT, 3.09, 3.65, -2.42, 4.80, 0.00, 61.27, 58.89 +CTUN, 590, 5.20, 1.68, 0.000000, 0, 2, -8, 623, 0 +ATT, 3.09, 3.51, -2.70, 3.86, 0.00, 60.37, 58.89 +CTUN, 538, 2.43, 2.82, 0.000000, 0, 1, -31, 555, 0 +ATT, 3.09, 2.81, -2.42, 1.47, 0.00, 59.50, 58.89 +CTUN, 484, 2.43, 2.96, 0.000000, 0, 0, -62, 489, 0 +ATT, 3.18, 2.93, -2.52, -0.73, 0.00, 58.68, 58.89 +CTUN, 459, 0.22, 2.05, 0.000000, 0, 0, -57, 459, 0 +ATT, 3.09, 0.52, -2.52, -0.12, 0.00, 57.77, 58.89 +CTUN, 430, 2.43, 1.88, 0.000000, 0, 0, -32, 440, 0 +ATT, 3.09, 0.31, -2.42, -1.25, 0.00, 57.95, 58.89 +CTUN, 382, 2.43, 2.27, 0.000000, 0, 0, -30, 402, 0 +ATT, 3.00, 0.38, -2.42, 0.18, 0.00, 57.99, 58.89 +CTUN, 331, 7.37, 2.42, 0.000000, 0, 0, -31, 345, 0 +ATT, 3.00, 0.43, -2.70, 0.52, 0.00, 58.09, 58.89 +CTUN, 284, 7.37, 2.67, 0.000000, 0, 0, -35, 288, 0 +DU32, 7, 166396 +CURR, 267, 3090531, 1021, 340, 5028, 2276.218300 +ATT, 2.71, 0.44, -2.70, 0.50, 0.00, 58.14, 58.89 +CTUN, 205, 7.65, 2.71, 0.000000, 0, 0, -35, 229, 0 +ATT, 2.53, 0.44, -2.70, 0.52, 0.00, 58.21, 58.89 +CTUN, 0, 7.65, 2.92, 0.000000, 0, 0, -36, 141, 0 +ATT, 2.53, 0.44, -2.52, 0.49, -0.18, 58.31, 58.31 +CTUN, 0, 7.65, 3.40, 0.000000, 0, 0, -36, 0, 0 +ATT, 2.53, 0.43, -2.52, 0.49, -3.58, 58.39, 58.39 +CTUN, 0, 6.63, 3.72, 0.000000, 0, 0, -36, 0, 0 +ATT, 2.90, 0.44, -2.42, 0.51, -10.37, 58.47, 58.47 +CTUN, 0, 6.63, 3.92, 0.000000, 0, 0, -35, 0, 0 +ATT, 2.90, 0.44, -2.52, 0.49, -19.71, 58.55, 58.55 +CTUN, 0, 6.63, 3.84, 0.000000, 0, 0, -34, 0, 0 +ATT, 2.90, 0.44, -2.42, 0.49, -31.88, 58.67, 58.67 +PM, 0, 0, 0, 0, 1000, 10488, 0, 0 +CTUN, 0, 7.12, 4.17, 0.000000, 0, 0, -34, 0, 0 +ATT, 2.34, 0.44, -2.24, 0.47, -41.50, 58.75, 58.75 +CTUN, 0, 7.12, 4.23, 0.000000, 0, 0, -33, 0, 0 +ATT, 0.09, 0.44, -1.58, 0.47, -42.73, 58.86, 58.86 +CTUN, 0, 7.65, 4.31, 0.000000, 0, 0, -31, 0, 0 +ATT, 0.00, 0.44, -2.33, 0.47, -44.15, 58.93, 58.93 +CTUN, 0, 7.65, 4.31, 0.000000, 0, 0, -30, 0, 0 +DU32, 7, 166332 +CURR, 0, 3090912, 1043, 1, 5028, 2276.391800 +ATT, 0.00, 0.44, -2.24, 0.46, -42.83, 59.01, 59.01 +CTUN, 0, 7.65, 4.36, 0.000000, 0, 0, -29, 0, 0 +ATT, 0.00, 0.44, -2.52, 0.46, -42.73, 59.10, 59.10 +CTUN, 0, 7.65, 4.36, 0.000000, 0, 0, -27, 0, 0 +ATT, 0.00, 0.44, -2.42, 0.45, -42.73, 59.19, 59.19 +CTUN, 0, 7.65, 4.41, 0.000000, 0, 0, -26, 0, 0 +ATT, 0.00, 0.44, -2.52, 0.45, -42.73, 59.28, 59.28 +CTUN, 0, 7.65, 4.47, 0.000000, 0, 0, -25, 0, 0 +ATT, 0.00, 0.44, -2.52, 0.45, -42.83, 59.37, 59.37 +CTUN, 0, 7.65, 4.58, 0.000000, 0, 0, -23, 0, 0 +ATT, 0.00, 0.44, -2.42, 0.45, -42.73, 59.46, 59.46 +CTUN, 0, 7.65, 4.46, 0.000000, 0, 0, -22, 0, 0 +ATT, 0.00, 0.44, -2.52, 0.45, -42.73, 59.55, 59.55 +CTUN, 0, 7.65, 4.53, 0.000000, 0, 0, -21, 0, 0 +ATT, 0.00, 0.44, -2.52, 0.44, -42.83, 59.63, 59.63 +CTUN, 0, 2.94, 4.56, 0.000000, 0, 0, -20, 0, 0 +ATT, 0.00, 0.44, -2.33, 0.44, -42.83, 59.72, 59.72 +CTUN, 0, 7.14, 4.54, 0.000000, 0, 0, -19, 0, 0 +ATT, 0.00, 0.45, -2.52, 0.44, -42.83, 59.80, 59.80 +CTUN, 0, 7.14, 4.50, 0.000000, 0, 0, -18, 0, 0 +DU32, 7, 166332 +CURR, 0, 3090912, 1050, 1, 5051, 2276.397000 +ATT, 0.00, 0.45, -2.52, 0.44, -42.73, 59.88, 59.88 +CTUN, 0, 7.61, 4.64, 0.000000, 0, 0, -17, 0, 0 +ATT, 0.00, 0.45, -2.52, 0.43, -42.64, 59.97, 59.97 +CTUN, 0, 7.61, 4.54, 0.000000, 0, 0, -16, 0, 0 +ATT, 0.00, 0.45, -2.42, 0.43, -42.83, 60.05, 60.05 +CTUN, 0, 7.65, 4.58, 0.000000, 0, 0, -15, 0, 0 +ATT, 0.00, 0.45, -2.52, 0.43, -42.73, 60.13, 60.13 +CTUN, 0, 7.61, 4.56, 0.000000, 0, 0, -14, 0, 0 +ATT, 0.00, 0.45, -2.42, 0.43, -42.64, 60.21, 60.21 +CTUN, 0, 7.61, 4.56, 0.000000, 0, 0, -13, 0, 0 +ATT, 0.00, 0.45, -2.52, 0.43, -42.64, 60.29, 60.29 +CTUN, 0, 4.37, 4.58, 0.000000, 0, 0, -12, 0, 0 +ATT, 0.00, 0.45, -2.42, 0.42, -42.64, 60.37, 60.37 +EV, 11 +DU32, 7, 133564 +DU32, 7, 133564 +DU32, 7, 133564 +MODE, STABILIZE, 699 +DU32, 7, 133564 +DU32, 7, 133564 +DU32, 7, 133564 +DU32, 7, 133564 diff --git a/Tools/LogAnalyzer/tests/TestBalanceTwist.py b/Tools/LogAnalyzer/tests/TestBalanceTwist.py new file mode 100644 index 0000000000..ee20de6c11 --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestBalanceTwist.py @@ -0,0 +1,18 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestBalanceTwist(Test): + '''test for badly unbalanced copter, including yaw twist''' + + def __init__(self): + self.name = "Balance/Twist" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + if logdata.vehicleType == "ArduPlane": + self.result.status = TestResult.StatusType.NA + + # TODO: implement copter test for unbalanced or twisted copter frame \ No newline at end of file diff --git a/Tools/LogAnalyzer/tests/TestBrownout.py b/Tools/LogAnalyzer/tests/TestBrownout.py new file mode 100644 index 0000000000..b349f972bd --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestBrownout.py @@ -0,0 +1,34 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + +import collections + +class TestBrownout(Test): + '''test for a log that has been truncated in flight''' + + def __init__(self): + self.name = "Brownout" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + # step through the arm/disarm events in order, to see if they're symmetrical + # note: it seems landing detection isn't robust enough to rely upon here, so we'll only consider arm+disarm, not takeoff+land + evData = logdata.channels["EV"]["Id"] + orderedEVData = collections.OrderedDict(sorted(evData.dictData.items(), key=lambda t: t[0])) + isArmed = False + for line,ev in orderedEVData.iteritems(): + if ev == 10: + isArmed = True + elif ev == 11: + isArmed = False + + # check for relative altitude at end + if "CTUN" in logdata.channels and "BarAlt" in logdata.channels["CTUN"]: + finalAlt = logdata.channels["CTUN"]["BarAlt"].getNearestValue(logdata.lineCount, lookForwards=False) + + finalAltMax = 3.0 # max alt offset that we'll still consider to be on the ground + if isArmed and finalAlt > finalAltMax: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Truncated Log? Ends while armed at altitude %.2fm" % finalAlt diff --git a/Tools/LogAnalyzer/tests/TestCompass.py b/Tools/LogAnalyzer/tests/TestCompass.py new file mode 100644 index 0000000000..401bd5a30c --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestCompass.py @@ -0,0 +1,54 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestCompass(Test): + '''test for compass offsets and throttle interference''' + + def __init__(self): + self.name = "Compass" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + # quick test that compass offset parameters are within recommended range (+/- 150) + maxOffset = 150 + if logdata.hardwareType == "PX4": + maxOffset = 250 # Pixhawks have their offsets scaled larger + compassOfsX = logdata.parameters["COMPASS_OFS_X"] + compassOfsY = logdata.parameters["COMPASS_OFS_Y"] + compassOfsZ = logdata.parameters["COMPASS_OFS_Z"] + #print "MAG params: %.2f %.2f %.2f" % (compassOfsX,compassOfsY,compassOfsZ) + if abs(compassOfsX) > maxOffset or abs(compassOfsY) > maxOffset or abs(compassOfsZ) > maxOffset: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Large compass off params (X:%.2f, Y:%.2f, Z:%.2f)" % (compassOfsX,compassOfsY,compassOfsZ) + + # check for excessive compass offsets using MAG data if present (it can change during flight is compass learn is on) + if "MAG" in logdata.channels: + err = False + #print "MAG min/max xyz... %.2f %.2f %.2f %.2f %.2f %.2f " % (logdata.channels["MAG"]["OfsX"].min(), logdata.channels["MAG"]["OfsX"].max(), logdata.channels["MAG"]["OfsY"].min(), logdata.channels["MAG"]["OfsY"].min(), logdata.channels["MAG"]["OfsZ"].min(), logdata.channels["MAG"]["OfsZ"].max()) + if logdata.channels["MAG"]["OfsX"].max() > maxOffset: + self.result.extraFeedback = self.result.extraFeedback + "X: %.2f\n" % logdata.channels["MAG"]["OfsX"].max() + err = True + if logdata.channels["MAG"]["OfsX"].min() < -maxOffset: + self.result.extraFeedback = self.result.extraFeedback + "X: %.2f\n" % logdata.channels["MAG"]["OfsX"].min() + err = True + if logdata.channels["MAG"]["OfsY"].max() > maxOffset: + self.result.extraFeedback = self.result.extraFeedback + "Y: %.2f\n" % logdata.channels["MAG"]["OfsY"].max() + err = True + if logdata.channels["MAG"]["OfsY"].min() < -maxOffset: + self.result.extraFeedback = self.result.extraFeedback + "Y: %.2f\n" % logdata.channels["MAG"]["OfsY"].min() + err = True + if logdata.channels["MAG"]["OfsZ"].max() > maxOffset: + self.result.extraFeedback = self.result.extraFeedback + "Z: %.2f\n" % logdata.channels["MAG"]["OfsZ"].max() + err = True + if logdata.channels["MAG"]["OfsZ"].min() < -maxOffset: + self.result.extraFeedback = self.result.extraFeedback + "Z: %.2f\n" % logdata.channels["MAG"]["OfsZ"].min() + err = True + if err: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Large compass offset in MAG data" + + # TODO: check for compass/throttle interference. Need to add mag_field to logging, or calc our own from MAG data if present + # TODO: can we derive a compassmot percentage from the params? Fail if >30%? diff --git a/Tools/LogAnalyzer/tests/TestEmpty.py b/Tools/LogAnalyzer/tests/TestEmpty.py new file mode 100644 index 0000000000..58ae654594 --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestEmpty.py @@ -0,0 +1,19 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestEmpty(Test): + '''test for empty or near-empty logs''' + + def __init__(self): + self.name = "Empty" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + # all the logic for this test is in the helper function, as it can also be called up front as an early exit + emptyErr = DataflashLog.DataflashLogHelper.isLogEmpty(logdata) + if emptyErr: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Empty log? " + emptyErr diff --git a/Tools/LogAnalyzer/tests/TestEvents.py b/Tools/LogAnalyzer/tests/TestEvents.py new file mode 100644 index 0000000000..43c4ad879f --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestEvents.py @@ -0,0 +1,54 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestEvents(Test): + '''test for erroneous events and failsafes''' + + def __init__(self): + self.name = "Event/Failsafe" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + errors = set() + + if "ERR" in logdata.channels: + errLines = sorted(logdata.channels["ERR"]["Subsys"].dictData.keys()) + for line in errLines: + subSys = logdata.channels["ERR"]["Subsys"].dictData[line] + eCode = logdata.channels["ERR"]["ECode"].dictData[line] + if subSys == 2 and (eCode == 1): + errors.add("PPM") + elif subSys == 3 and (eCode == 1 or eCode == 2): + errors.add("COMPASS") + elif subSys == 5 and (eCode == 1): + errors.add("FS_THR") + elif subSys == 6 and (eCode == 1): + errors.add("FS_BATT") + elif subSys == 7 and (eCode == 1): + errors.add("GPS") + elif subSys == 8 and (eCode == 1): + errors.add("GCS") + elif subSys == 9 and (eCode == 1 or eCode == 2): + errors.add("FENCE") + elif subSys == 10: + errors.add("FLT_MODE") + elif subSys == 11 and (eCode == 2): + errors.add("GPS_GLITCH") + elif subSys == 12 and (eCode == 1): + errors.add("CRASH") + + if len(errors) > 0: + if len(errors) == 1 and "FENCE" in errors: + self.result.status = TestResult.StatusType.WARN + else: + self.result.status = TestResult.StatusType.FAIL + if len(errors) == 1: + self.result.statusMessage = "ERR found: " + else: + self.result.statusMessage = "ERRs found: " + for err in errors: + self.result.statusMessage = self.result.statusMessage + err + " " + diff --git a/Tools/LogAnalyzer/tests/TestGPSGlitch.py b/Tools/LogAnalyzer/tests/TestGPSGlitch.py new file mode 100644 index 0000000000..7e5e1c199b --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestGPSGlitch.py @@ -0,0 +1,32 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestGPSGlitch(Test): + '''test for bad GPS data (satellite count, hdop), and later for sudden repositioning beyond what the drone could do''' + + def __init__(self): + self.name = "GPS" + + def run(self, logdata): + self.result = TestResult() + # define and check different thresholds for WARN level and FAIL level + minSatsWARN = 6 + minSatsFAIL = 5 + maxHDopWARN = 3.0 + maxHDopFAIL = 10.0 + foundBadSatsWarn = logdata.channels["GPS"]["NSats"].min() < minSatsWARN + foundBadHDopWarn = logdata.channels["GPS"]["HDop"].max() > maxHDopWARN + foundBadSatsFail = logdata.channels["GPS"]["NSats"].min() < minSatsFAIL + foundBadHDopFail = logdata.channels["GPS"]["HDop"].max() > maxHDopFAIL + if foundBadSatsFail or foundBadHDopFail: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max()) + elif foundBadSatsWarn or foundBadHDopWarn: + self.result.status = TestResult.StatusType.WARN + self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max()) + else: + self.result.status = TestResult.StatusType.PASS + + # TODO: also test for sudden repositioning beyond what the drone could reasonably achieve + # ... diff --git a/Tools/LogAnalyzer/tests/TestParams.py b/Tools/LogAnalyzer/tests/TestParams.py new file mode 100644 index 0000000000..3ccff6271d --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestParams.py @@ -0,0 +1,52 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + +import math # for isnan() + + +class TestParams(Test): + '''test for any obviously bad parameters in the config''' + + def __init__(self): + self.name = "Parameters" + + def __checkParamIsEqual(self, paramName, expectedValue, logdata): + value = logdata.parameters[paramName] + if value != expectedValue: + self.result.status = TestResult.StatusType.FAIL + self.result.extraFeedback = self.result.extraFeedback + "%s set to %s, expecting %s\n" % (paramName, `value`, `expectedValue`) + + def __checkParamIsLessThan(self, paramName, maxValue, logdata): + value = logdata.parameters[paramName] + if value >= maxValue: + self.result.status = TestResult.StatusType.FAIL + self.result.extraFeedback = self.result.extraFeedback + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `maxValue`) + + def __checkParamIsMoreThan(self, paramName, minValue, logdata): + value = logdata.parameters[paramName] + if value <= minValue: + self.result.status = TestResult.StatusType.FAIL + self.result.extraFeedback = self.result.extraFeedback + "%s set to %s, expecting less than %s\n" % (paramName, `value`, `minValue`) + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS # PASS by default, tests below will override it if they fail + + # check all params for NaN + for name,value in logdata.parameters.iteritems(): + if math.isnan(value): + self.result.status = TestResult.StatusType.FAIL + self.result.extraFeedback = self.result.extraFeedback + name + " is NaN\n" + + # add parameter checks below using the helper functions, any failures will trigger a FAIL status and accumulate info in extraFeedback + # if more complex checking or correlations are required you can access parameter values directly using the logdata.parameters[paramName] dict + if logdata.vehicleType == "ArduCopter": + self.__checkParamIsEqual ("MAG_ENABLE", 1, logdata) + self.__checkParamIsLessThan("THR_MIN", 200, logdata) + self.__checkParamIsLessThan("THR_MID", 650, logdata) + self.__checkParamIsMoreThan("THR_MID", 300, logdata) + # TODO: add more parameter tests, these are just an example... + elif logdata.vehicleType == "ArduPlane": + # TODO: add parameter checks for plane... + pass + diff --git a/Tools/LogAnalyzer/tests/TestPerformance.py b/Tools/LogAnalyzer/tests/TestPerformance.py new file mode 100644 index 0000000000..48d4760f7e --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestPerformance.py @@ -0,0 +1,16 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestPerformance(Test): + '''check performance monitoring messages (PM) for issues with slow loops, etc''' + + def __init__(self): + self.name = "Performance" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + + # TODO: test for performance warning messages, slow loops, etc diff --git a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py new file mode 100644 index 0000000000..bcd8865bb6 --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py @@ -0,0 +1,18 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestPitchRollCoupling(Test): + '''test for divergence between input and output pitch/roll, i.e. mechanical failure or bad PID tuning''' + + def __init__(self): + self.name = "Pitch/Roll" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + # TODO: implement pitch/roll input/output divergence testing - + + # note: names changed from PitchIn to DesPitch at some point, check for both + \ No newline at end of file diff --git a/Tools/LogAnalyzer/tests/TestUnderpowered.py b/Tools/LogAnalyzer/tests/TestUnderpowered.py new file mode 100644 index 0000000000..5dec859071 --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestUnderpowered.py @@ -0,0 +1,18 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + + +class TestUnderpowered(Test): + '''test for underpowered copter''' + + def __init__(self): + self.name = "Underpowered" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + if logdata.vehicleType == "ArduPlane": + self.result.status = TestResult.StatusType.NA + + # TODO: implement test for underpowered copter (use log Randy provided) diff --git a/Tools/LogAnalyzer/tests/TestVCC.py b/Tools/LogAnalyzer/tests/TestVCC.py new file mode 100644 index 0000000000..f127469761 --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestVCC.py @@ -0,0 +1,34 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + +import collections + + +class TestVCC(Test): + '''test for VCC within recommendations, or abrupt end to log in flight''' + + def __init__(self): + self.name = "VCC" + + def run(self, logdata): + self.result = TestResult() + self.result.status = TestResult.StatusType.PASS + + if not "CURR" in logdata.channels: + self.result.status = TestResult.StatusType.UNKNOWN + self.result.statusMessage = "No CURR log data found" + return + + # just a naive min/max test for now + vccMin = logdata.channels["CURR"]["Vcc"].min() + vccMax = logdata.channels["CURR"]["Vcc"].max() + vccDiff = vccMax - vccMin; + vccMinThreshold = 4.6 * 1000; + vccMaxDiff = 0.3 * 1000; + if vccDiff > vccMaxDiff: + self.result.status = TestResult.StatusType.WARN + self.result.statusMessage = "VCC min/max diff %s, should be <%s" % (vccDiff/1000.0, vccMaxDiff/1000.0) + elif vccMin < vccMinThreshold: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "VCC below minimum of %s (%s)" % (`vccMinThreshold/1000.0`,`vccMin/1000.0`) + diff --git a/Tools/LogAnalyzer/tests/TestVibration.py b/Tools/LogAnalyzer/tests/TestVibration.py new file mode 100644 index 0000000000..49282a67cc --- /dev/null +++ b/Tools/LogAnalyzer/tests/TestVibration.py @@ -0,0 +1,63 @@ +from LogAnalyzer import Test,TestResult +import DataflashLog + +import numpy + + +class TestVibration(Test): + '''test for accelerometer vibration (accX/accY/accZ) within recommendations''' + + def __init__(self): + self.name = "Vibration" + + + def run(self, logdata): + self.result = TestResult() + + # constants + gravity = -9.81 + aimRangeWarnXY = 1.5 + aimRangeFailXY = 3.0 + aimRangeWarnZ = 2.0 # gravity +/- aim range + aimRangeFailZ = 5.0 # gravity +/- aim range + + # TODO: in Pixhawk should we use IMU or IMU2? + if not "IMU" in logdata.channels: + self.result.status = TestResult.StatusType.UNKNOWN + self.result.statusMessage = "No IMU log data found" + return + + # find some stable LOITER data to analyze, at least 10 seconds + chunks = DataflashLog.DataflashLogHelper.findLoiterChunks(logdata, minLengthSeconds=10, noRCInputs=True) + if not chunks: + self.result.status = TestResult.StatusType.UNKNOWN + self.result.statusMessage = "No stable LOITER log data found" + return + + # for now we'll just use the first (largest) chunk of LOITER data + # TODO: ignore the first couple of secs to avoid bad data during transition - or can we check more analytically that we're stable? + # TODO: accumulate all LOITER chunks over min size, or just use the largest one? + startLine = chunks[0][0] + endLine = chunks[0][1] + #print "TestVibration using LOITER chunk from lines %s to %s" % (`startLine`, `endLine`) + + def getStdDevIMU(logdata, channelName, startLine,endLine): + loiterData = logdata.channels["IMU"][channelName].getSegment(startLine,endLine) + numpyData = numpy.array(loiterData.dictData.values()) + return numpy.std(numpyData) + + # use 2x standard deviations as the metric, so if 95% of samples lie within the aim range we're good + stdDevX = abs(2 * getStdDevIMU(logdata,"AccX",startLine,endLine)) + stdDevY = abs(2 * getStdDevIMU(logdata,"AccY",startLine,endLine)) + stdDevZ = abs(2 * getStdDevIMU(logdata,"AccZ",startLine,endLine)) + if (stdDevX > aimRangeFailXY) or (stdDevY > aimRangeFailXY) or (stdDevZ > aimRangeFailZ): + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Vibration too high (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX,stdDevY,stdDevZ) + elif (stdDevX > aimRangeWarnXY) or (stdDevY > aimRangeWarnXY) or (stdDevZ > aimRangeWarnZ): + self.result.status = TestResult.StatusType.WARN + self.result.statusMessage = "Vibration slightly high (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX,stdDevY,stdDevZ) + else: + self.result.status = TestResult.StatusType.PASS + self.result.statusMessage = "Good vibration values (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX,stdDevY,stdDevZ) + +