diff --git a/index.html b/index.html
index 3f41083f..94cf99f8 100644
--- a/index.html
+++ b/index.html
@@ -457,9 +457,11 @@
Workspace
diff --git a/src/graph_spectrum.js b/src/graph_spectrum.js
index 5d07c588..af5509bd 100644
--- a/src/graph_spectrum.js
+++ b/src/graph_spectrum.js
@@ -112,6 +112,14 @@ export function FlightLogAnalyser(flightLog, canvas, analyserCanvas) {
fftData = GraphSpectrumCalc.dataLoadFrequencyVsRpm();
break;
+ case SPECTRUM_TYPE.PSD_VS_THROTTLE:
+ fftData = GraphSpectrumCalc.dataLoadFrequencyVsThrottle(true);
+ break;
+
+ case SPECTRUM_TYPE.PSD_VS_RPM:
+ fftData = GraphSpectrumCalc.dataLoadFrequencyVsRpm(true);
+ break;
+
case SPECTRUM_TYPE.PIDERROR_VS_SETPOINT:
fftData = GraphSpectrumCalc.dataLoadPidErrorVsSetpoint();
break;
diff --git a/src/graph_spectrum_calc.js b/src/graph_spectrum_calc.js
index f29989aa..75301636 100644
--- a/src/graph_spectrum_calc.js
+++ b/src/graph_spectrum_calc.js
@@ -79,7 +79,7 @@ GraphSpectrumCalc.setOutTime = function(time) {
if ((time - this._analyserTimeRange.in) <= MAX_ANALYSER_LENGTH) {
this._analyserTimeRange.out = time;
} else {
- this._analyserTimeRange.out = analyserTimeRange.in + MAX_ANALYSER_LENGTH;
+ this._analyserTimeRange.out = this._analyserTimeRange.in + MAX_ANALYSER_LENGTH;
}
return this._analyserTimeRange.out;
};
@@ -110,11 +110,11 @@ GraphSpectrumCalc.dataLoadPSD = function(analyserZoomY) {
const flightSamples = this._getFlightSamplesFreq(false);
let pointsPerSegment = 512;
- const multipiler = Math.floor(1 / analyserZoomY); // 0. ... 10
- if (multipiler == 0) {
+ const multiplier = Math.floor(1 / analyserZoomY); // 0. ... 10
+ if (multiplier == 0) {
pointsPerSegment = 256;
- } else if (multipiler > 1) {
- pointsPerSegment *= 2 ** Math.floor(multipiler / 2);
+ } else if (multiplier > 1) {
+ pointsPerSegment *= 2 ** Math.floor(multiplier / 2);
}
pointsPerSegment = Math.min(pointsPerSegment, flightSamples.samples.length);
const overlapCount = Math.floor(pointsPerSegment / 2);
@@ -129,7 +129,7 @@ GraphSpectrumCalc.dataLoadPSD = function(analyserZoomY) {
blackBoxRate : this._blackBoxRate,
minimum: psd.min,
maximum: psd.max,
- maxNoiseIdx: psd.maxNoiseIdx,
+ maxNoiseFrequency: psd.maxNoiseFrequency,
};
return psdData;
};
@@ -218,12 +218,85 @@ GraphSpectrumCalc._dataLoadFrequencyVsX = function(vsFieldNames, minValue = Infi
};
-GraphSpectrumCalc.dataLoadFrequencyVsThrottle = function() {
- return this._dataLoadFrequencyVsX(FIELD_THROTTLE_NAME, 0, 100);
+GraphSpectrumCalc._dataLoadPowerSpectralDensityVsX = function(vsFieldNames, minValue = Infinity, maxValue = -Infinity) {
+
+ const flightSamples = this._getFlightSamplesFreqVsX(vsFieldNames, minValue, maxValue, false);
+
+ // We divide it into FREQ_VS_THR_CHUNK_TIME_MS FFT chunks, we calculate the average throttle
+ // for each chunk. We use a moving window to get more chunks available.
+ const fftChunkLength = Math.round(this._blackBoxRate * FREQ_VS_THR_CHUNK_TIME_MS / 1000);
+ const fftChunkWindow = Math.round(fftChunkLength / FREQ_VS_THR_WINDOW_DIVISOR);
+
+ let maxNoise = 0; // Stores the maximum amplitude of the fft over all chunks
+ const psdLength = Math.floor(fftChunkLength / 2);
+ // Matrix where each row represents a bin of vs values, and the columns are amplitudes at frequencies
+ const matrixPsdOutput = new Array(NUM_VS_BINS)
+ .fill(null)
+ .map(() => (new Float64Array(psdLength)).fill(-100));
+
+ const numberSamples = new Uint32Array(NUM_VS_BINS); // Number of samples in each vs value, used to average them later.
+
+ for (let fftChunkIndex = 0; fftChunkIndex + fftChunkLength < flightSamples.samples.length; fftChunkIndex += fftChunkWindow) {
+
+ const fftInput = flightSamples.samples.slice(fftChunkIndex, fftChunkIndex + fftChunkLength);
+ const psd = this._psd(fftInput, fftChunkLength, 0, 'density');
+ maxNoise = Math.max(psd.max, maxNoise);
+ // calculate a bin index and put the fft value in that bin for each field (e.g. eRPM[0], eRPM[1]..) sepparately
+ for (const vsValueArray of flightSamples.vsValues) {
+ // Calculate average of the VS values in the chunk
+ let sumVsValues = 0;
+ for (let indexVs = fftChunkIndex; indexVs < fftChunkIndex + fftChunkLength; indexVs++) {
+ sumVsValues += vsValueArray[indexVs];
+ }
+ // Translate the average vs value to a bin index
+ const avgVsValue = sumVsValues / fftChunkLength;
+ let vsBinIndex = Math.floor(NUM_VS_BINS * (avgVsValue - flightSamples.minValue) / (flightSamples.maxValue - flightSamples.minValue));
+ // ensure that avgVsValue == flightSamples.maxValue does not result in an out of bounds access
+ if (vsBinIndex === NUM_VS_BINS) { vsBinIndex = NUM_VS_BINS - 1; }
+ numberSamples[vsBinIndex]++;
+
+ // add the output from the fft to the row given by the vs value bin index
+ for (let i = 0; i < psdLength; i++) {
+ matrixPsdOutput[vsBinIndex][i] += psd.psdOutput[i];
+ }
+ }
+ }
+
+ // Divide the values from the fft in each row (vs value bin) by the number of samples in the bin
+ for (let i = 0; i < NUM_VS_BINS; i++) {
+ if (numberSamples[i] > 1) {
+ for (let j = 0; j < psdLength; j++) {
+ matrixPsdOutput[i][j] /= numberSamples[i];
+ }
+ }
+ }
+
+ // The output data needs to be smoothed, the sampling is not perfect
+ // but after some tests we let the data as is, an we prefer to apply a
+ // blur algorithm to the heat map image
+
+ const psdData = {
+ fieldIndex : this._dataBuffer.fieldIndex,
+ fieldName : this._dataBuffer.fieldName,
+ fftLength : psdLength,
+ fftOutput : matrixPsdOutput,
+ maxNoise : maxNoise,
+ blackBoxRate : this._blackBoxRate,
+ vsRange : { min: flightSamples.minValue, max: flightSamples.maxValue},
+ };
+
+ return psdData;
+
+};
+
+GraphSpectrumCalc.dataLoadFrequencyVsThrottle = function(drawPSD = false) {
+ return drawPSD ? this._dataLoadPowerSpectralDensityVsX(FIELD_THROTTLE_NAME, 0, 100) :
+ this._dataLoadFrequencyVsX(FIELD_THROTTLE_NAME, 0, 100);
};
-GraphSpectrumCalc.dataLoadFrequencyVsRpm = function() {
- const fftData = this._dataLoadFrequencyVsX(FIELD_RPM_NAMES, 0);
+GraphSpectrumCalc.dataLoadFrequencyVsRpm = function(drawPSD = false) {
+ const fftData = drawPSD ? this._dataLoadPowerSpectralDensityVsX(FIELD_RPM_NAMES, 0) :
+ this._dataLoadFrequencyVsX(FIELD_RPM_NAMES, 0);
fftData.vsRange.max *= 3.333 / this._motorPoles;
fftData.vsRange.min *= 3.333 / this._motorPoles;
return fftData;
@@ -345,7 +418,7 @@ GraphSpectrumCalc._getVsIndexes = function(vsFieldNames) {
return fieldIndexes;
};
-GraphSpectrumCalc._getFlightSamplesFreqVsX = function(vsFieldNames, minValue = Infinity, maxValue = -Infinity) {
+GraphSpectrumCalc._getFlightSamplesFreqVsX = function(vsFieldNames, minValue = Infinity, maxValue = -Infinity, scaled = true) {
const allChunks = this._getFlightChunks();
const vsIndexes = this._getVsIndexes(vsFieldNames);
@@ -356,7 +429,11 @@ GraphSpectrumCalc._getFlightSamplesFreqVsX = function(vsFieldNames, minValue = I
let samplesCount = 0;
for (const chunk of allChunks) {
for (let frameIndex = 0; frameIndex < chunk.frames.length; frameIndex++) {
- samples[samplesCount] = (this._dataBuffer.curve.lookupRaw(chunk.frames[frameIndex][this._dataBuffer.fieldIndex]));
+ if (scaled) {
+ samples[samplesCount] = (this._dataBuffer.curve.lookupRaw(chunk.frames[frameIndex][this._dataBuffer.fieldIndex]));
+ } else {
+ samples[samplesCount] = chunk.frames[frameIndex][this._dataBuffer.fieldIndex];
+ }
for (let i = 0; i < vsIndexes.length; i++) {
let vsFieldIx = vsIndexes[i];
let value = chunk.frames[frameIndex][vsFieldIx];
@@ -503,14 +580,14 @@ GraphSpectrumCalc._normalizeFft = function(fftOutput, fftLength) {
}
}
- maxNoiseIdx = maxNoiseIdx / fftLength * maxFrequency;
+ const maxNoiseFrequency = maxNoiseIdx / fftLength * maxFrequency;
const fftData = {
fieldIndex : this._dataBuffer.fieldIndex,
fieldName : this._dataBuffer.fieldName,
fftLength : fftLength,
fftOutput : fftOutput,
- maxNoiseIdx : maxNoiseIdx,
+ maxNoiseFrequency : maxNoiseFrequency,
blackBoxRate : this._blackBoxRate,
};
@@ -561,7 +638,7 @@ GraphSpectrumCalc._psd = function(samples, pointsPerSegment, overlapCount, scal
psdOutput: new Float64Array(0),
min: 0,
max: 0,
- maxNoiseIdx: 0,
+ maxNoiseFrequency: 0,
};
}
const maxFrequency = (this._blackBoxRate / 2.0);
@@ -599,16 +676,16 @@ GraphSpectrumCalc._psd = function(samples, pointsPerSegment, overlapCount, scal
psdOutput: psdOutput,
min: min,
max: max,
- maxNoiseIdx: maxNoiseFrequency,
+ maxNoiseFrequency: maxNoiseFrequency,
};
};
-
/**
* Compute FFT for samples segments by lenghts as pointsPerSegment with overlapCount overlap points count
*/
GraphSpectrumCalc._fft_segmented = function(samples, pointsPerSegment, overlapCount) {
- const samplesCount = samples.length;
+ const samplesCount = samples.length,
+ fftLength = Math.floor(pointsPerSegment / 2);
let output = [];
for (let i = 0; i <= samplesCount - pointsPerSegment; i += pointsPerSegment - overlapCount) {
const fftInput = samples.slice(i, i + pointsPerSegment);
@@ -618,8 +695,8 @@ GraphSpectrumCalc._fft_segmented = function(samples, pointsPerSegment, overlapC
}
const fftComplex = this._fft(fftInput);
- const magnitudes = new Float64Array(pointsPerSegment / 2);
- for (let i = 0; i < pointsPerSegment / 2; i++) {
+ const magnitudes = new Float64Array(fftLength);
+ for (let i = 0; i < fftLength; i++) {
const re = fftComplex[2 * i];
const im = fftComplex[2 * i + 1];
magnitudes[i] = Math.hypot(re, im);
diff --git a/src/graph_spectrum_plot.js b/src/graph_spectrum_plot.js
index 2ff35470..93c04267 100644
--- a/src/graph_spectrum_plot.js
+++ b/src/graph_spectrum_plot.js
@@ -15,9 +15,11 @@ const BLUR_FILTER_PIXEL = 1,
export const SPECTRUM_TYPE = {
FREQUENCY: 0,
FREQ_VS_THROTTLE: 1,
- PIDERROR_VS_SETPOINT: 2,
- FREQ_VS_RPM: 3,
- POWER_SPECTRAL_DENSITY: 4,
+ FREQ_VS_RPM: 2,
+ POWER_SPECTRAL_DENSITY: 3,
+ PSD_VS_THROTTLE: 4,
+ PSD_VS_RPM: 5,
+ PIDERROR_VS_SETPOINT: 6,
};
export const SPECTRUM_OVERDRAW_TYPE = {
@@ -169,6 +171,14 @@ GraphSpectrumPlot._drawGraph = function (canvasCtx) {
this._drawFrequencyVsXGraph(canvasCtx);
break;
+ case SPECTRUM_TYPE.PSD_VS_THROTTLE:
+ this._drawFrequencyVsXGraph(canvasCtx, true);
+ break;
+
+ case SPECTRUM_TYPE.PSD_VS_RPM:
+ this._drawFrequencyVsXGraph(canvasCtx, true);
+ break;
+
case SPECTRUM_TYPE.PIDERROR_VS_SETPOINT:
this._drawPidErrorVsSetpointGraph(canvasCtx);
break;
@@ -382,7 +392,7 @@ GraphSpectrumPlot._drawPowerSpectralDensityGraph = function (canvasCtx) {
const offset = 1;
this._drawInterestFrequency(
canvasCtx,
- this._fftData.maxNoiseIdx,
+ this._fftData.maxNoiseFrequency,
PLOTTED_BLACKBOX_RATE,
"Max noise",
WIDTH,
@@ -395,7 +405,14 @@ GraphSpectrumPlot._drawPowerSpectralDensityGraph = function (canvasCtx) {
canvasCtx.restore();
};
-GraphSpectrumPlot._drawFrequencyVsXGraph = function (canvasCtx) {
+GraphSpectrumPlot.getPSDbyFreq = function(frequency) {
+ let freqIndex = Math.round(2 * frequency / this._fftData.blackBoxRate * (this._fftData.psdOutput.length - 1) );
+ freqIndex = Math.min(freqIndex, this._fftData.psdOutput.length - 1);
+ freqIndex = Math.max(freqIndex, 0);
+ return this._fftData.psdOutput.length ? this._fftData.psdOutput[freqIndex] : 0;
+};
+
+GraphSpectrumPlot._drawFrequencyVsXGraph = function (canvasCtx, drawPSD = false) {
const PLOTTED_BLACKBOX_RATE = this._fftData.blackBoxRate / this._zoomX;
const ACTUAL_MARGIN_LEFT = this._getActualMarginLeft();
@@ -407,7 +424,7 @@ GraphSpectrumPlot._drawFrequencyVsXGraph = function (canvasCtx) {
canvasCtx.translate(LEFT, TOP);
if (this._cachedDataCanvas == null) {
- this._cachedDataCanvas = this._drawHeatMap();
+ this._cachedDataCanvas = this._drawHeatMap(drawPSD);
}
canvasCtx.drawImage(this._cachedDataCanvas, 0, 0, WIDTH, HEIGHT);
@@ -442,7 +459,8 @@ GraphSpectrumPlot._drawFrequencyVsXGraph = function (canvasCtx) {
"Hz"
);
- if (this._spectrumType === SPECTRUM_TYPE.FREQ_VS_THROTTLE) {
+ if (this._spectrumType === SPECTRUM_TYPE.FREQ_VS_THROTTLE ||
+ this._spectrumType === SPECTRUM_TYPE.PSD_VS_THROTTLE) {
this._drawVerticalGridLines(
canvasCtx,
LEFT,
@@ -453,7 +471,8 @@ GraphSpectrumPlot._drawFrequencyVsXGraph = function (canvasCtx) {
this._fftData.vsRange.max,
"%"
);
- } else if (this._spectrumType === SPECTRUM_TYPE.FREQ_VS_RPM) {
+ } else if (this._spectrumType === SPECTRUM_TYPE.FREQ_VS_RPM ||
+ this._spectrumType === SPECTRUM_TYPE.PSD_VS_RPM) {
this._drawVerticalGridLines(
canvasCtx,
LEFT,
@@ -467,7 +486,7 @@ GraphSpectrumPlot._drawFrequencyVsXGraph = function (canvasCtx) {
}
};
-GraphSpectrumPlot._drawHeatMap = function () {
+GraphSpectrumPlot._drawHeatMap = function (drawPSD = false) {
const THROTTLE_VALUES_SIZE = 100;
const SCALE_HEATMAP = 1.3; // Value decided after some tests to be similar to the scale of frequency graph
// This value will be maximum color
@@ -485,9 +504,17 @@ GraphSpectrumPlot._drawHeatMap = function () {
for (let j = 0; j < 100; j++) {
// Loop for frequency
for (let i = 0; i < this._fftData.fftLength; i++) {
- const valuePlot = Math.round(
- Math.min(this._fftData.fftOutput[j][i] * fftColorScale, 100)
- );
+ let valuePlot;
+ if (drawPSD) {
+ const min = -40, max = 10; //limit values dBm
+ valuePlot = Math.max(this._fftData.fftOutput[j][i], min);
+ valuePlot = Math.min(valuePlot, max);
+ valuePlot = Math.round((valuePlot - min) * 100 / (max - min));
+ } else {
+ valuePlot = Math.round(
+ Math.min(this._fftData.fftOutput[j][i] * fftColorScale, 100)
+ );
+ }
// The fillStyle is slow, but I haven't found a way to do this faster...
canvasCtx.fillStyle = `hsl(360, 100%, ${valuePlot}%)`;
@@ -503,6 +530,19 @@ GraphSpectrumPlot._drawHeatMap = function () {
return heatMapCanvas;
};
+GraphSpectrumPlot.getValueFromMatrixFFT = function(frequency, vsArgument) {
+ const NUM_VS_BINS = 100; // redefinition of value from graph_spectrum_calc.js module!
+ const matrixFFT = this._fftData;
+ let vsArgumentIndex = Math.round(NUM_VS_BINS * (vsArgument - matrixFFT.vsRange.min) / (matrixFFT.vsRange.max - matrixFFT.vsRange.min));
+ if (vsArgumentIndex === NUM_VS_BINS) {
+ vsArgumentIndex = NUM_VS_BINS - 1;
+ }
+ let freqIndex = Math.round(2 * frequency / matrixFFT.blackBoxRate * (matrixFFT.fftLength - 1));
+ freqIndex = Math.max(freqIndex, 0);
+ freqIndex = Math.min(freqIndex, matrixFFT.fftLength - 1);
+ return matrixFFT.fftOutput[vsArgumentIndex][freqIndex];
+};
+
GraphSpectrumPlot._drawPidErrorVsSetpointGraph = function (canvasCtx) {
const ACTUAL_MARGIN_LEFT = this._getActualMarginLeft();
@@ -947,7 +987,7 @@ GraphSpectrumPlot._drawFiltersAndMarkers = function (canvasCtx) {
if (this._spectrumType === SPECTRUM_TYPE.FREQUENCY) {
this._drawInterestFrequency(
canvasCtx,
- this._fftData.maxNoiseIdx,
+ this._fftData.maxNoiseFrequency,
PLOTTED_BLACKBOX_RATE,
"Max noise",
WIDTH,
@@ -1238,7 +1278,14 @@ GraphSpectrumPlot._drawInterestFrequency = function (
stroke,
lineWidth
) {
- const interestLabel = `${label} ${frequency.toFixed(0)}Hz`;
+
+ let interestLabel = "";
+ if (this._spectrumType === SPECTRUM_TYPE.POWER_SPECTRAL_DENSITY && label != "" ) {
+ const psdValue = this.getPSDbyFreq(frequency);
+ interestLabel = `${label}: (${frequency.toFixed(0)}Hz, ${psdValue.toFixed(0)}dBm/Hz)`;
+ } else {
+ interestLabel = `${label} ${frequency.toFixed(0)}Hz`;
+ }
return this._drawVerticalMarkerLine(
canvasCtx,
frequency,
@@ -1443,17 +1490,20 @@ GraphSpectrumPlot._drawMousePosition = function (
lineWidth
) {
// X axis
+ let mouseFrequency = 0;
if (
this._spectrumType === SPECTRUM_TYPE.FREQUENCY ||
this._spectrumType === SPECTRUM_TYPE.FREQ_VS_THROTTLE ||
this._spectrumType === SPECTRUM_TYPE.FREQ_VS_RPM ||
- this._spectrumType === SPECTRUM_TYPE.POWER_SPECTRAL_DENSITY
+ this._spectrumType === SPECTRUM_TYPE.POWER_SPECTRAL_DENSITY ||
+ this._spectrumType === SPECTRUM_TYPE.PSD_VS_THROTTLE ||
+ this._spectrumType === SPECTRUM_TYPE.PSD_VS_RPM
) {
// Calculate frequency at mouse
const sampleRate = this._fftData.blackBoxRate / this._zoomX;
const marginLeft = this._getActualMarginLeft();
- const mouseFrequency =
+ mouseFrequency =
((mouseX - marginLeft) / WIDTH) *
(this._fftData.blackBoxRate / this._zoomX / 2);
if (mouseFrequency >= 0 && mouseFrequency <= sampleRate) {
@@ -1470,13 +1520,26 @@ GraphSpectrumPlot._drawMousePosition = function (
);
}
+ if (this._spectrumType === SPECTRUM_TYPE.POWER_SPECTRAL_DENSITY) {
+ const psdLabel = Math.round(this.getPSDbyFreq(mouseFrequency)).toString() + "dBm/Hz";
+ this._drawAxisLabel(
+ canvasCtx,
+ psdLabel,
+ mouseX - 30,
+ mouseY - 4,
+ "left",
+ );
+ }
+
// Y axis
let unitLabel;
switch (this._spectrumType) {
case SPECTRUM_TYPE.FREQ_VS_THROTTLE:
+ case SPECTRUM_TYPE.PSD_VS_THROTTLE:
unitLabel = "%";
break;
case SPECTRUM_TYPE.FREQ_VS_RPM:
+ case SPECTRUM_TYPE.PSD_VS_RPM:
unitLabel = "Hz";
break;
case SPECTRUM_TYPE.POWER_SPECTRAL_DENSITY:
@@ -1489,12 +1552,12 @@ GraphSpectrumPlot._drawMousePosition = function (
if (unitLabel !== null) {
const val_min = this._fftData.vsRange.min;
const val_max = this._fftData.vsRange.max;
- const mouseValue = (1 - mouseY / HEIGHT) * (val_max - val_min) + val_min;
- if (mouseValue >= val_min && mouseValue <= val_max) {
- const valueLabel = `${mouseValue.toFixed(0)}${unitLabel}`;
+ const vsArgValue = (1 - mouseY / HEIGHT) * (val_max - val_min) + val_min;
+ if (vsArgValue >= val_min && vsArgValue <= val_max) {
+ const valueLabel = `${vsArgValue.toFixed(0)}${unitLabel}`;
this._drawHorizontalMarkerLine(
canvasCtx,
- mouseValue,
+ vsArgValue,
val_min,
val_max,
valueLabel,
@@ -1504,6 +1567,18 @@ GraphSpectrumPlot._drawMousePosition = function (
stroke,
lineWidth
);
+
+ if (this._spectrumType === SPECTRUM_TYPE.PSD_VS_THROTTLE ||
+ this._spectrumType === SPECTRUM_TYPE.PSD_VS_RPM) {
+ const label = Math.round(this.getValueFromMatrixFFT(mouseFrequency, vsArgValue)).toString() + "dBm/Hz";
+ this._drawAxisLabel(
+ canvasCtx,
+ label,
+ mouseX - 30,
+ mouseY - 4,
+ "left",
+ );
+ }
}
}
} else if (this._spectrumType === SPECTRUM_TYPE.PIDERROR_VS_SETPOINT) {
@@ -1557,6 +1632,8 @@ GraphSpectrumPlot._getActualMarginLeft = function () {
switch (this._spectrumType) {
case SPECTRUM_TYPE.FREQ_VS_THROTTLE:
case SPECTRUM_TYPE.FREQ_VS_RPM:
+ case SPECTRUM_TYPE.PSD_VS_THROTTLE:
+ case SPECTRUM_TYPE.PSD_VS_RPM:
case SPECTRUM_TYPE.POWER_SPECTRAL_DENSITY:
actualMarginLeft = this._isFullScreen
? MARGIN_LEFT_FULLSCREEN