diff --git a/index.html b/index.html index 2e3df80..210f341 100755 --- a/index.html +++ b/index.html @@ -53,7 +53,7 @@

INAV Blackbox Explorer!

- The Blackbox feature is built in to INAV + The Blackbox feature is built in to INAV and is supported on most flight controllers..

@@ -125,7 +125,7 @@

INAV Blackbox Explorer!

- + @@ -824,7 +824,7 @@ - + @@ -937,7 +937,7 @@
- + @@ -1437,6 +1437,16 @@ +
+
+
Log Data Settings
+
+
+
+ +
+
+
diff --git a/js/flightlog.js b/js/flightlog.js index fbd3eb0..434edf8 100644 --- a/js/flightlog.js +++ b/js/flightlog.js @@ -11,7 +11,7 @@ */ function FlightLog(logData) { var - ADDITIONAL_COMPUTED_FIELD_COUNT = 9, /** attitude + PID_SUM + PID_ERROR + VELOCITY + WIND_VELOCITY + WIND_HEADING **/ + ADDITIONAL_COMPUTED_FIELD_COUNT = 10, /** attitude + PID_SUM + PID_ERROR + VELOCITY + WIND_VELOCITY + WIND_HEADING + HOME DISTANCE**/ that = this, logIndex = false, @@ -222,10 +222,16 @@ function FlightLog(logData) { } } + if (userSettings.logDataGps && parser.frameDefs.G) { + for (i = 0; i < parser.frameDefs.G.name.length; i++) { + fieldNames.push(parser.frameDefs.G.name[i]); + } + } + // Add names for our ADDITIONAL_COMPUTED_FIELDS fieldNames.push("axisSum[0]", "axisSum[1]", "axisSum[2]"); fieldNames.push("axisError[0]", "axisError[1]", "axisError[2]"); // Custom calculated error field - fieldNames.push("velocity", "windVelocity", "windHeading"); + fieldNames.push("velocity", "windVelocity", "windHeading", "homeDistance"); fieldNameToIndex = {}; for (i = 0; i < fieldNames.length; i++) { @@ -253,7 +259,7 @@ function FlightLog(logData) { found = false; var refVoltage; - if((sysConfig.firmwareType == FIRMWARE_TYPE_BETAFLIGHT && semver.gte(sysConfig.firmwareVersion, '3.1.0')) || + if((sysConfig.firmwareType == FIRMWARE_TYPE_BETAFLIGHT && semver.gte(sysConfig.firmwareVersion, '3.1.0')) || (sysConfig.firmwareType == FIRMWARE_TYPE_CLEANFLIGHT && semver.gte(sysConfig.firmwareVersion, '2.0.0'))) { refVoltage = sysConfig.vbatref; } else { @@ -360,6 +366,11 @@ function FlightLog(logData) { slowFrameLength = parser.frameDefs.S ? parser.frameDefs.S.count : 0, lastSlow = parser.frameDefs.S ? iframeDirectory.initialSlow[chunkIndex].slice(0) : []; + var + gpsFrameLength = userSettings.logDataGps && parser.frameDefs.G ? parser.frameDefs.G.count : 0, + lastGPSData = userSettings.logDataGps && parser.frameDefs.G ? iframeDirectory.initialGPSData[chunkIndex].slice(0) : []; + + parser.onFrameReady = function(frameValid, frame, frameType, frameOffset, frameSize) { var destFrame; @@ -369,9 +380,7 @@ function FlightLog(logData) { case 'P': case 'I': //The parser re-uses the "frame" array so we must copy that data somewhere else - - var - numOutputFields = frame.length + slowFrameLength + ADDITIONAL_COMPUTED_FIELD_COUNT; + var numOutputFields = frame.length + slowFrameLength + gpsFrameLength + ADDITIONAL_COMPUTED_FIELD_COUNT ; //Do we have a recycled chunk to copy on top of? if (chunk.frames[mainFrameIndex]) { @@ -393,6 +402,13 @@ function FlightLog(logData) { destFrame[i + frame.length] = lastSlow[i] === undefined ? null : lastSlow[i]; } + if (userSettings.logDataGps) { + // Then merge in the last seen gps-frame data + for (var i = 0; i < gpsFrameLength; i++) { + destFrame[i + frame.length + slowFrameLength] = lastGPSData[i] === undefined ? null : lastGPSData[i]; + } + } + for (var i = 0; i < eventNeedsTimestamp.length; i++) { eventNeedsTimestamp[i].time = frame[FlightLogParser.prototype.FLIGHT_LOG_FIELD_INDEX_TIME]; } @@ -423,6 +439,13 @@ function FlightLog(logData) { lastSlow[i] = frame[i]; } break; + case 'G': + if (userSettings.logDataGps) { + for (var i = 0; i < frame.length; i++) { + lastGPSData[i] = frame[i]; + } + } + break; } } else { chunk.gapStartsHere[mainFrameIndex - 1] = true; @@ -502,7 +525,8 @@ function FlightLog(logData) { sourceChunkIndex, destChunkIndex, sysConfig, navVel = [fieldNameToIndex["navVel[0]"], fieldNameToIndex["navVel[1]"]], - wind = [fieldNameToIndex["wind[0]"], fieldNameToIndex["wind[1]"], fieldNameToIndex["wind[2]"]]; + wind = [fieldNameToIndex["wind[0]"], fieldNameToIndex["wind[1]"], fieldNameToIndex["wind[2]"]], + navPos = [fieldNameToIndex["navPos[0]"], fieldNameToIndex["navPos[1]"]]; let axisPID = [ [fieldNameToIndex["axisP[0]"], fieldNameToIndex["axisI[0]"], fieldNameToIndex["axisD[0]"], fieldNameToIndex["axisF[0]"]], @@ -580,6 +604,13 @@ function FlightLog(logData) { destFrame[fieldIndex+1] = windRads; } fieldIndex += 2; + + // Compute distance to home + let posX = srcFrame[navPos[0]], posY = srcFrame[navPos[1]]; + if (posX != undefined && posY != undefined) { + destFrame[fieldIndex] = Math.round(Math.hypot(posX, posY)); + } + fieldIndex++; } } } diff --git a/js/flightlog_fielddefs.js b/js/flightlog_fielddefs.js index 09b7a8e..27e30ac 100644 --- a/js/flightlog_fielddefs.js +++ b/js/flightlog_fielddefs.js @@ -354,7 +354,18 @@ var "CRUISE_3D_ADJUSTING", "WAYPOINT_HOLD", "RTH_HOVER_ABOVE_HOME", - "UNUSED_4" + "UNUSED_4", + "RTH_TRACKBACK", + "MIXERAT_INITIALIZE", + "MIXERAT_IN_PROGRESS", + "MIXERAT_ABORT", + "FW_LANDING_CLIMB_TO_LOITER", + "FW_LANDING_LOITER", + "FW_LANDING_APPROACH", + "FW_LANDING_GLIDE", + "FW_LANDING_FLARE", + "FW_LANDING_ABORT", + "FW_LANDING_FINISHED" ]), FLIGHT_LOG_NAV_FLAGS = makeReadOnly([ diff --git a/js/flightlog_fields_presenter.js b/js/flightlog_fields_presenter.js index d560fa1..fcce688 100644 --- a/js/flightlog_fields_presenter.js +++ b/js/flightlog_fields_presenter.js @@ -297,7 +297,7 @@ function FlightLogFieldPresenter() { * @param value Value of the field */ FlightLogFieldPresenter.decodeFieldToFriendly = function (flightLog, fieldName, value, currentFlightMode) { - if (value === undefined) + if (value === undefined || value === null) return ""; switch (fieldName) { @@ -454,15 +454,18 @@ function FlightLogFieldPresenter() { case 'windHeading': return (value / Math.PI * 180).toFixed(1) + "deg"; - case 'BaroAlt': - return (value / 100).toFixed(2) + "m"; - case "navEPH": return (value/100).toFixed(2); + case 'BaroAlt': + case "navPos[0]": + case "navPos[1]": case "navPos[2]": + case "navTgtPos[0]": + case "navTgtPos[1]": case "navTgtPos[2]": - return (value / 100).toFixed(2) + "m"; + case "homeDistance": + return (value / 100).toFixed(2) + " m"; case 'flightModeFlags': return presentFlags(value, FLIGHT_LOG_FLIGHT_MODE_NAME); @@ -506,6 +509,7 @@ function FlightLogFieldPresenter() { case 'wind[0]': case 'wind[1]': case 'windVelocity': + case 'GPS_speed': if (userSettings.velocityUnits == 'I') // Imperial return (value * 0.0223694).toFixed(1) + "mph"; if (userSettings.velocityUnits == 'M') // Metric @@ -539,6 +543,18 @@ function FlightLogFieldPresenter() { case 'sens7Temp': case 'escTemperature': return (value == -1250) ? "" : (value / 10.0).toFixed(1) + '°'; + case 'GPS_coord[0]': + case 'GPS_coord[1]': + return (value / 10000000.0).toFixed(7) + " degs"; + case 'GPS_altitude': + return value + " m"; + case 'GPS_ground_course': + case 'attitude[0]': + case 'attitude[1]': + case 'attitude[2]': + return (value / 10.0).toFixed(1) + " degs"; + case 'navTgtHdg': + return (value / 100.0).toFixed(1) + " degs"; default: return value.toString(); diff --git a/js/flightlog_index.js b/js/flightlog_index.js index c6a4235..422e203 100644 --- a/js/flightlog_index.js +++ b/js/flightlog_index.js @@ -2,56 +2,57 @@ function FlightLogIndex(logData) { //Private: - var + var that = this, logBeginOffsets = false, logCount = false, intraframeDirectories = false; - + function buildLogOffsetsIndex() { - var - stream = new ArrayDataStream(logData), + var + stream = new ArrayDataStream(logData), i, logStart; - + logBeginOffsets = []; - + for (i = 0; ; i++) { logStart = stream.nextOffsetOf(FlightLogParser.prototype.FLIGHT_LOG_START_MARKER); - + if (logStart == -1) { //No more logs found in the file logBeginOffsets.push(stream.end); - break; + break; } - + logBeginOffsets.push(logStart); - + //Restart the search after this header stream.pos = logStart + FlightLogParser.prototype.FLIGHT_LOG_START_MARKER.length; } } - + function buildIntraframeDirectories() { - var + var parser = new FlightLogParser(logData, that); - + intraframeDirectories = []; for (var i = 0; i < that.getLogCount(); i++) { - var + var intraIndex = { times: [], offsets: [], avgThrottle: [], initialSlow: [], initialGPSHome: [], + initialGPSData: [], hasEvent: [], minTime: false, maxTime: false }, - + gyroADC, accSmooth, magADC, - + iframeCount = 0, motorFields = [], matches, @@ -59,97 +60,106 @@ function FlightLogIndex(logData) { eventInThisChunk = null, parsedHeader, sawEndMarker = false; - + try { parser.parseHeader(logBeginOffsets[i], logBeginOffsets[i + 1]); parsedHeader = true; } catch (e) { console.log("Error parsing header of log #" + (i + 1) + ": " + e); intraIndex.error = e; - + parsedHeader = false; } // Only attempt to parse the log if the header wasn't corrupt if (parsedHeader) { - var + var sysConfig = parser.sysConfig, mainFrameDef = parser.frameDefs.I, - + gyroADC = [mainFrameDef.nameToIndex["gyroADC[0]"], mainFrameDef.nameToIndex["gyroADC[1]"], mainFrameDef.nameToIndex["gyroADC[2]"]], accSmooth = [mainFrameDef.nameToIndex["accSmooth[0]"], mainFrameDef.nameToIndex["accSmooth[1]"], mainFrameDef.nameToIndex["accSmooth[2]"]], magADC = [mainFrameDef.nameToIndex["magADC[0]"], mainFrameDef.nameToIndex["magADC[1]"], mainFrameDef.nameToIndex["magADC[2]"]], - + lastSlow = [], - lastGPSHome = []; - + lastGPSHome = [], + lastGPSData = []; + // Identify motor fields so they can be used to show the activity summary bar for (var j = 0; j < 8; j++) { if (mainFrameDef.nameToIndex["motor[" + j + "]"] !== undefined) { motorFields.push(mainFrameDef.nameToIndex["motor[" + j + "]"]); } } - + // Do we have mag fields? If not mark that data as absent if (magADC[0] === undefined) { magADC = false; } - + parser.onFrameReady = function(frameValid, frame, frameType, frameOffset, frameSize) { if (!frameValid) { return; } - + switch (frameType) { case 'P': case 'I': - var + var frameTime = frame[FlightLogParser.prototype.FLIGHT_LOG_FIELD_INDEX_TIME]; - + if (intraIndex.minTime === false) { intraIndex.minTime = frameTime; } - + if (intraIndex.maxTime === false || frameTime > intraIndex.maxTime) { intraIndex.maxTime = frameTime; } - + if (frameType == 'I') { // Start a new chunk on every 4th I-frame if (iframeCount % 4 === 0) { // Log the beginning of the new chunk intraIndex.times.push(frameTime); intraIndex.offsets.push(frameOffset); - + if (motorFields.length) { throttleTotal = 0; for (var j = 0; j < motorFields.length; j++) { throttleTotal += frame[motorFields[j]]; } - + intraIndex.avgThrottle.push(Math.round(throttleTotal / motorFields.length)); } - + /* To enable seeking to an arbitrary point in the log without re-reading anything * that came before, we have to record the initial state of various items which aren't * logged anew every iteration. - */ + */ intraIndex.initialSlow.push(lastSlow); intraIndex.initialGPSHome.push(lastGPSHome); + if (userSettings.logDataGps) { + intraIndex.initialGPSData.push(lastGPSData); + } } - + iframeCount++; } break; case 'H': lastGPSHome = frame.slice(0); break; + case 'G': + if (userSettings.logDataGps) { + lastGPSData = frame.slice(0); + } + break; case 'E': // Mark that there was an event inside the current chunk if (intraIndex.times.length > 0) { intraIndex.hasEvent[intraIndex.times.length - 1] = true; } - + if (frame.event == FlightLogEvent.LOG_END) { sawEndMarker = true; } @@ -159,13 +169,13 @@ function FlightLogIndex(logData) { break; } }; - + try { parser.parseLogData(false); } catch (e) { intraIndex.error = e; } - + // Don't bother including the initial (empty) states for S and H frames if we didn't have any in the source data if (!parser.frameDefs.S) { delete intraIndex.initialSlow; @@ -175,9 +185,13 @@ function FlightLogIndex(logData) { delete intraIndex.initialGPSHome; } + if (userSettings.logDataGps && !parser.frameDefs.G) { + delete intraIndex.initialGPSData; + } + intraIndex.stats = parser.stats; } - + // Did we not find any events in this log? if (intraIndex.minTime === false) { if (sawEndMarker) { @@ -186,90 +200,90 @@ function FlightLogIndex(logData) { intraIndex.error = "Log truncated, no data"; } } - + intraframeDirectories.push(intraIndex); } } - - //Public: + + //Public: this.loadFromJSON = function(json) { - + }; - + this.saveToJSON = function() { - var + var intraframeDirectories = this.getIntraframeDirectories(), - i, j, + i, j, resultIndexes = new Array(intraframeDirectories.length); - + for (i = 0; i < intraframeDirectories.length; i++) { - var - lastTime, lastLastTime, + var + lastTime, lastLastTime, lastOffset, lastLastOffset, lastThrottle, - + sourceIndex = intraframeDirectories[i], - + resultIndex = { - times: new Array(sourceIndex.times.length), + times: new Array(sourceIndex.times.length), offsets: new Array(sourceIndex.offsets.length), minTime: sourceIndex.minTime, maxTime: sourceIndex.maxTime, avgThrottle: new Array(sourceIndex.avgThrottle.length) }; - + if (sourceIndex.times.length > 0) { resultIndex.times[0] = sourceIndex.times[0]; resultIndex.offsets[0] = sourceIndex.offsets[0]; - + lastLastTime = lastTime = sourceIndex.times[0]; lastLastOffset = lastOffset = sourceIndex.offsets[0]; - + for (j = 1; j < sourceIndex.times.length; j++) { resultIndex.times[j] = sourceIndex.times[j] - 2 * lastTime + lastLastTime; resultIndex.offsets[j] = sourceIndex.offsets[j] - 2 * lastOffset + lastLastOffset; - + lastLastTime = lastTime; lastTime = sourceIndex.times[j]; - + lastLastOffset = lastOffset; lastOffset = sourceIndex.offsets[j]; } } - + if (sourceIndex.avgThrottle.length > 0) { for (j = 0; j < sourceIndex.avgThrottle.length; j++) { resultIndex.avgThrottle[j] = sourceIndex.avgThrottle[j] - 1000; } } - + resultIndexes[i] = resultIndex; } - + return JSON.stringify(resultIndexes); - }; - + }; + this.getLogBeginOffset = function(index) { if (!logBeginOffsets) buildLogOffsetsIndex(); - + return logBeginOffsets[index]; }; - + this.getLogCount = function() { if (!logBeginOffsets) buildLogOffsetsIndex(); return logBeginOffsets.length - 1; }; - + this.getIntraframeDirectories = function() { if (!intraframeDirectories) buildIntraframeDirectories(); - + return intraframeDirectories; }; - + this.getIntraframeDirectory = function(logIndex) { return this.getIntraframeDirectories()[logIndex]; }; diff --git a/js/main.js b/js/main.js index b26487b..ca94e3a 100644 --- a/js/main.js +++ b/js/main.js @@ -1239,6 +1239,8 @@ function BlackboxLogViewer() { prefs.set('userSettings', newSettings); + selectLog(null); + // refresh the craft model if(graph!=null) { graph.refreshOptions(newSettings); diff --git a/js/user_settings_dialog.js b/js/user_settings_dialog.js index 4d12ff6..0e3e52f 100644 --- a/js/user_settings_dialog.js +++ b/js/user_settings_dialog.js @@ -3,7 +3,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { // Private Variables - + // generate mixer (from Cleanflight Configurator) (note that the mixerConfiguration index starts at 1) var mixerList = [ {name: 'Tricopter', model: 'tricopter', image: 'tri', defaultMotorOrder: [0, 1, 2], defaultYawOffset: -Math.PI / 2}, @@ -44,11 +44,12 @@ function UserSettingsDialog(dialog, onLoad, onSave) { stickTrails : false, // Show stick trails? stickInvertYaw : false, // Invert yaw in stick display? legendUnits : true, // Show units on legend? + logDataGps : false, velocityUnits : "D", // Units for composite velocity "D" / "M" / "I" gapless : false, - drawCraft : "3D", - drawPidTable : true, - drawSticks : true, + drawCraft : "3D", + drawPidTable : true, + drawSticks : true, drawTime : true, drawEvents : true, drawAnalyser : true, // add an analyser option @@ -97,7 +98,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { var customMix; if($(".custom-mixes").is(":checked")) { - + var motorOrder = new Array(mixerList[currentSettings.mixerConfiguration-1].defaultMotorOrder.length); for(var i=0;i") .text(FlightLogFieldPresenter.fieldNameToFriendly(fieldName)) .attr("value", i); - + if (fieldName == selectedName) { option.attr("selected", "selected"); } - + return option; } @@ -168,7 +169,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { select_e.append(renderFieldOption(i, availableMotors[i], selectedName)); }; } - + function buildMotorList(mixerConfiguration) { var motor_list_e = $('.motorList'); $(motor_list_e).empty(); // clear all the motors @@ -180,13 +181,13 @@ function UserSettingsDialog(dialog, onLoad, onSave) { 'There are only a maximum of ' + availableMotors.length + ' motors in the log file; the selection you have chosen requires ' + mixerList[mixerConfiguration-1].defaultMotorOrder.length + ' motors.' + '

