Tools: Web: FilterReview: update to latest version on of parser from https://github.com/Williangalvani/JsDataflashParser

This commit is contained in:
Iampete1 2023-05-11 23:48:05 +01:00 committed by Andrew Tridgell
parent 925e9d8cbc
commit 819b867b00
1 changed files with 149 additions and 164 deletions

View File

@ -127,16 +127,16 @@ const multipliers = {
'-': 0, // no multiplier e.g. a string '-': 0, // no multiplier e.g. a string
'?': 1, // multipliers which haven't been worked out yet.... '?': 1, // multipliers which haven't been worked out yet....
// <leave a gap here, just in case....> // <leave a gap here, just in case....>
2: 1e2, '2': 1e2,
1: 1e1, '1': 1e1,
0: 1e0, '0': 1e0,
A: 1e-1, 'A': 1e-1,
B: 1e-2, 'B': 1e-2,
C: 1e-3, 'C': 1e-3,
D: 1e-4, 'D': 1e-4,
E: 1e-5, 'E': 1e-5,
F: 1e-6, 'F': 1e-6,
G: 1e-7, 'G': 1e-7,
// <leave a gap here, just in case....> // <leave a gap here, just in case....>
'!': 3.6, // (ampere*second => milliampere*hour) and (km/h => m/s) '!': 3.6, // (ampere*second => milliampere*hour) and (km/h => m/s)
'/': 3600 // (ampere*second => ampere*hour) '/': 3600 // (ampere*second => ampere*hour)
@ -154,36 +154,36 @@ const HEAD2 = 149
const units = { const units = {
'-': '', // no units e.g. Pi, or a string '-': '', // no units e.g. Pi, or a string
'?': 'UNKNOWN', // Units which haven't been worked out yet.... '?': 'UNKNOWN', // Units which haven't been worked out yet....
A: 'A', // Ampere 'A': 'A', // Ampere
d: '°', // of the angular variety, -180 to 180 'd': '°', // of the angular variety, -180 to 180
b: 'B', // bytes 'b': 'B', // bytes
k: '°/s', // degrees per second. Degrees are NOT SI, but is some situations more user-friendly than radians 'k': '°/s', // degrees per second. Degrees are NOT SI, but is some situations more user-friendly than radians
D: '°', // degrees of latitude 'D': '°', // degrees of latitude
e: '°/s/s', // degrees per second per second. Degrees are NOT SI, but is some situations more user-friendly 'e': '°/s/s', // degrees per second per second. Degrees are NOT SI, but is some situations more user-friendly
E: 'rad/s', // radians per second 'E': 'rad/s', // radians per second
G: 'Gauss', // Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here 'G': 'Gauss', // Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
h: '°', // 0.? to 359.? 'h': '°', // 0.? to 359.?
i: 'A.s', // Ampere second 'i': 'A.s', // Ampere second
J: 'W.s', // Joule (Watt second) 'J': 'W.s', // Joule (Watt second)
// { 'l', "l" }, // litres // { 'l', "l" }, // litres
L: 'rad/s/s', // radians per second per second 'L': 'rad/s/s', // radians per second per second
m: 'm', // metres 'm': 'm', // metres
n: 'm/s', // metres per second 'n': 'm/s', // metres per second
// { 'N', "N" }, // Newton // { 'N', "N" }, // Newton
o: 'm/s/s', // metres per second per second 'o': 'm/s/s', // metres per second per second
O: '°C', // degrees Celsius. Not SI, but Kelvin is too cumbersome for most users 'O': '°C', // degrees Celsius. Not SI, but Kelvin is too cumbersome for most users
'%': '%', // percent '%': '%', // percent
S: 'satellites', // number of satellites 'S': 'satellites', // number of satellites
s: 's', // seconds 's': 's', // seconds
q: 'rpm', // rounds per minute. Not SI, but sometimes more intuitive than Hertz 'q': 'rpm', // rounds per minute. Not SI, but sometimes more intuitive than Hertz
r: 'rad', // radians 'r': 'rad', // radians
U: '°', // degrees of longitude 'U': '°', // degrees of longitude
u: 'ppm', // pulses per minute 'u': 'ppm', // pulses per minute
v: 'V', // Volt 'v': 'V', // Volt
P: 'Pa', // Pascal 'P': 'Pa', // Pascal
w: 'Ohm', // Ohm 'w': 'Ohm', // Ohm
Y: 'us', // pulse width modulation in microseconds 'Y': 'us', // pulse width modulation in microseconds
z: 'Hz', // Hertz 'z': 'Hz', // Hertz
'#': 'instance' // instance number for message '#': 'instance' // instance number for message
} }
@ -216,7 +216,7 @@ function getModeMap (mavType) {
} }
function assignColumn (obj) { function assignColumn (obj) {
const ArrayOfString = obj.split(',') var ArrayOfString = obj.split(',')
return ArrayOfString return ArrayOfString
} }
@ -238,11 +238,11 @@ class DataflashParser {
this.data = null this.data = null
this.FMT = [] this.FMT = []
this.FMT[128] = { this.FMT[128] = {
Type: '128', 'Type': '128',
length: '89', 'length': '89',
Name: 'FMT', 'Name': 'FMT',
Format: 'BBnNZ', 'Format': 'BBnNZ',
Columns: 'Type,Length,Name,Format,Columns' 'Columns': 'Type,Length,Name,Format,Columns'
} }
this.offset = 0 this.offset = 0
this.msgType = [] this.msgType = []
@ -257,13 +257,13 @@ class DataflashParser {
} }
FORMAT_TO_STRUCT (obj) { FORMAT_TO_STRUCT (obj) {
let temp var temp
const dict = { var dict = {
name: obj.Name, name: obj.Name,
fieldnames: obj.Columns.split(',') fieldnames: obj.Columns.split(',')
} }
const column = assignColumn(obj.Columns) let column = assignColumn(obj.Columns)
let low let low
let n let n
for (let i = 0; i < obj.Format.length; i++) { for (let i = 0; i < obj.Format.length; i++) {
@ -376,7 +376,7 @@ class DataflashParser {
} }
gpstimetoTime (week, msec) { gpstimetoTime (week, msec) {
const epoch = 86400 * (10 * 365 + (1980 - 1969) / 4 + 1 + 6 - 2) let epoch = 86400 * (10 * 365 + (1980 - 1969) / 4 + 1 + 6 - 2)
return epoch + 86400 * 7 * week + msec * 0.001 - 15 return epoch + 86400 * 7 * week + msec * 0.001 - 15
} }
@ -385,8 +385,8 @@ class DataflashParser {
} }
findTimeBase (gps) { findTimeBase (gps) {
const temp = this.gpstimetoTime(parseInt(gps.GWk), parseInt(gps.GMS)) const temp = this.gpstimetoTime(parseInt(gps['GWk']), parseInt(gps['GMS']))
this.setTimeBase(parseInt(temp - gps.TimeUS * 0.000001)) this.setTimeBase(parseInt(temp - gps['TimeUS'] * 0.000001))
} }
getMsgType (element) { getMsgType (element) {
@ -409,20 +409,20 @@ class DataflashParser {
} else { } else {
this.messages[message.name] = [this.fixData(message)] this.messages[message.name] = [this.fixData(message)]
} }
const percentage = 100 * this.offset / this.totalSize let percentage = 100 * this.offset / this.totalSize
if ((percentage - this.lastPercentage) > this.maxPercentageInterval) { if ((percentage - this.lastPercentage) > this.maxPercentageInterval) {
self.postMessage({ percentage: percentage }) self.postMessage({percentage: percentage})
this.lastPercentage = percentage this.lastPercentage = percentage
} }
} }
messageHasInstances (name) { messageHasInstances (name) {
const type = this.FMT.find(msg => msg !== undefined && msg.Name === name) let type = this.FMT.find(msg => msg !== undefined && msg.Name === name)
return type !== undefined && type.units !== undefined && type.units.indexOf('instance') !== -1 return type !== undefined && type.units !== undefined && type.units.includes('instance')
} }
getInstancesFieldName (name) { getInstancesFieldName (name) {
const type = this.FMT.find(msg => msg !== undefined && msg.Name === name) let type = this.FMT.find(msg => msg !== undefined && msg.Name === name)
if (type.units === undefined) { if (type.units === undefined) {
return null return null
} }
@ -439,9 +439,9 @@ class DataflashParser {
} }
postData (data) { postData (data) {
data.dataType = {} data['dataType'] = {}
const transferables = [] const transferables = []
for (const field of Object.keys(data.messageList)) { for (let field of Object.keys(data.messageList)) {
const arrayType = this.getType(data.messageList[field]) const arrayType = this.getType(data.messageList[field])
if (arrayType) { if (arrayType) {
transferables.push(data.messageList[field].buffer) transferables.push(data.messageList[field].buffer)
@ -452,22 +452,15 @@ class DataflashParser {
self.postMessage(data, transferables) self.postMessage(data, transferables)
} }
extractTimeMetadataFromGPS () {
const metadata = {
startTime: this.extractStartTime()
}
self.postMessage({ metadata: metadata })
}
parseAtOffset (name) { parseAtOffset (name) {
const type = this.getMsgType(name) let type = this.getMsgType(name)
const parsed = [] var parsed = []
for (let i = 0; i < this.msgType.length; i++) { for (var i = 0; i < this.msgType.length; i++) {
if (type === this.msgType[i]) { if (type === this.msgType[i]) {
this.offset = this.offsetArray[i] this.offset = this.offsetArray[i]
try { try {
const temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]]) let temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]])
if (temp.name != null) { if (temp['name'] != null) {
parsed.push(this.fixData(temp)) parsed.push(this.fixData(temp))
} }
} catch (e) { } catch (e) {
@ -476,52 +469,43 @@ class DataflashParser {
} }
} }
if (i % 100000 === 0) { if (i % 100000 === 0) {
const perc = 100 * i / this.msgType.length let perc = 100 * i / this.msgType.length
self.postMessage({ percentage: perc }) self.postMessage({percentage: perc})
} }
} }
delete this.messages[name] delete this.messages[name]
this.messages[name] = parsed this.messages[name] = parsed
self.postMessage({ percentage: 100 }) self.postMessage({percentage: 100})
console.log(name, this.messageHasInstances(name) ? 'has instances' : 'has no instances') console.log(name, this.messageHasInstances(name) ? 'has instances' : 'has no instances')
if (parsed.length && this.messageHasInstances(name)) { if (parsed.length && this.messageHasInstances(name)) {
const instanceField = this.getInstancesFieldName(name) let instanceField = this.getInstancesFieldName(name)
const instances = {} let instances = {}
for (const msg of parsed) { for (let msg of parsed) {
try { try {
instances[msg[instanceField]].push(msg) instances[msg[instanceField]].push(msg)
} catch (e) { } catch (e) {
instances[msg[instanceField]] = [msg] instances[msg[instanceField]] = [ msg ]
} }
} }
if (Object.keys(instances).length === 1) { if (Object.keys(instances).length === 1) {
this.fixDataOnce(name) this.fixDataOnce(name)
this.simplifyData(name) this.simplifyData(name)
this.postData({messageType: name, messageList: this.messages[name]})
if (name === 'GPS') {
this.extractTimeMetadataFromGPS()
}
this.postData({ messageType: name, messageList: this.messages[name] })
return parsed return parsed
} }
for (const [index, messages] of Object.entries(instances)) { for (let [index, messages] of Object.entries(instances)) {
const newName = name + '[' + index + ']' let newName = name + '[' + index + ']'
this.messages[newName] = messages this.messages[newName] = messages
this.fixDataOnce(newName) this.fixDataOnce(newName)
this.simplifyData(newName) this.simplifyData(newName)
this.postData({ this.postData({messageType: newName,
messageType: newName, messageList: this.messages[newName]})
messageList: this.messages[newName]
})
} }
} else if (parsed.length) { } else if (parsed.length) {
this.fixDataOnce(name) this.fixDataOnce(name)
this.simplifyData(name) this.simplifyData(name)
if (name === 'GPS') { this.postData({messageType: name, messageList: this.messages[name]})
this.extractTimeMetadataFromGPS()
}
this.postData({ messageType: name, messageList: this.messages[name] })
} }
this.alreadyParsed.push(name) this.alreadyParsed.push(name)
return parsed return parsed
@ -529,26 +513,26 @@ class DataflashParser {
checkNumberOfInstances (name) { checkNumberOfInstances (name) {
// Similar to parseOffset, but finishes earlier and updates messageTypes // Similar to parseOffset, but finishes earlier and updates messageTypes
const type = this.getMsgType(name) let type = this.getMsgType(name)
const availableInstances = [] let availableInstances = []
const instanceField = this.getInstancesFieldName(name) let instanceField = this.getInstancesFieldName(name)
if (instanceField === null) { if (instanceField === null) {
return [1] return [1]
} }
let repeats = 0 let repeats = 0
for (let i = 0; i < this.msgType.length; i++) { for (var i = 0; i < this.msgType.length; i++) {
if (type === this.msgType[i]) { if (type === this.msgType[i]) {
this.offset = this.offsetArray[i] this.offset = this.offsetArray[i]
try { try {
const temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]]) let temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]])
if (temp.name != null) { if (temp['name'] != null) {
const msg = temp let msg = temp
if (msg[instanceField] === undefined) { if (!msg.hasOwnProperty(instanceField)) {
break break
} }
// we do an early return after we get 20 repeated instance numbers. should we? // we do an early return after we get 20 repeated instance numbers. should we?
const instance = msg[instanceField] const instance = msg[instanceField]
if (availableInstances.indexOf(instance) !== -1) { if (availableInstances.includes(instance)) {
repeats += 1 repeats += 1
if (repeats > 20) { if (repeats > 20) {
return availableInstances return availableInstances
@ -566,17 +550,17 @@ class DataflashParser {
} }
timestamp (TimeUs) { timestamp (TimeUs) {
const temp = this.timebase + TimeUs * 0.000001 let temp = this.timebase + TimeUs * 0.000001
if (temp > 0) { if (temp > 0) {
TimeUs = temp TimeUs = temp
} }
let date = new Date(TimeUs * 1000) let date = new Date(TimeUs * 1000)
const hours = date.getHours() let hours = date.getHours()
const minutes = '0' + date.getMinutes() let minutes = '0' + date.getMinutes()
const seconds = '0' + date.getSeconds() let seconds = '0' + date.getSeconds()
const formattedTime = hours + ':' + minutes.substr(-2) + ':' + seconds.substr(-2) let formattedTime = hours + ':' + minutes.substr(-2) + ':' + seconds.substr(-2)
date = date.toString() date = date.toString()
const time = date.split(' ') let time = date.split(' ')
if (time[0] !== 'Invalid') { if (time[0] !== 'Invalid') {
this.time = time[0] + ' ' + time[1] + ' ' + time[2] + ' ' + time[3] this.time = time[0] + ' ' + time[1] + ' ' + time[2] + ' ' + time[3]
} }
@ -592,14 +576,13 @@ class DataflashParser {
} }
this.offset += 2 this.offset += 2
const attribute = this.data.getUint8(this.offset) let attribute = this.data.getUint8(this.offset)
if (this.FMT[attribute] != null) { if (this.FMT[attribute] != null) {
this.offset += 1 this.offset += 1
this.offsetArray.push(this.offset) this.offsetArray.push(this.offset)
this.msgType.push(attribute) this.msgType.push(attribute)
let value
try { try {
value = this.FORMAT_TO_STRUCT(this.FMT[attribute]) var value = this.FORMAT_TO_STRUCT(this.FMT[attribute])
if (this.FMT[attribute].Name === 'GPS') { if (this.FMT[attribute].Name === 'GPS') {
this.findTimeBase(value) this.findTimeBase(value)
} }
@ -607,15 +590,14 @@ class DataflashParser {
// console.log('reached log end?') // console.log('reached log end?')
// console.log(e) // console.log(e)
this.offset += 1 this.offset += 1
continue
} }
if (attribute === 128) { if (attribute === 128) {
this.FMT[value.Type] = { this.FMT[value['Type']] = {
Type: value.Type, 'Type': value['Type'],
length: value.Length, 'length': value['Length'],
Name: value.Name, 'Name': value['Name'],
Format: value.Format, 'Format': value['Format'],
Columns: value.Columns 'Columns': value['Columns']
} }
} }
// this.onMessage(value) // this.onMessage(value)
@ -623,20 +605,20 @@ class DataflashParser {
this.offset += 1 this.offset += 1
} }
if (this.offset - lastOffset > 50000) { if (this.offset - lastOffset > 50000) {
const perc = 100 * this.offset / this.buffer.byteLength let perc = 100 * this.offset / this.buffer.byteLength
self.postMessage({ percentage: perc }) self.postMessage({percentage: perc})
lastOffset = this.offset lastOffset = this.offset
} }
} }
self.postMessage({ percentage: 100 }) self.postMessage({percentage: 100})
self.postMessage({ messages: this.messages }) self.postMessage({messages: this.messages})
this.sent = true this.sent = true
} }
getModeString (cmode) { getModeString (cmode) {
let mavtype let mavtype
const msgs = this.messages.MSG let msgs = this.messages['MSG']
for (const i in msgs.Message) { for (let i in msgs.Message) {
if (msgs.Message[i].toLowerCase().includes('arduplane')) { if (msgs.Message[i].toLowerCase().includes('arduplane')) {
mavtype = MAV_TYPE_FIXED_WING mavtype = MAV_TYPE_FIXED_WING
return getModeMap(mavtype)[cmode] return getModeMap(mavtype)[cmode]
@ -660,7 +642,7 @@ class DataflashParser {
fixData (message) { fixData (message) {
if (message.name === 'MODE') { if (message.name === 'MODE') {
message.asText = this.getModeString(message.Mode) message.asText = this.getModeString(message['Mode'])
} }
// eslint-disable-next-line // eslint-disable-next-line
message.time_boot_ms = message.TimeUS / 1000 message.time_boot_ms = message.TimeUS / 1000
@ -670,13 +652,13 @@ class DataflashParser {
} }
fixDataOnce (name) { fixDataOnce (name) {
if (['GPS', 'ATT', 'AHR2', 'MODE'].indexOf(name) === -1) { if (!['GPS', 'ATT', 'AHR2', 'MODE'].includes(name)) {
if (this.messageTypes[name]) { if (this.messageTypes.hasOwnProperty(name)) {
const fields = this.messages[name][0].fieldnames let fields = this.messages[name][0].fieldnames
if (this.messageTypes[name].multipliers) { if (this.messageTypes[name].hasOwnProperty('multipliers')) {
for (const message in this.messages[name]) { for (let message in this.messages[name]) {
for (let i = 1; i < fields.length; i++) { for (let i = 1; i < fields.length; i++) {
const fieldname = fields[i] let fieldname = fields[i]
if (!isNaN(this.messageTypes[name].multipliers[i])) { if (!isNaN(this.messageTypes[name].multipliers[i])) {
this.messages[name][message][fieldname] *= this.messageTypes[name].multipliers[i] this.messages[name][message][fieldname] *= this.messageTypes[name].multipliers[i]
} }
@ -688,7 +670,7 @@ class DataflashParser {
} }
concatTypedArrays (a, b) { // a, b TypedArray of same type concatTypedArrays (a, b) { // a, b TypedArray of same type
const c = new (a.constructor)(a.length + b.length) var c = new (a.constructor)(a.length + b.length)
c.set(a, 0) c.set(a, 0)
c.set(b, a.length) c.set(b, a.length)
return c return c
@ -704,8 +686,8 @@ class DataflashParser {
processFiles () { processFiles () {
this.files = {} this.files = {}
for (const msg of this.messages.FILE) { for (let msg of this.messages['FILE']) {
if (!this.files[msg.FileName]) { if (!this.files.hasOwnProperty(msg.FileName)) {
this.files[msg.FileName] = this.createUint8ArrayFromString(msg.Data) this.files[msg.FileName] = this.createUint8ArrayFromString(msg.Data)
} else { } else {
this.files[msg.FileName] = this.concatTypedArrays( this.files[msg.FileName] = this.concatTypedArrays(
@ -713,7 +695,7 @@ class DataflashParser {
) )
} }
} }
self.postMessage({ files: this.files }) self.postMessage({files: this.files})
} }
simplifyData (name) { simplifyData (name) {
@ -723,19 +705,19 @@ class DataflashParser {
if (name === 'FILE') { if (name === 'FILE') {
return return
} }
if (['FMTU'].indexOf(name) === -1) { if (!['FMTU'].includes(name)) {
if (this.messageTypes[name]) { if (this.messageTypes.hasOwnProperty(name)) {
const fields = this.messageTypes[name].expressions let fields = this.messageTypes[name].expressions
if (!fields.includes('time_boot_ms')) { if (!fields.includes('time_boot_ms')) {
fields.push('time_boot_ms') fields.push('time_boot_ms')
} }
const mergedData = {} let mergedData = {}
for (const field of fields) { for (let field of fields) {
mergedData[field] = [] mergedData[field] = []
} }
for (const message of this.messages[name]) { for (let message of this.messages[name]) {
for (let i = 1; i < fields.length; i++) { for (let i = 1; i < fields.length; i++) {
const fieldname = fields[i] let fieldname = fields[i]
mergedData[fieldname].push(message[fieldname]) mergedData[fieldname].push(message[fieldname])
} }
} }
@ -754,24 +736,24 @@ class DataflashParser {
populateUnits () { populateUnits () {
// console.log(this.messages['FMTU']) // console.log(this.messages['FMTU'])
for (const msg of this.messages.FMTU) { for (let msg of this.messages['FMTU']) {
this.FMT[msg.FmtType].units = [] this.FMT[msg.FmtType]['units'] = []
for (const unit of msg.UnitIds) { for (let unit of msg.UnitIds) {
this.FMT[msg.FmtType].units.push(units[unit]) this.FMT[msg.FmtType]['units'].push(units[unit])
} }
this.FMT[msg.FmtType].multipliers = [] this.FMT[msg.FmtType]['multipliers'] = []
for (const mult of msg.MultIds) { for (let mult of msg.MultIds) {
this.FMT[msg.FmtType].multipliers.push(multipliers[mult]) this.FMT[msg.FmtType]['multipliers'].push(multipliers[mult])
} }
} }
} }
extractStartTime () { extractStartTime () {
const msgs = this.messages.GPS let msgs = this.messages['GPS']
for (const i in msgs.time_boot_ms) { for (let i in msgs.time_boot_ms) {
if (msgs.GWk[i] > 1000) { // lousy validation if (msgs.GWk[i] > 1000) { // lousy validation
const weeks = msgs.GWk[i] let weeks = msgs.GWk[i]
const ms = msgs.GMS[i] let ms = msgs.GMS[i]
let d = new Date((315964800.0 + ((60 * 60 * 24 * 7) * weeks) + ms / 1000.0) * 1000.0) let d = new Date((315964800.0 + ((60 * 60 * 24 * 7) * weeks) + ms / 1000.0) * 1000.0)
// adjusting for leap seconds // adjusting for leap seconds
d = new Date(d.getTime() - this.leapSecondsGPS(d.getUTCFullYear(), d.getUTCMonth() + 1) * 1000) d = new Date(d.getTime() - this.leapSecondsGPS(d.getUTCFullYear(), d.getUTCMonth() + 1) * 1000)
@ -802,18 +784,18 @@ class DataflashParser {
this.buffer = data this.buffer = data
this.data = new DataView(this.buffer) this.data = new DataView(this.buffer)
this.DfReader() this.DfReader()
const messageTypes = {} let messageTypes = {}
this.parseAtOffset('FMTU') this.parseAtOffset('FMTU')
this.populateUnits() this.populateUnits()
const typeSet = new Set(this.msgType) let typeSet = new Set(this.msgType)
for (const msg of this.FMT) { for (let msg of this.FMT) {
if (msg) { if (msg) {
if (typeSet.has(msg.Type)) { if (typeSet.has(msg.Type)) {
const fields = msg.Columns.split(',') let fields = msg.Columns.split(',')
// expressions = expressions.filter(e => e !== 'TimeUS') // expressions = expressions.filter(e => e !== 'TimeUS')
const complexFields = {} let complexFields = {}
if (msg.units) { if (msg.hasOwnProperty('units')) {
for (const field in fields) { for (let field in fields) {
complexFields[fields[field]] = { complexFields[fields[field]] = {
name: fields[field], name: fields[field],
units: (multipliersTable[msg.multipliers[field]] || '') + msg.units[field], units: (multipliersTable[msg.multipliers[field]] || '') + msg.units[field],
@ -821,7 +803,7 @@ class DataflashParser {
} }
} }
} else { } else {
for (const field in fields) { for (let field in fields) {
complexFields[fields[field]] = { complexFields[fields[field]] = {
name: fields[field], name: fields[field],
units: '?', units: '?',
@ -829,9 +811,9 @@ class DataflashParser {
} }
} }
} }
const availableInstances = this.checkNumberOfInstances(msg.Name) let availableInstances = this.checkNumberOfInstances(msg.Name)
if (availableInstances.length > 1) { if (availableInstances.length > 1) {
for (const instance of availableInstances) { for (let instance of availableInstances) {
messageTypes[msg.Name + '[' + instance + ']'] = { messageTypes[msg.Name + '[' + instance + ']'] = {
expressions: fields, expressions: fields,
units: msg.units, units: msg.units,
@ -850,7 +832,7 @@ class DataflashParser {
} }
} }
} }
self.postMessage({ availableMessages: messageTypes }) self.postMessage({availableMessages: messageTypes})
this.messageTypes = messageTypes this.messageTypes = messageTypes
this.parseAtOffset('CMD') this.parseAtOffset('CMD')
this.parseAtOffset('MSG') this.parseAtOffset('MSG')
@ -870,10 +852,13 @@ class DataflashParser {
this.parseAtOffset('MSG') this.parseAtOffset('MSG')
this.parseAtOffset('STAT') this.parseAtOffset('STAT')
this.parseAtOffset('EV') this.parseAtOffset('EV')
this.parseAtOffset('FNCE') let metadata = {
startTime: this.extractStartTime()
}
self.postMessage({metadata: metadata})
self.postMessage({ messagesDoneLoading: true }) self.postMessage({messagesDoneLoading: true})
return { types: this.messageTypes, messages: this.messages } return {types: this.messageTypes, messages: this.messages}
} }
loadType (type) { loadType (type) {