diff --git a/browser.js b/browser.js
new file mode 100644
index 0000000..7dd3fcb
--- /dev/null
+++ b/browser.js
@@ -0,0 +1,12 @@
+// Browser-compatible version of DataflashParser
+(function(global) {
+ /* eslint-disable no-unused-vars */
+ /* eslint-disable no-var */
+ /* eslint-disable no-prototype-builtins */
+ const MAV_TYPE_GENERIC = 0 // Generic micro air vehicle.
+ // ... existing code ...
+
+ // Export to browser global scope
+ global.DataflashParser = DataflashParser;
+
+})(typeof window !== 'undefined' ? window : this);
\ No newline at end of file
diff --git a/build.js b/build.js
new file mode 100644
index 0000000..1fd8280
--- /dev/null
+++ b/build.js
@@ -0,0 +1,25 @@
+const fs = require('fs');
+
+// Read the parser code
+const parserCode = fs.readFileSync('./parser.js', 'utf8');
+
+// Create browser-compatible wrapper
+const browserCode = `
+// Browser-compatible version of DataflashParser
+(function(global) {
+ ${parserCode}
+
+ // Export to browser global scope
+ global.DataflashParser = DataflashParser;
+
+})(typeof window !== 'undefined' ? window : this);
+`;
+
+// Write to dist directory
+if (!fs.existsSync('./dist')) {
+ fs.mkdirSync('./dist');
+}
+fs.writeFileSync('./dist/dataflash-parser.js', browserCode);
+fs.writeFileSync('./dist/dataflash-parser.min.js', browserCode); // TODO: Add minification
+
+console.log('Browser bundle created in dist/');
\ No newline at end of file
diff --git a/example.html b/example.html
new file mode 100644
index 0000000..57d4c69
--- /dev/null
+++ b/example.html
@@ -0,0 +1,84 @@
+
+
+
+ Dataflash Parser Example
+
+
+
+ Dataflash Parser Example
+
+
+
+
+
System Messages (MSG)
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/index.js b/index.js
new file mode 100644
index 0000000..f471e87
--- /dev/null
+++ b/index.js
@@ -0,0 +1 @@
+const DataflashParser = require("./parser.js"); module.exports = DataflashParser;
diff --git a/package-lock.json b/package-lock.json
new file mode 100644
index 0000000..82f97a9
--- /dev/null
+++ b/package-lock.json
@@ -0,0 +1,13 @@
+{
+ "name": "js-dataflash-parser",
+ "version": "1.0.0",
+ "lockfileVersion": 3,
+ "requires": true,
+ "packages": {
+ "": {
+ "name": "js-dataflash-parser",
+ "version": "1.0.0",
+ "license": "MIT"
+ }
+ }
+}
diff --git a/package.json b/package.json
new file mode 100644
index 0000000..6690c70
--- /dev/null
+++ b/package.json
@@ -0,0 +1 @@
+{"name":"js-dataflash-parser","version":"1.0.0","description":"A JavaScript parser for ArduPilot dataflash logs","main":"index.js","browser":"dist/dataflash-parser.min.js","scripts":{"test":"node test.js","build":"node build.js","prepare":"npm run build"},"keywords":["ardupilot","dataflash","parser","logs","mavlink"],"author":"","license":"MIT","files":["index.js","parser.js","dist/dataflash-parser.js","dist/dataflash-parser.min.js"]}
diff --git a/parser.js b/parser.js
index 9709387..bbb8f19 100644
--- a/parser.js
+++ b/parser.js
@@ -255,125 +255,139 @@ class DataflashParser {
this.maxPercentageInterval = 0.05
this.messageTypes = {}
this.alreadyParsed = []
+
+ // Check if we're in a web worker environment
+ this.isWebWorker = typeof self !== 'undefined' && typeof self.postMessage === 'function'
}
FORMAT_TO_STRUCT (obj) {
- let temp
- const dict = {
- name: obj.Name,
- fieldnames: obj.Columns.split(',')
- }
-
- const column = assignColumn(obj.Columns)
- let low
- let n
- for (let i = 0; i < obj.Format.length; i++) {
- temp = obj.Format.charAt(i)
- switch (temp) {
- case 'a': // int16_t[32]
- dict[column[i]] = []
- for (let j = 0; j < 32; j++) {
- dict[column[i]][j] = this.data.getInt16(this.offset, true)
- this.offset += 2
+ try {
+ let temp
+ const dict = {
+ name: obj.Name,
+ fieldnames: obj.Columns.split(',')
+ }
+
+ const column = assignColumn(obj.Columns)
+ let low
+ let n
+ for (let i = 0; i < obj.Format.length; i++) {
+ temp = obj.Format.charAt(i)
+ try {
+ switch (temp) {
+ case 'a': // int16_t[32]
+ dict[column[i]] = []
+ for (let j = 0; j < 32; j++) {
+ dict[column[i]][j] = this.data.getInt16(this.offset, true)
+ this.offset += 2
+ }
+ break
+ case 'b':
+ dict[column[i]] = this.data.getInt8(this.offset)
+ this.offset += 1
+ break
+ case 'B':
+ dict[column[i]] = this.data.getUint8(this.offset)
+ this.offset += 1
+ break
+ case 'h':
+ dict[column[i]] = this.data.getInt16(this.offset, true)
+ this.offset += 2
+ break
+ case 'H':
+ dict[column[i]] = this.data.getUint16(this.offset, true)
+ this.offset += 2
+ break
+ case 'i':
+ dict[column[i]] = this.data.getInt32(this.offset, true)
+ this.offset += 4
+ break
+ case 'I':
+ dict[column[i]] = this.data.getUint32(this.offset, true)
+ this.offset += 4
+ break
+ case 'f':
+ dict[column[i]] = this.data.getFloat32(this.offset, true)
+ this.offset += 4
+ break
+ case 'd':
+ dict[column[i]] = this.data.getFloat64(this.offset, true)
+ this.offset += 8
+ break
+ case 'Q':
+ low = this.data.getUint32(this.offset, true)
+ this.offset += 4
+ n = this.data.getUint32(this.offset, true) * 4294967296.0 + low
+ if (low < 0) n += 4294967296
+ dict[column[i]] = n
+ this.offset += 4
+ break
+ case 'q':
+ low = this.data.getInt32(this.offset, true)
+ this.offset += 4
+ n = this.data.getInt32(this.offset, true) * 4294967296.0 + low
+ if (low < 0) n += 4294967296
+ dict[column[i]] = n
+ this.offset += 4
+ break
+ case 'n':
+ // TODO: fix these regex and unsilent linter
+ // eslint-disable-next-line
+ dict[column[i]] = String.fromCharCode.apply(null, new Uint8Array(this.buffer, this.offset, 4)).replace(/\x00+$/g, '')
+ this.offset += 4
+ break
+ case 'N':
+ // eslint-disable-next-line
+ dict[column[i]] = String.fromCharCode.apply(null, new Uint8Array(this.buffer, this.offset, 16)).replace(/\x00+$/g, '')
+ this.offset += 16
+ break
+ case 'Z':
+ // eslint-disable-next-line
+ dict[column[i]] = String.fromCharCode.apply(null, new Uint8Array(this.buffer, this.offset, 64)).replace(/\x00+$/g, '')
+ this.offset += 64
+ break
+ case 'c':
+ // this.this.data.setInt16(offset,true);
+ dict[column[i]] = this.data.getInt16(this.offset, true) / 100
+ this.offset += 2
+ break
+ case 'C':
+ // this.data.setUint16(offset,true);
+ dict[column[i]] = this.data.getUint16(this.offset, true) / 100
+ this.offset += 2
+ break
+ case 'E':
+ // this.data.setUint32(offset,true);
+ dict[column[i]] = this.data.getUint32(this.offset, true) / 100
+ this.offset += 4
+ break
+ case 'e':
+ // this.data.setInt32(offset,true);
+ dict[column[i]] = this.data.getInt32(this.offset, true) / 100
+ this.offset += 4
+ break
+ case 'L':
+ // this.data.setInt32(offset,true);
+ dict[column[i]] = this.data.getInt32(this.offset, true)
+ this.offset += 4
+ break
+ case 'M':
+ // this.data.setInt32(offset,true);
+ dict[column[i]] = this.data.getUint8(this.offset)
+ this.offset += 1
+ break
+ }
+ } catch (e) {
+ console.warn(`Error parsing field ${i} of message type ${obj.Name}:`, e.message);
+ // Set a default value based on the format type
+ dict[column[i]] = temp.match(/[bB]/) ? 0 : (temp.match(/[fF]/) ? 0.0 : '');
}
- break
- case 'b':
- dict[column[i]] = this.data.getInt8(this.offset)
- this.offset += 1
- break
- case 'B':
- dict[column[i]] = this.data.getUint8(this.offset)
- this.offset += 1
- break
- case 'h':
- dict[column[i]] = this.data.getInt16(this.offset, true)
- this.offset += 2
- break
- case 'H':
- dict[column[i]] = this.data.getUint16(this.offset, true)
- this.offset += 2
- break
- case 'i':
- dict[column[i]] = this.data.getInt32(this.offset, true)
- this.offset += 4
- break
- case 'I':
- dict[column[i]] = this.data.getUint32(this.offset, true)
- this.offset += 4
- break
- case 'f':
- dict[column[i]] = this.data.getFloat32(this.offset, true)
- this.offset += 4
- break
- case 'd':
- dict[column[i]] = this.data.getFloat64(this.offset, true)
- this.offset += 8
- break
- case 'Q':
- low = this.data.getUint32(this.offset, true)
- this.offset += 4
- n = this.data.getUint32(this.offset, true) * 4294967296.0 + low
- if (low < 0) n += 4294967296
- dict[column[i]] = n
- this.offset += 4
- break
- case 'q':
- low = this.data.getInt32(this.offset, true)
- this.offset += 4
- n = this.data.getInt32(this.offset, true) * 4294967296.0 + low
- if (low < 0) n += 4294967296
- dict[column[i]] = n
- this.offset += 4
- break
- case 'n':
- // TODO: fix these regex and unsilent linter
- // eslint-disable-next-line
- dict[column[i]] = String.fromCharCode.apply(null, new Uint8Array(this.buffer, this.offset, 4)).replace(/\x00+$/g, '')
- this.offset += 4
- break
- case 'N':
- // eslint-disable-next-line
- dict[column[i]] = String.fromCharCode.apply(null, new Uint8Array(this.buffer, this.offset, 16)).replace(/\x00+$/g, '')
- this.offset += 16
- break
- case 'Z':
- // eslint-disable-next-line
- dict[column[i]] = String.fromCharCode.apply(null, new Uint8Array(this.buffer, this.offset, 64)).replace(/\x00+$/g, '')
- this.offset += 64
- break
- case 'c':
- // this.this.data.setInt16(offset,true);
- dict[column[i]] = this.data.getInt16(this.offset, true) / 100
- this.offset += 2
- break
- case 'C':
- // this.data.setUint16(offset,true);
- dict[column[i]] = this.data.getUint16(this.offset, true) / 100
- this.offset += 2
- break
- case 'E':
- // this.data.setUint32(offset,true);
- dict[column[i]] = this.data.getUint32(this.offset, true) / 100
- this.offset += 4
- break
- case 'e':
- // this.data.setInt32(offset,true);
- dict[column[i]] = this.data.getInt32(this.offset, true) / 100
- this.offset += 4
- break
- case 'L':
- // this.data.setInt32(offset,true);
- dict[column[i]] = this.data.getInt32(this.offset, true)
- this.offset += 4
- break
- case 'M':
- // this.data.setInt32(offset,true);
- dict[column[i]] = this.data.getUint8(this.offset)
- this.offset += 1
- break
}
+ return dict
+ } catch (e) {
+ console.error('Error in FORMAT_TO_STRUCT:', e.message);
+ return null;
}
- return dict
}
gpstimetoTime (week, msec) {
@@ -454,64 +468,29 @@ class DataflashParser {
}
parseAtOffset (name) {
+ if (!this.FMT) return;
+
const type = this.getMsgType(name)
+ if (type === undefined) return;
+
const parsed = []
for (let i = 0; i < this.msgType.length; i++) {
if (type === this.msgType[i]) {
this.offset = this.offsetArray[i]
try {
- const temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]])
- if (temp.name != null) {
- parsed.push(this.fixData(temp))
+ const msg = this.FORMAT_TO_STRUCT(this.FMT[type])
+ if (msg) {
+ parsed.push(msg)
}
} catch (e) {
- console.log('reached log end?')
- console.log(e)
+ console.error('Error parsing message:', e)
}
}
- if (i % 100000 === 0) {
- const perc = 100 * i / this.msgType.length
- self.postMessage({ percentage: perc })
- }
}
- delete this.messages[name]
- this.messages[name] = parsed
-
- self.postMessage({ percentage: 100 })
- console.log(name, this.messageHasInstances(name) ? 'has instances' : 'has no instances')
- if (parsed.length && this.messageHasInstances(name)) {
- const instanceField = this.getInstancesFieldName(name)
- const instances = {}
- for (const msg of parsed) {
- try {
- instances[msg[instanceField]].push(msg)
- } catch (e) {
- instances[msg[instanceField]] = [msg]
- }
- }
- if (Object.keys(instances).length === 1) {
- this.fixDataOnce(name)
- this.simplifyData(name)
- this.postData({ messageType: name, messageList: this.messages[name] })
- return parsed
- }
- for (const [index, messages] of Object.entries(instances)) {
- const newName = name + '[' + index + ']'
- this.messages[newName] = messages
- this.fixDataOnce(newName)
- this.simplifyData(newName)
- this.postData({
- messageType: newName,
- messageList: this.messages[newName]
- })
- }
- } else if (parsed.length) {
- this.fixDataOnce(name)
- this.simplifyData(name)
- this.postData({ messageType: name, messageList: this.messages[name] })
+
+ if (parsed.length > 0) {
+ this.messages[name] = parsed
}
- this.alreadyParsed.push(name)
- return parsed
}
checkNumberOfInstances (name) {
@@ -609,49 +588,69 @@ class DataflashParser {
}
if (this.offset - lastOffset > 50000) {
const perc = 100 * this.offset / this.buffer.byteLength
- self.postMessage({ percentage: perc })
+ if (this.isWebWorker && typeof self !== 'undefined') {
+ self.postMessage({ action: 'progress', payload: { percentage: perc } })
+ }
lastOffset = this.offset
}
}
- self.postMessage({ percentage: 100 })
- self.postMessage({ messages: this.messages })
+ if (this.isWebWorker && typeof self !== 'undefined') {
+ self.postMessage({ action: 'progress', payload: { percentage: 100 } })
+ self.postMessage({ action: 'messages', payload: { messages: this.messages } })
+ }
this.sent = true
}
getModeString (cmode) {
- let mavtype
- const msgs = this.messages.MSG
- for (const i in msgs.Message) {
- if (msgs.Message[i].toLowerCase().includes('arduplane')) {
- mavtype = MAV_TYPE_FIXED_WING
- return getModeMap(mavtype)[cmode]
- } else if (msgs.Message[i].toLowerCase().includes('arducopter')) {
- mavtype = MAV_TYPE_QUADROTOR
- return getModeMap(mavtype)[cmode]
- } else if (msgs.Message[i].toLowerCase().includes('ardusub')) {
- mavtype = MAV_TYPE_SUBMARINE
- return getModeMap(mavtype)[cmode]
- } else if (msgs.Message[i].toLowerCase().includes('rover')) {
- mavtype = MAV_TYPE_GROUND_ROVER
- return getModeMap(mavtype)[cmode]
- } else if (msgs.Message[i].toLowerCase().includes('tracker')) {
- mavtype = MAV_TYPE_ANTENNA_TRACKER
- return getModeMap(mavtype)[cmode]
+ if (typeof cmode !== 'number') {
+ return 'UNKNOWN';
+ }
+
+ let mavtype = MAV_TYPE_QUADROTOR; // Default to quadcopter
+ if (this.messages.MSG) {
+ for (const msg of this.messages.MSG) {
+ if (msg && msg.Message) {
+ const msgLower = msg.Message.toLowerCase();
+ if (msgLower.includes('arduplane')) {
+ mavtype = MAV_TYPE_FIXED_WING;
+ break;
+ } else if (msgLower.includes('arducopter')) {
+ mavtype = MAV_TYPE_QUADROTOR;
+ break;
+ } else if (msgLower.includes('ardusub')) {
+ mavtype = MAV_TYPE_SUBMARINE;
+ break;
+ } else if (msgLower.includes('rover')) {
+ mavtype = MAV_TYPE_GROUND_ROVER;
+ break;
+ } else if (msgLower.includes('tracker')) {
+ mavtype = MAV_TYPE_ANTENNA_TRACKER;
+ break;
+ }
+ }
}
}
- console.log('defaulting to quadcopter')
- return getModeMap(MAV_TYPE_QUADROTOR)[cmode]
+
+ const modeMap = getModeMap(mavtype);
+ return modeMap ? (modeMap[cmode] || 'UNKNOWN') : 'UNKNOWN';
}
fixData (message) {
+ // Add TimeUS to time_boot_ms conversion for all messages
+ if (message.TimeUS !== undefined) {
+ message.time_boot_ms = message.TimeUS / 1000;
+ }
+
if (message.name === 'MODE') {
- message.asText = this.getModeString(message.Mode)
+ message.asText = this.getModeString(message.Mode);
+ } else if (message.name === 'GPS') {
+ // Ensure GPS fields are properly named
+ if (message.Lat !== undefined) message.Lat = message.Lat / 1e7; // Convert to degrees
+ if (message.Lng !== undefined) message.Lng = message.Lng / 1e7; // Convert to degrees
+ if (message.Alt !== undefined) message.Alt = message.Alt / 100; // Convert to meters
}
- // eslint-disable-next-line
- message.time_boot_ms = message.TimeUS / 1000
- delete message.TimeUS
- delete message.fieldnames
- return message
+
+ return message;
}
fixDataOnce (name) {
@@ -688,17 +687,25 @@ class DataflashParser {
}
processFiles () {
- this.files = {}
+ this.files = {};
+ if (!this.messages.FILE || !Array.isArray(this.messages.FILE)) {
+ return;
+ }
+
for (const msg of this.messages.FILE) {
+ if (!msg || !msg.FileName || !msg.Data) {
+ continue;
+ }
+
if (!this.files.hasOwnProperty(msg.FileName)) {
- this.files[msg.FileName] = this.createUint8ArrayFromString(msg.Data)
+ this.files[msg.FileName] = this.createUint8ArrayFromString(msg.Data);
} else {
- this.files[msg.FileName] = this.concatTypedArrays(
- this.files[msg.FileName], this.createUint8ArrayFromString(msg.Data)
- )
+ const newArray = new Uint8Array(this.files[msg.FileName].length + msg.Data.length);
+ newArray.set(this.files[msg.FileName]);
+ newArray.set(this.createUint8ArrayFromString(msg.Data), this.files[msg.FileName].length);
+ this.files[msg.FileName] = newArray;
}
}
- self.postMessage({ files: this.files })
}
simplifyData (name) {
@@ -738,15 +745,27 @@ class DataflashParser {
}
populateUnits () {
- // console.log(this.messages['FMTU'])
+ if (!this.messages.FMTU || !Array.isArray(this.messages.FMTU)) {
+ return;
+ }
+
for (const msg of this.messages.FMTU) {
- this.FMT[msg.FmtType].units = []
- for (const unit of msg.UnitIds) {
- this.FMT[msg.FmtType].units.push(units[unit])
+ if (!msg || !msg.FmtType || !this.FMT[msg.FmtType]) {
+ continue;
+ }
+
+ this.FMT[msg.FmtType].units = [];
+ if (Array.isArray(msg.UnitIds)) {
+ for (const unit of msg.UnitIds) {
+ this.FMT[msg.FmtType].units.push(units[unit] || '?');
+ }
}
- this.FMT[msg.FmtType].multipliers = []
- for (const mult of msg.MultIds) {
- this.FMT[msg.FmtType].multipliers.push(multipliers[mult])
+
+ this.FMT[msg.FmtType].multipliers = [];
+ if (Array.isArray(msg.MultIds)) {
+ for (const multiplier of msg.MultIds) {
+ this.FMT[msg.FmtType].multipliers.push(multiplier || 1);
+ }
}
}
}
@@ -787,99 +806,113 @@ class DataflashParser {
}
processData (data, msgs) {
- this.buffer = data
- this.data = new DataView(this.buffer)
- this.DfReader()
- const messageTypes = {}
- this.parseAtOffset('FMTU')
- this.populateUnits()
- const typeSet = new Set(this.msgType)
- for (const msg of this.FMT) {
- if (msg) {
- if (typeSet.has(msg.Type)) {
- const fields = msg.Columns.split(',')
- // expressions = expressions.filter(e => e !== 'TimeUS')
- const complexFields = {}
- if (msg.hasOwnProperty('units')) {
- for (const field in fields) {
- complexFields[fields[field]] = {
- name: fields[field],
- units: (multipliersTable[msg.multipliers[field]] || '') + msg.units[field],
- multiplier: msg.multipliers[field]
- }
- }
- } else {
- for (const field in fields) {
- complexFields[fields[field]] = {
- name: fields[field],
- units: '?',
- multiplier: 1
- }
- }
- }
- const availableInstances = this.checkNumberOfInstances(msg.Name)
- if (availableInstances.length > 1) {
- for (const instance of availableInstances) {
- messageTypes[msg.Name + '[' + instance + ']'] = {
- expressions: fields,
- units: msg.units,
- multipiers: msg.multipliers,
- complexFields: complexFields
+ if (!data || data.byteLength === 0) {
+ return {
+ messageTypes: [],
+ messages: []
+ }
+ }
+
+ try {
+ this.buffer = data
+ this.data = new DataView(this.buffer)
+ this.DfReader()
+ const messageTypes = []
+
+ // First parse FMT messages to get message definitions
+ this.parseAtOffset('FMT')
+ this.parseAtOffset('FMTU')
+ this.populateUnits()
+
+ // Collect all message types from FMT messages
+ for (const msg of this.FMT) {
+ if (msg && msg.Name) {
+ messageTypes.push(msg.Name)
+ }
+ }
+
+ // Process MSG messages first to determine vehicle type
+ this.parseAtOffset('MSG')
+
+ // Default messages if msgs is null or undefined
+ const messagesToProcess = msgs || messageTypes;
+
+ // Process each message type
+ for (const msg of messagesToProcess) {
+ if (msg !== 'MSG') { // Skip MSG as we've already processed it
+ this.parseAtOffset(msg)
+ }
+ if (msg === 'FILE') {
+ this.processFiles()
+ }
+ }
+
+ // Convert messages object to array format and fix data
+ const messagesArray = []
+ for (const [type, msgs] of Object.entries(this.messages)) {
+ if (Array.isArray(msgs)) {
+ msgs.forEach(msg => {
+ if (msg) {
+ const fixedMsg = this.fixData({...msg, name: type});
+ if (fixedMsg.time_boot_ms === undefined && fixedMsg.TimeUS !== undefined) {
+ fixedMsg.time_boot_ms = fixedMsg.TimeUS / 1000;
}
+ messagesArray.push(fixedMsg);
}
- } else {
- messageTypes[msg.Name] = {
- expressions: fields,
- units: msg.units,
- multipiers: msg.multipliers,
- complexFields: complexFields
- }
- }
+ })
}
}
- }
- self.postMessage({ availableMessages: messageTypes })
- this.messageTypes = messageTypes
- if (msgs === null) {
- // Default messages
- msgs = ['CMD','MSG','FILE','MODE','AHR2','ATT','GPS','POS',
- 'XKQ1','XKQ','NKQ1','NKQ2','XKQ2','PARM','MSG','STAT','EV']
- }
- for (const msg of msgs) {
- this.parseAtOffset(msg)
- if (msg === 'FILE') {
- this.processFiles()
+ // Sort messages by timestamp
+ messagesArray.sort((a, b) => {
+ const timeA = a.time_boot_ms || 0;
+ const timeB = b.time_boot_ms || 0;
+ return timeA - timeB;
+ });
+
+ return {
+ messageTypes: messageTypes,
+ messages: messagesArray
+ }
+ } catch (e) {
+ console.error('Error processing data:', e);
+ return {
+ messageTypes: [],
+ messages: [],
+ error: e.message
}
}
- const metadata = {
- startTime: this.extractStartTime()
- }
- self.postMessage({ metadata: metadata })
-
- self.postMessage({ messagesDoneLoading: true })
- return { types: this.messageTypes, messages: this.messages }
}
loadType (type) {
- this.parseAtOffset(type)
- console.log('done')
+ if (!this.messages[type]) {
+ return [];
+ }
+ return Array.isArray(this.messages[type]) ? this.messages[type] : [];
}
}
-self.addEventListener('message', function (event) {
- let parser
- if (event.data === null) {
- console.log('got bad file message!')
- } else if (event.data.action === 'parse') {
- parser = new DataflashParser()
- const data = event.data.file
- parser.processData(data)
- } else if (event.data.action === 'loadType') {
- parser.loadType(event.data.type.split('[')[0])
- } else if (event.data.action === 'trimFile') {
- parser.trimFile(event.data.time)
- }
-})
-
-export default DataflashParser
+// Setup web worker event listener only if in a web worker environment
+if (typeof self !== 'undefined' && typeof self.postMessage === 'function') {
+ self.addEventListener('message', function (event) {
+ let parser
+ if (event.data === null) {
+ console.log('got bad file message!')
+ } else if (event.data.action === 'parse') {
+ parser = new DataflashParser()
+ const data = event.data.file
+ parser.processData(data)
+ } else if (event.data.action === 'loadType') {
+ parser.loadType(event.data.type.split('[')[0])
+ } else if (event.data.action === 'trimFile') {
+ parser.trimFile(event.data.time)
+ }
+ })
+}
+
+// Export for Node.js environment
+if (typeof module !== 'undefined' && module.exports) {
+ module.exports = {
+ DataflashParser
+ };
+}
diff --git a/rover.BIN b/rover.BIN
new file mode 100644
index 0000000..74b7a76
Binary files /dev/null and b/rover.BIN differ
diff --git a/test.js b/test.js
new file mode 100644
index 0000000..7a5dde3
--- /dev/null
+++ b/test.js
@@ -0,0 +1,130 @@
+const fs = require('fs');
+const assert = require('assert');
+const { DataflashParser } = require('./parser.js');
+
+// Test suite
+function runTests() {
+ console.log('Running DataflashParser tests...\n');
+ let totalTests = 0;
+ let passedTests = 0;
+
+ function test(name, fn) {
+ totalTests++;
+ try {
+ fn();
+ console.log(`✓ ${name}`);
+ passedTests++;
+ } catch (err) {
+ console.error(`✗ ${name}`);
+ console.error(' ', err.message);
+ }
+ }
+
+ // Read test data
+ const data = fs.readFileSync('./rover.BIN');
+ const buffer = data.buffer.slice(data.byteOffset, data.byteOffset + data.byteLength);
+
+ // Create parser instance
+ const parser = new DataflashParser();
+ const result = parser.processData(buffer);
+
+ // Test 1: Basic message count
+ test('Should parse minimum number of messages', () => {
+ const MINIMUM_MESSAGES = 5511;
+ assert.ok(
+ result.messages.length >= MINIMUM_MESSAGES,
+ `Expected at least ${MINIMUM_MESSAGES} messages, but got ${result.messages.length}`
+ );
+ });
+
+ // Test 2: Verify essential message types exist
+ test('Should contain essential message types', () => {
+ const requiredTypes = ['MSG', 'MODE', 'GPS', 'ATT', 'PARM'];
+ const missingTypes = requiredTypes.filter(type => !result.messageTypes.includes(type));
+ assert.strictEqual(
+ missingTypes.length,
+ 0,
+ `Missing required message types: ${missingTypes.join(', ')}`
+ );
+ });
+
+ // Test 3: Check MSG messages format
+ test('Should have properly formatted MSG messages', () => {
+ const msgMessages = result.messages.filter(msg => msg.name === 'MSG');
+ assert.ok(msgMessages.length > 0, 'No MSG messages found');
+
+ // Check first MSG message structure
+ const firstMsg = msgMessages[0];
+ assert.ok(firstMsg.Message, 'MSG message missing Message field');
+ assert.ok(firstMsg.time_boot_ms !== undefined, 'MSG message missing time_boot_ms');
+ });
+
+ // Test 4: Verify GPS messages contain required fields
+ test('Should have valid GPS messages', () => {
+ const gpsMessages = result.messages.filter(msg => msg.name === 'GPS');
+ assert.ok(gpsMessages.length > 0, 'No GPS messages found');
+
+ // Check first GPS message structure
+ const firstGps = gpsMessages[0];
+ const requiredFields = ['Lat', 'Lng', 'Alt'];
+ requiredFields.forEach(field => {
+ assert.ok(
+ firstGps.hasOwnProperty(field),
+ `GPS message missing required field: ${field}`
+ );
+ });
+ });
+
+ // Test 5: Check MODE messages for valid values
+ test('Should have valid MODE messages', () => {
+ const modeMessages = result.messages.filter(msg => msg.name === 'MODE');
+ assert.ok(modeMessages.length > 0, 'No MODE messages found');
+
+ // Verify mode values
+ modeMessages.forEach(msg => {
+ assert.ok(
+ msg.hasOwnProperty('Mode') && typeof msg.Mode === 'number',
+ 'MODE message has invalid Mode value'
+ );
+ assert.ok(
+ msg.hasOwnProperty('asText') && typeof msg.asText === 'string',
+ 'MODE message missing asText translation'
+ );
+ });
+ });
+
+ // Test 6: Verify message timestamps are sequential
+ test('Should have sequential timestamps', () => {
+ const messages = result.messages.filter(msg => msg.time_boot_ms !== undefined);
+ let lastTime = 0;
+
+ for (let i = 0; i < messages.length; i++) {
+ const currentTime = messages[i].time_boot_ms;
+ assert.ok(
+ currentTime >= lastTime,
+ `Message timestamps not sequential at index ${i}`
+ );
+ lastTime = currentTime;
+ }
+ });
+
+ // Test 7: Check PARM messages format
+ test('Should have valid PARM messages', () => {
+ const parmMessages = result.messages.filter(msg => msg.name === 'PARM');
+ assert.ok(parmMessages.length > 0, 'No PARM messages found');
+
+ // Check PARM message structure
+ const firstParm = parmMessages[0];
+ assert.ok(firstParm.Name, 'PARM message missing Name field');
+ assert.ok(firstParm.Value !== undefined, 'PARM message missing Value field');
+ });
+
+ // Print test summary
+ console.log(`\nTest Summary: ${passedTests}/${totalTests} tests passed`);
+
+ // Exit with appropriate code
+ process.exit(passedTests === totalTests ? 0 : 1);
+}
+
+// Run the tests
+runTests();
\ No newline at end of file