' + - '' + + '' + ''); motor_list_e.append(motors_e); } else { for(var i=0; i' + - '' + + '' + ''); var select_e = $('select', motors_e); if(currentSettings.customMix!=null) { @@ -200,12 +201,12 @@ function UserSettingsDialog(dialog, onLoad, onSave) { buildAvailableMotors(select_e, 'motor[' + i + ']'); } motor_list_e.append(motors_e); - }; + }; } } - + // Initialisation Code ... - + // Setup the mixer list (pretty much cloned from the configurator...) var mixer_list_e = $('select.mixerList'); for (var i = 0; i < mixerList.length; i++) { @@ -221,7 +222,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { if(val>0 && val <= mixerList.length) { $('.mixerPreview img').attr('src', './images/motor_order/' + mixerList[val - 1].image + '.svg'); } - + buildMotorList(val); // rebuild the motor list based upon the current selection } @@ -237,7 +238,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { } // Buttons and Selectors - + $('select.mixerList').change(function () { mixerListSelection(parseInt($(this).val())); }); @@ -296,6 +297,10 @@ function UserSettingsDialog(dialog, onLoad, onSave) { currentSettings.legendUnits = $(this).is(":checked"); }); + $(".logdata-gps").click(function() { + currentSettings.logDataGps = $(this).is(":checked"); + }); + $(".velocity-units").click(function() { currentSettings.velocityUnits = $(this).val(); }); @@ -304,16 +309,16 @@ function UserSettingsDialog(dialog, onLoad, onSave) { function readURL(input) { if (input.files && input.files[0]) { var reader = new FileReader(); - + reader.onload = function (e) { $('#watermark-logo').attr('src', e.target.result); currentLogo = e.target.result; } - + reader.readAsDataURL(input.files[0]); } } - + $("#watermark-logo-load").change(function(){ readURL(this); }); @@ -329,13 +334,13 @@ function UserSettingsDialog(dialog, onLoad, onSave) { onSave(currentSettings); } - + this.show = function(flightLog, settings) { currentSettings = $.extend({}, defaultSettings, currentSettings, settings || {}); getAvailableMotors(flightLog); // Which motors are in the log file ? - + if(currentSettings.customMix==null) { // clear the toggle switch $(".custom-mixes").prop('checked', false); @@ -349,7 +354,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { if(currentSettings.stickUnits!=null) { // set the toggle switch $(".stick-units").prop('checked', currentSettings.stickUnits); - } + } if(currentSettings.stickTrails!=null) { // set the toggle switch @@ -371,6 +376,11 @@ function UserSettingsDialog(dialog, onLoad, onSave) { $(".legend-units").prop('checked', currentSettings.legendUnits); } + if(currentSettings.logDataGps != null) { + // set the toggle switch + $(".logdata-gps").prop('checked', currentSettings.logDataGps); + } + $(".velocity-units").val(currentSettings.velocityUnits || "D"); mixerListSelection(currentSettings.mixerConfiguration); // select current mixer configuration @@ -395,12 +405,12 @@ function UserSettingsDialog(dialog, onLoad, onSave) { $(".watermark").prop('checked', currentSettings.drawWatermark); (currentSettings.drawWatermark)?$(".watermark-group").show(200):$(".watermark-group").hide(200); } - + $('.watermark-settings input[name="watermark-top"]').val(parseInt(currentSettings.watermark.top)); $('.watermark-settings input[name="watermark-left"]').val(parseInt(currentSettings.watermark.left)); $('.watermark-settings input[name="watermark-size"]').val(parseInt(currentSettings.watermark.size)); $('.watermark-settings input[name="watermark-transparency"]').val(parseInt(currentSettings.watermark.transparency)); - + if(currentSettings.watermark.logo!=null) { currentLogo = currentSettings.watermark.logo; $('#watermark-logo').attr('src', currentLogo); @@ -413,7 +423,7 @@ function UserSettingsDialog(dialog, onLoad, onSave) { $(".laptimer").prop('checked', currentSettings.drawLapTimer); (currentSettings.drawLapTimer)?$(".laptimer-group").show(200):$(".laptimer-group").hide(200); } - + $('.laptimer-settings input[name="laptimer-top"]').val(parseInt(currentSettings.laptimer.top)); $('.laptimer-settings input[name="laptimer-left"]').val(parseInt(currentSettings.laptimer.left)); $('.laptimer-settings input[name="laptimer-transparency"]').val(parseInt(currentSettings.laptimer.transparency));