From 2d500134d98651044e83891d032e8c412aaafc8b Mon Sep 17 00:00:00 2001 From: iso9660 Date: Sun, 22 Jan 2023 10:48:20 +0100 Subject: [PATCH] Updated parser and field presenter for edt signals. Found a workaround to plot esc signal 4 Added basic ESC plot functionality updated project files Implemented array fiels propagation over empty fields Fixed bad FLIGHT_LOG_FIELD_ENCODING_PACK_1F_1F_1F_1G_4U_8U decoding Removed tabs on changed files Fixed some more review findings Updated DSHOT_STATUS_N_ERPM_FRACTION_18 graph ranges Reverted changes in package.json and yarn.lock Improved wording and graph ranges Updated concatenations to template literals If a field contain array values always use the last field for graph Added DSHOT motor events to graph Fixed review findings Added demag events to graph Changed speciffic Bluejay wording by general esc one Fixed sonarcloud false positive Updated debug modes to match the ones in bf master Added debug mode to match edt_events Betaflight branch Removed duplicated BARO graph config Fixed review findings Using let instead of var Refactored if to meet sonarcloud advise --- js/flightlog.js | 34 ++++++++ js/flightlog_fielddefs.js | 7 ++ js/flightlog_fields_presenter.js | 66 +++++++++++++++ js/flightlog_parser.js | 103 ++++++++++++++++++----- js/graph_config.js | 29 ++++++- js/grapher.js | 133 +++++++++++++++++++----------- js/main.js | 137 ++++++++++++++++--------------- 7 files changed, 370 insertions(+), 139 deletions(-) diff --git a/js/flightlog.js b/js/flightlog.js index 74353128..af86e5a6 100644 --- a/js/flightlog.js +++ b/js/flightlog.js @@ -296,6 +296,39 @@ function FlightLog(logData) { return numMotors; }; + /* + * Propagates array data fiels over empty fields + * Debug fields can be arrays with data, so it fills data gaps when no arrays are stored + */ + function propagateArrayFields(chunks) + { + var currentFrame; + + for (let k = 0; k < chunks.length; k++) + { + let previousFrame = 0; + + for (let j = 0; j < chunks[k].frames.length; j++) + { + currentFrame = chunks[k].frames[j]; + if (previousFrame == 0) + { + previousFrame = currentFrame; + } + + for (let i = 0; i < currentFrame.length; i++) + { + if (!Array.isArray(currentFrame[i]) && Array.isArray(previousFrame[i])) + { + currentFrame[i] = previousFrame[i]; + } + } + + previousFrame = chunks[k].frames[j]; + } + } + } + /** * Get the raw chunks in the range [startIndex...endIndex] (inclusive) * @@ -504,6 +537,7 @@ function FlightLog(logData) { } injectComputedFields(resultChunks, resultChunks); + propagateArrayFields(resultChunks); return resultChunks; } diff --git a/js/flightlog_fielddefs.js b/js/flightlog_fielddefs.js index 25ea17d4..659988d6 100644 --- a/js/flightlog_fielddefs.js +++ b/js/flightlog_fielddefs.js @@ -361,6 +361,13 @@ let "MAG_CALIB", "MAG_TASK_RATE", "EZLANDING", + "DSHOT_STATUS_N_TEMPERATURE", + "DSHOT_STATUS_N_VOLTAGE", + "DSHOT_STATUS_N_CURRENT", + "DSHOT_STATUS_N_DEBUG1", + "DSHOT_STATUS_N_DEBUG2", + "DSHOT_STATUS_N_STRESS_LVL", + "DSHOT_STATUS_N_ERPM_FRACTION_18", ]), SUPER_EXPO_YAW = makeReadOnly([ diff --git a/js/flightlog_fields_presenter.js b/js/flightlog_fields_presenter.js index 1a271d14..f45c09cd 100644 --- a/js/flightlog_fields_presenter.js +++ b/js/flightlog_fields_presenter.js @@ -1114,6 +1114,55 @@ function FlightLogFieldPresenter() { 'debug[2]': 'Upper Limit', 'debug[3]': 'EZ Land Limit', }, + 'DSHOT_STATUS_N_TEMPERATURE' : { + 'debug[all]': 'ESC Status & Temperature', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, + 'DSHOT_STATUS_N_VOLTAGE' : { + 'debug[all]': 'ESC Status & Voltage', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, + 'DSHOT_STATUS_N_CURRENT' : { + 'debug[all]': 'ESC Status & Current', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, + 'DSHOT_STATUS_N_DEBUG1' : { + 'debug[all]': 'ESC Status & Debug1', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, + 'DSHOT_STATUS_N_DEBUG2' : { + 'debug[all]': 'ESC Status & Debug2', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, + 'DSHOT_STATUS_N_STRESS_LVL' : { + 'debug[all]': 'ESC Status & Stress Level', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, + 'DSHOT_STATUS_N_ERPM_FRACTION_18' : { + 'debug[all]': 'ESC Status & RPM', + 'debug[0]': 'ESC1', + 'debug[1]': 'ESC2', + 'debug[2]': 'ESC3', + 'debug[3]': 'ESC4', + }, }; let DEBUG_FRIENDLY_FIELD_NAMES = null; @@ -1879,7 +1928,24 @@ function FlightLogFieldPresenter() { return value.toFixed(0); case 'DSHOT_TELEMETRY_COUNTS': return value.toFixed(0); + case 'DSHOT_STATUS_N_TEMPERATURE': + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${value[4]}ÂșC` : '---'; + case 'DSHOT_STATUS_N_VOLTAGE': + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${value[4]}V` : '---'; + case 'DSHOT_STATUS_N_CURRENT': + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${value[4]}A` : '---'; + case 'DSHOT_STATUS_N_DEBUG1': + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${value[4]}` : '---'; + case 'DSHOT_STATUS_N_DEBUG2': + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${value[4]}` : '---'; + case 'DSHOT_STATUS_N_STRESS_LVL': + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${value[4]}sTrs` : '---'; + case 'DSHOT_STATUS_N_ERPM_FRACTION_18': + var rpm = (value[4] * 200 / flightLog.getSysConfig().motor_poles).toFixed(); + return (value[0] != null) ? `A${value[0]} W${value[1]} E${value[2]} STRESS:${value[3]} ${rpm}Rpm` : '---'; + } + return value.toFixed(0); } return ""; diff --git a/js/flightlog_parser.js b/js/flightlog_parser.js index 4ea3abab..87e41977 100644 --- a/js/flightlog_parser.js +++ b/js/flightlog_parser.js @@ -58,18 +58,23 @@ var FlightLogParser = function(logData) { //Predict that this field is minthrottle FLIGHT_LOG_FIELD_PREDICTOR_MINMOTOR = 11, + //Predict that this field is dshot status and other data + FLIGHT_LOG_FIELD_PREDICTOR_DSHOT_STATUS_N_VOLTAGE = 12, + FLIGHT_LOG_FIELD_PREDICTOR_DSHOT_STATUS_N_ERPM_FRACTION_18 = 13, + //Home coord predictors appear in pairs (two copies of FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD). Rewrite the second //one we see to this to make parsing easier FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD_1 = 256, - FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, // Signed variable-byte - FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, // Unsigned variable-byte - FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3, // Unsigned variable-byte but we negate the value before storing, value is 14 bits - FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6, - FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7, - FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8, - FLIGHT_LOG_FIELD_ENCODING_NULL = 9, // Nothing is written to the file, take value to be zero - FLIGHT_LOG_FIELD_ENCODING_TAG2_3SVARIABLE = 10, + FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0, // Signed variable-byte + FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1, // Unsigned variable-byte + FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3, // Unsigned variable-byte but we negate the value before storing, value is 14 bits + FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6, + FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7, + FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8, + FLIGHT_LOG_FIELD_ENCODING_NULL = 9, // Nothing is written to the file, take value to be zero + FLIGHT_LOG_FIELD_ENCODING_TAG2_3SVARIABLE = 10, + FLIGHT_LOG_FIELD_ENCODING_PACK_1F_1F_1F_1G_4U_8U = 11, // 1 flagBit, 1 flagBit, 1 flagBit, 1 gapBit, 4 unsignedIntBit, 8 unsignedIntBit FLIGHT_LOG_EVENT_LOG_END = 255, @@ -530,9 +535,9 @@ var FlightLogParser = function(logData) { function translateFieldName(fieldName) { var translation = translationValues[fieldName]; if (typeof translation !== 'undefined') { - return translation; + return translation; } else { - return fieldName; + return fieldName; } } @@ -602,14 +607,14 @@ var FlightLogParser = function(logData) { case "Cleanflight": that.sysConfig.firmwareType = FIRMWARE_TYPE_CLEANFLIGHT; $('html').removeClass('isBaseF'); - $('html').addClass('isCF'); + $('html').addClass('isCF'); $('html').removeClass('isBF'); $('html').removeClass('isINAV'); break; default: that.sysConfig.firmwareType = FIRMWARE_TYPE_BASEFLIGHT; $('html').addClass('isBaseF'); - $('html').removeClass('isCF'); + $('html').removeClass('isCF'); $('html').removeClass('isBF'); $('html').removeClass('isINAV'); } @@ -946,7 +951,7 @@ var FlightLogParser = function(logData) { $('html').addClass('isINAV'); } else { - // Cleanflight 1.x and others + // Cleanflight 1.x and others that.sysConfig.firmwareVersion = '0.0.0'; that.sysConfig.firmware = 0.0; that.sysConfig.firmwarePatch = 0; @@ -1109,6 +1114,34 @@ var FlightLogParser = function(logData) { % that.sysConfig.frameIntervalPDenom < that.sysConfig.frameIntervalPNum; } + /** + * Debug data interpretation depends on the chosen debug mode encodings and other parameters could need to be fixed + */ + function assimilateDebugMode(sysConfig, frameDef) { + console.log("Debug mode is " + DEBUG_MODE[sysConfig.debug_mode] + ":" + sysConfig.debug_mode); + + if (DEBUG_MODE[sysConfig.debug_mode].startsWith("DSHOT_STATUS_N_")) { + for (let k = 0; k < frameDef.name.length; k++) { + if (frameDef.name[k].startsWith("debug")) { + // Assimilate encoding depending on debug mode + frameDef.encoding[k] = FLIGHT_LOG_FIELD_ENCODING_PACK_1F_1F_1F_1G_4U_8U; + + // Assimilate predictor depending on debug mode + switch (DEBUG_MODE[sysConfig.debug_mode]) { + case "DSHOT_STATUS_N_VOLTAGE": + frameDef.predictor[k] = FLIGHT_LOG_FIELD_PREDICTOR_DSHOT_STATUS_N_VOLTAGE; + break; + case "DSHOT_STATUS_N_ERPM_FRACTION_18": + frameDef.predictor[k] = FLIGHT_LOG_FIELD_PREDICTOR_DSHOT_STATUS_N_ERPM_FRACTION_18; + break; + default: + break; + } + } + } + } + } + /** * Attempt to parse the frame of into the supplied `current` buffer using the encoding/predictor * definitions from `frameDefs`. The previous frame values are used for predictions. @@ -1123,8 +1156,8 @@ var FlightLogParser = function(logData) { predictor = frameDef.predictor, encoding = frameDef.encoding, values = new Array(8), - i, j, groupCount; - + i, j, groupCount, updateCurrent; + i = 0; while (i < frameDef.count) { var @@ -1138,6 +1171,10 @@ var FlightLogParser = function(logData) { i++; } else { + // Update current by default + updateCurrent = true; + + // Decode switch (encoding[i]) { case FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB: value = stream.readSignedVB(); @@ -1158,7 +1195,7 @@ var FlightLogParser = function(logData) { for (j = 0; j < 4; j++, i++) current[i] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], values[j], current, previous, previous2); - continue; + updateCurrent = false; break; case FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32: stream.readTag2_3S32(values); @@ -1167,7 +1204,7 @@ var FlightLogParser = function(logData) { for (j = 0; j < 3; j++, i++) current[i] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], values[j], current, previous, previous2); - continue; + updateCurrent = false; break; case FLIGHT_LOG_FIELD_ENCODING_TAG2_3SVARIABLE: stream.readTag2_3SVariable(values); @@ -1176,7 +1213,7 @@ var FlightLogParser = function(logData) { for (j = 0; j < 3; j++, i++) current[i] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], values[j], current, previous, previous2); - continue; + updateCurrent = false; break; case FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB: //How many fields are in this encoded group? Check the subsequent field encodings: @@ -1191,7 +1228,20 @@ var FlightLogParser = function(logData) { for (j = 0; j < groupCount; j++, i++) current[i] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], values[j], current, previous, previous2); - continue; + updateCurrent = false; + break; + case FLIGHT_LOG_FIELD_ENCODING_PACK_1F_1F_1F_1G_4U_8U: + value = stream.readSignedVB(); + + current[i] = new Array(5); + current[i][0] = ((value & 0x8000) != 0) ? 1 : 0; + current[i][1] = ((value & 0x4000) != 0) ? 1 : 0; + current[i][2] = ((value & 0x2000) != 0) ? 1 : 0; + current[i][3] = (value >> 8) & 0x000F; + current[i][4] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], value & 0x00FF, current, previous, previous2); + i++; + + updateCurrent = false; break; case FLIGHT_LOG_FIELD_ENCODING_NULL: //Nothing to read @@ -1204,8 +1254,11 @@ var FlightLogParser = function(logData) { throw "Unsupported field encoding " + encoding[i]; } - current[i] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], value, current, previous, previous2); - i++; + // Updates current when it is not updated by the decoder path` + if (updateCurrent) { + current[i] = applyPrediction(i, raw ? FLIGHT_LOG_FIELD_PREDICTOR_0 : predictor[i], value, current, previous, previous2); + i++; + } } } } @@ -1366,6 +1419,12 @@ var FlightLogParser = function(logData) { if (mainHistory[1]) value += mainHistory[1][FlightLogParser.prototype.FLIGHT_LOG_FIELD_INDEX_TIME]; break; + case FLIGHT_LOG_FIELD_PREDICTOR_DSHOT_STATUS_N_VOLTAGE: + value /= 4; + break; + case FLIGHT_LOG_FIELD_PREDICTOR_DSHOT_STATUS_N_ERPM_FRACTION_18: + value *= 18; + break; default: throw "Unsupported field predictor " + predictor; } @@ -1703,6 +1762,8 @@ var FlightLogParser = function(logData) { } else { lastSlow = []; } + + assimilateDebugMode(that.sysConfig, this.frameDefs.I); }; /** diff --git a/js/graph_config.js b/js/graph_config.js index 5b5c8a75..17d1e628 100644 --- a/js/graph_config.js +++ b/js/graph_config.js @@ -996,6 +996,7 @@ GraphConfig.load = function(config) { default: return getCurveForMinMaxFields(fieldName); } + case 'GPS_DOP': switch (fieldName) { case 'debug[0]': // Number of Satellites (now this is in normal GPS data, maybe gpsTrust?) @@ -1135,7 +1136,33 @@ GraphConfig.load = function(config) { default: return getCurveForMinMaxFields(fieldName); } - } + case 'DSHOT_STATUS_N_TEMPERATURE': + case 'DSHOT_STATUS_N_CURRENT': + case 'DSHOT_STATUS_N_DEBUG1': + case 'DSHOT_STATUS_N_DEBUG2': + case 'DSHOT_STATUS_N_STRESS_LVL': + return { + offset: 0, + power: 1.0, + inputRange: 400, + outputRange: 1.0, + }; + case 'DSHOT_STATUS_N_VOLTAGE': + return { + offset: 0, + power: 1.0, + inputRange: 255, + outputRange: 1.0, + }; + case 'DSHOT_STATUS_N_ERPM_FRACTION_18': + return { + offset: 0, + power: 1.0, + inputRange: 4000, + outputRange: 1.0, + }; + + } } // if not found above then // Scale and center the field based on the whole-log observed ranges for that field diff --git a/js/grapher.js b/js/grapher.js index 32142222..fa055fbb 100644 --- a/js/grapher.js +++ b/js/grapher.js @@ -67,7 +67,7 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv craft3D = null, craft2D = null, - analyser = null, /* define a new spectrum analyser */ + analyser = null, /* define a new spectrum analyser */ watermarkLogo, /* Watermark feature */ @@ -266,7 +266,7 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv function drawLapTimer() { // Update the Lap Timer lapTimer.refresh(windowCenterTime, (3600*1000000/*a long time*/), blackboxLogViewer.getBookmarkTimes()); - lapTimer.drawCanvas(canvas, options); + lapTimer.drawCanvas(canvas, options); } var @@ -300,9 +300,9 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv drawingLine = false, notInBounds = -5, // when <0, then line is always drawn, (this allows us to paritially dash the line when the bounds is exceeded) inGap = false, - lastX, lastY, yScale = -plotHeight, - xScale = canvas.width / windowWidthMicros; + xScale = canvas.width / windowWidthMicros, + drawDshotStatusArrayField = DEBUG_MODE[flightLog.parser.sysConfig.debug_mode].startsWith("DSHOT_STATUS_N_"); //Draw points from this line until we leave the window @@ -323,26 +323,33 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv var fieldValue = chunk.frames[frameIndex][fieldIndex], frameTime = chunk.frames[frameIndex][FlightLogParser.prototype.FLIGHT_LOG_FIELD_INDEX_TIME], - nextX, nextY; - + nextX, nextY, + valueIsArray = Array.isArray(fieldValue); + + // When field value is an array use the last array value to build the graph + if (valueIsArray) { + nextY = curve.lookup(fieldValue[fieldValue.length - 1]) * yScale; + } + else { + nextY = curve.lookup(fieldValue) * yScale; + } - nextY = curve.lookup(fieldValue) * yScale; nextX = (frameTime - windowStartTime) * xScale; // clamp the Y to the range of the graph to prevent bleed into next graph if zoomed in (for example) - if(nextY>plotHeight) { + if (nextY > plotHeight) { nextY = plotHeight; notInBounds++; } else - if(nextY<(-1)*plotHeight) { - nextY = (-1)*plotHeight; + if (nextY < (-1) * plotHeight) { + nextY = (-1) * plotHeight; notInBounds++; } else notInBounds = -5; - if(notInBounds>5) notInBounds = -5; // reset it every 5th line draw (to simulate dashing) + if (notInBounds>5) notInBounds = -5; // reset it every 5th line draw (to simulate dashing) - if (drawingLine && (notInBounds<=0)) { + if (drawingLine && (notInBounds <= 0)) { canvasContext.lineTo(nextX, nextY); if (!options.gapless && chunk.gapStartsHere[frameIndex]) { @@ -350,7 +357,7 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv inGap = true; drawingLine = false; continue; - } + } } else { canvasContext.moveTo(nextX, nextY); @@ -371,12 +378,38 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv } } + // Draw DSHOT motor events + if (valueIsArray && drawDshotStatusArrayField) { + // Draw triangle to notify motor alert event + if (fieldValue[0]) { + canvasContext.lineTo(nextX, nextY - 2); + canvasContext.moveTo(nextX, nextY); + } + + // Draw triangle to notify motor warning event + if (fieldValue[1]) { + canvasContext.lineTo(nextX - 4, nextY + 8); + canvasContext.lineTo(nextX + 4, nextY + 8); + canvasContext.lineTo(nextX, nextY); + } + + // Draw vertical line to notify motor error event + if (fieldValue[2]) { + canvasContext.moveTo(nextX, -plotHeight); + canvasContext.lineTo(nextX, plotHeight); + canvasContext.fillText("Stall!!!", nextX, -plotHeight + 10); + } + + // Restore last position + canvasContext.moveTo(nextX, nextY); + } + drawingLine = true; if (frameTime >= windowEndTime) break plottingLoop; } - + frameIndex = 0; } @@ -398,13 +431,13 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv function drawAxisLine() { canvasContext.strokeStyle = "rgba(255,255,255,0.5)"; canvasContext.lineWidth = 1; - canvasContext.setLineDash([5]); // Make the center line a dash + canvasContext.setLineDash([5]); // Make the center line a dash canvasContext.beginPath(); canvasContext.moveTo(0, 0); canvasContext.lineTo(canvas.width, 0); - + canvasContext.stroke(); - canvasContext.setLineDash([]); + canvasContext.setLineDash([]); } //Draw an background for the line for a graph (at the origin and spanning the window) @@ -425,36 +458,36 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv GRID_LINES = 10, min = -settings.inputRange - settings.offset, max = settings.inputRange - settings.offset, - GRID_INTERVAL = 1/GRID_LINES * (max - min), - yScale = -plotHeight/2; + GRID_INTERVAL = 1 / GRID_LINES * (max - min), + yScale = -plotHeight / 2; canvasContext.strokeStyle = "rgba(255,255,255,0.5)"; // Grid Color - canvasContext.setLineDash([1,10]); // Make the grid line a dash + canvasContext.setLineDash([1, 10]); // Make the grid line a dash canvasContext.lineWidth = 1; canvasContext.beginPath(); // horizontal lines - for(var y=1; y= windowStartTime - BEGIN_MARGIN_MICROSECONDS) && (bookmarkEvents[i].time < windowEndTime)) { drawEvent( { - event:FlightLogEvent.CUSTOM, - time:bookmarkEvents[i].time, - label: i + event: FlightLogEvent.CUSTOM, + time: bookmarkEvents[i].time, + label: i }, sequenceNum++); }; - }; - }; + }; + }; }; } @@ -763,7 +796,7 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv chunks = flightLog.getSmoothedChunksInTimeRange(windowStartTime, windowEndTime), startChunkIndex, startFrameIndex, i, j; - + if (chunks.length) { //Find the first sample that lies inside the window for (startFrameIndex = 0; startFrameIndex < chunks[0].frames.length; startFrameIndex++) { @@ -798,16 +831,16 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv if (options.drawGradient && graphs.length > 1) // only draw the background if more than one graph set. drawAxisBackground(canvas.height * graph.height); - + for (j = 0; j < graph.fields.length; j++) { if (graphConfig.isGraphFieldHidden(i, j)) { continue; } var field = graph.fields[j]; - plotField(chunks, startFrameIndex, field.index, field.curve, canvas.height * graph.height / 2, + plotField(chunks, startFrameIndex, field.index, field.curve, canvas.height * graph.height / 2, field.color ? field.color : GraphConfig.PALETTE[j % GraphConfig.PALETTE.length], - field.lineWidth ? field.lineWidth : null, - graphConfig.highlightGraphIndex==i && graphConfig.highlightFieldIndex==j); + field.lineWidth ? field.lineWidth : null, + graphConfig.highlightGraphIndex == i && graphConfig.highlightFieldIndex == j); } if (graph.label) { @@ -836,7 +869,7 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv canvasContext.moveTo(centerX, 0); canvasContext.lineTo(centerX, canvas.height); canvasContext.stroke(); - + } // Draw events - if option set or even if option is not set but there are graphs @@ -871,11 +904,11 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv // Draw Analyser if (options.drawAnalyser && graphConfig.selectedFieldName) { - try{ // If we do not select a graph/field, then the analyser is hidden - var graph = graphs[graphConfig.selectedGraphIndex]; - var field = graph.fields[graphConfig.selectedFieldIndex]; - analyser.plotSpectrum(field.index, field.curve, field.friendlyName); - } catch(err) {console.log('Cannot plot analyser ' + err);} + try { // If we do not select a graph/field, then the analyser is hidden + var graph = graphs[graphConfig.selectedGraphIndex]; + var field = graph.fields[graphConfig.selectedFieldIndex]; + analyser.plotSpectrum(field.index, field.curve, field.friendlyName); + } catch (err) { console.log('Cannot plot analyser ' + err); } } //Draw Watermark @@ -1047,10 +1080,10 @@ function FlightLogGrapher(flightLog, graphConfig, canvas, stickCanvas, craftCanv this.refreshLogo(); /* Create the FlightLogAnalyser object */ - analyser = new FlightLogAnalyser(flightLog, canvas, analyserCanvas); + analyser = new FlightLogAnalyser(flightLog, canvas, analyserCanvas); /* Create the Lap Timer object */ - lapTimer = new LapTimer(); + lapTimer = new LapTimer(); //Handle dragging events $(canvas).on("mousedown", onMouseDown); diff --git a/js/main.js b/js/main.js index d9cc2051..be2a131a 100644 --- a/js/main.js +++ b/js/main.js @@ -50,7 +50,7 @@ function BlackboxLogViewer() { prefs = new PrefStorage(), - configuration = null, // is their an associated dump file ? + configuration = null, // is their an associated dump file ? configurationDefaults = new ConfigurationDefaults(prefs), // configuration defaults // User's video render config: @@ -66,7 +66,7 @@ function BlackboxLogViewer() { lastGraphConfig = null, // Undo feature - go back to last configuration. workspaceGraphConfigs = [], // Workspaces activeWorkspace = 1, // Active Workspace - bookmarkTimes = [], // Empty array for bookmarks (times) + bookmarkTimes = [], // Empty array for bookmarks (times) // Graph configuration which is currently in use, customised based on the current flight log from graphConfig activeGraphConfig = new GraphConfig(), @@ -168,6 +168,9 @@ function BlackboxLogViewer() { if (value === null) return "(absent)"; + if (Array.isArray(value)) + return value.toString(); + return value.toFixed(2); } @@ -239,8 +242,8 @@ function BlackboxLogViewer() { // Update flight mode flags on status bar $(".flight-mode", statusBar).text( - fieldPresenter.decodeFieldToFriendly(null, 'flightModeFlags', currentFlightMode, null) - ); + fieldPresenter.decodeFieldToFriendly(null, 'flightModeFlags', currentFlightMode, null) + ); // update time field on status bar $(".graph-time").val(formatTime((currentBlackboxTime-flightLog.getMinTime())/1000, true)); @@ -857,22 +860,22 @@ function BlackboxLogViewer() { } this.getBookmarks = function() { // get bookmark events - var bookmarks = []; - try { - if(bookmarkTimes!=null) { - for(var i=0; i<=9; i++) { - if(bookmarkTimes[i]!=null) { - bookmarks[i] = { - state: (bookmarkTimes[i]!=0), - time: bookmarkTimes[i] - }; - } else bookmarks[i] = null; - } - } - return bookmarks; - } catch(e) { - return null; - } + var bookmarks = []; + try { + if (bookmarkTimes != null) { + for (var i = 0; i <= 9; i++) { + if (bookmarkTimes[i] != null) { + bookmarks[i] = { + state: (bookmarkTimes[i] != 0), + time: bookmarkTimes[i] + }; + } else bookmarks[i] = null; + } + } + return bookmarks; + } catch (e) { + return null; + } } this.getBookmarkTimes = function() { @@ -1444,28 +1447,28 @@ function BlackboxLogViewer() { }, function(newSettings) { // onSave - userSettings = newSettings; + userSettings = newSettings; - prefs.set('userSettings', newSettings); + prefs.set('userSettings', newSettings); - // refresh the craft model - if(graph!=null) { - graph.refreshOptions(newSettings); - graph.refreshLogo(); - graph.initializeCraftModel(); + // refresh the craft model + if(graph!=null) { + graph.refreshOptions(newSettings); + graph.refreshLogo(); + graph.initializeCraftModel(); if(flightLog.hasGpsData()) { mapGrapher.setUserSettings(newSettings); } - updateCanvasSize(); - } + updateCanvasSize(); + } - }), + }), - exportDialog = new VideoExportDialog($("#dlgVideoExport"), function(newConfig) { - videoConfig = newConfig; - - prefs.set('videoConfig', newConfig); - }); + exportDialog = new VideoExportDialog($("#dlgVideoExport"), function(newConfig) { + videoConfig = newConfig; + + prefs.set('videoConfig', newConfig); + }); $(".open-graph-configuration-dialog").click(function(e) { e.preventDefault(); @@ -1491,14 +1494,14 @@ function BlackboxLogViewer() { }); $(".marker-offset", statusBar).click(function(e) { - setCurrentBlackboxTime(markerTime); - invalidateGraph(); + setCurrentBlackboxTime(markerTime); + invalidateGraph(); }); for(var i=1; i< 9; i++) { // Loop through all the bookmarks. $('.bookmark-'+i, statusBar).click(function() { - setCurrentBlackboxTime(bookmarkTimes[parseInt(this.className.slice(-1))]); - invalidateGraph(); + setCurrentBlackboxTime(bookmarkTimes[parseInt(this.className.slice(-1))]); + invalidateGraph(); }); } @@ -1508,7 +1511,7 @@ function BlackboxLogViewer() { $('.bookmark-'+ i, statusBar).css('visibility', 'hidden' ); } $('.bookmark-clear', statusBar).css('visibility', 'hidden' ); - invalidateGraph(); + invalidateGraph(); }); $('.configuration-file-name', statusBar).click(function(e) { @@ -1935,38 +1938,38 @@ function BlackboxLogViewer() { } } } else { // Bookmark Feature - if (!e.shiftKey) { // retrieve time from bookmark - if (bookmarkTimes[e.which-48] != null) { - setCurrentBlackboxTime(bookmarkTimes[e.which-48]); - invalidateGraph(); - } - - } else {// store time to bookmark - // Special Case : Shift Alt 0 clears all bookmarks - if(e.which==48) { - bookmarkTimes = null; - for(var i=1; i<=9; i++) { - $('.bookmark-'+ i, statusBar).css('visibility', 'hidden' ); - } - $('.bookmark-clear', statusBar).css('visibility', 'hidden' ); - } else { - if(bookmarkTimes==null) bookmarkTimes = new Array(); - if (bookmarkTimes[e.which-48] == null) { - bookmarkTimes[e.which-48] = currentBlackboxTime; // Save current time to bookmark + if (!e.shiftKey) { // retrieve time from bookmark + if (bookmarkTimes[e.which - 48] != null) { + setCurrentBlackboxTime(bookmarkTimes[e.which - 48]); + invalidateGraph(); + } + + } else {// store time to bookmark + // Special Case : Shift Alt 0 clears all bookmarks + if (e.which == 48) { + bookmarkTimes = null; + for (var i = 1; i <= 9; i++) { + $('.bookmark-' + i, statusBar).css('visibility', 'hidden'); + } + $('.bookmark-clear', statusBar).css('visibility', 'hidden'); + } else { + if (bookmarkTimes == null) bookmarkTimes = new Array(); + if (bookmarkTimes[e.which - 48] == null) { + bookmarkTimes[e.which - 48] = currentBlackboxTime; // Save current time to bookmark } else { - bookmarkTimes[e.which-48] = null; // clear the bookmark + bookmarkTimes[e.which - 48] = null; // clear the bookmark } - $('.bookmark-'+(e.which-48), statusBar).css('visibility', ((bookmarkTimes[e.which-48]!=null)?('visible'):('hidden')) ); + $('.bookmark-' + (e.which - 48), statusBar).css('visibility', ((bookmarkTimes[e.which - 48] != null) ? ('visible') : ('hidden'))); var countBookmarks = 0; - for(var i=0; i<=9; i++) { - countBookmarks += (bookmarkTimes[i]!=null)?1:0; + for (var i = 0; i <= 9; i++) { + countBookmarks += (bookmarkTimes[i] != null) ? 1 : 0; } - $('.bookmark-clear', statusBar).css('visibility', ((countBookmarks>0)?('visible'):('hidden')) ); + $('.bookmark-clear', statusBar).css('visibility', ((countBookmarks > 0) ? ('visible') : ('hidden'))); - } - invalidateGraph(); - } - } + } + invalidateGraph(); + } + } } catch(e) { console.log('Workspace feature not functioning'); }