From 4d72a86032db4632402940e7f90fbac9a101a338 Mon Sep 17 00:00:00 2001
From: Iampete1
Date: Mon, 22 May 2023 02:09:54 +0100
Subject: [PATCH] Tools: autotest: Web: remove tools (now here :
https://github.com/ArduPilot/WebTools)
---
.../Tools/FilterReview/DecodeDevID.js | 154 ---
.../Tools/FilterReview/FilterReview.js | 1196 -----------------
.../web-firmware/Tools/FilterReview/Readme.md | 6 -
.../Tools/FilterReview/index.html | 354 -----
.../web-firmware/Tools/FilterReview/parser.js | 882 ------------
.../Tools/FilterTool/FileSaver.js | 171 ---
.../web-firmware/Tools/FilterTool/app.py | 16 -
.../web-firmware/Tools/FilterTool/filters.js | 1196 -----------------
.../web-firmware/Tools/FilterTool/index.html | 378 ------
9 files changed, 4353 deletions(-)
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterReview/DecodeDevID.js
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterReview/FilterReview.js
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterReview/Readme.md
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterReview/index.html
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterReview/parser.js
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterTool/app.py
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterTool/filters.js
delete mode 100644 Tools/autotest/web-firmware/Tools/FilterTool/index.html
diff --git a/Tools/autotest/web-firmware/Tools/FilterReview/DecodeDevID.js b/Tools/autotest/web-firmware/Tools/FilterReview/DecodeDevID.js
deleted file mode 100644
index 26359c3c17..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterReview/DecodeDevID.js
+++ /dev/null
@@ -1,154 +0,0 @@
-/*
- Translated from Tools/scripts/decode_devid.py
-*/
-
-const DEVICE_TYPE_COMPASS = 0
-const DEVICE_TYPE_IMU = 1
-const DEVICE_TYPE_BARO = 2
-const DEVICE_TYPE_AIRSPEED = 3
-
-function decode_devid(ID, type) {
-
-const bus_type = ID & 0x07
-const bus = (ID>>3) & 0x1F
-const address = (ID>>8) & 0xFF
-const devtype = (ID>>16)
-
-bustypes = {
- 1: "I2C",
- 2: "SPI",
- 3: "DRONECAN",
- 4: "SITL",
- 5: "MSP",
- 6: "SERIAL",
-}
-
-compass_types = {
- 0x01 : "HMC5883_OLD",
- 0x07 : "HMC5883",
- 0x02 : "LSM303D",
- 0x04 : "AK8963 ",
- 0x05 : "BMM150 ",
- 0x06 : "LSM9DS1",
- 0x08 : "LIS3MDL",
- 0x09 : "AK09916",
- 0x0A : "IST8310",
- 0x0B : "ICM20948",
- 0x0C : "MMC3416",
- 0x0D : "QMC5883L",
- 0x0E : "MAG3110",
- 0x0F : "SITL",
- 0x10 : "IST8308",
- 0x11 : "RM3100_OLD",
- 0x12 : "RM3100",
- 0x13 : "MMC5883",
- 0x14 : "AK09918",
-}
-
-imu_types = {
- 0x09 : "BMI160",
- 0x10 : "L3G4200D",
- 0x11 : "ACC_LSM303D",
- 0x12 : "ACC_BMA180",
- 0x13 : "ACC_MPU6000",
- 0x16 : "ACC_MPU9250",
- 0x17 : "ACC_IIS328DQ",
- 0x21 : "GYR_MPU6000",
- 0x22 : "GYR_L3GD20",
- 0x24 : "GYR_MPU9250",
- 0x25 : "GYR_I3G4250D",
- 0x26 : "GYR_LSM9DS1",
- 0x27 : "ICM20789",
- 0x28 : "ICM20689",
- 0x29 : "BMI055",
- 0x2A : "SITL",
- 0x2B : "BMI088",
- 0x2C : "ICM20948",
- 0x2D : "ICM20648",
- 0x2E : "ICM20649",
- 0x2F : "ICM20602",
- 0x30 : "ICM20601",
- 0x31 : "ADIS1647x",
- 0x32 : "SERIAL",
- 0x33 : "ICM40609",
- 0x34 : "ICM42688",
- 0x35 : "ICM42605",
- 0x36 : "ICM40605",
- 0x37 : "IIM42652",
- 0x38 : "BMI270",
- 0x39 : "BMI085",
- 0x3A : "ICM42670",
-}
-
-baro_types = {
- 0x01 : "SITL",
- 0x02 : "BMP085",
- 0x03 : "BMP280",
- 0x04 : "BMP388",
- 0x05 : "DPS280",
- 0x06 : "DPS310",
- 0x07 : "FBM320",
- 0x08 : "ICM20789",
- 0x09 : "KELLERLD",
- 0x0A : "LPS2XH",
- 0x0B : "MS5611",
- 0x0C : "SPL06",
- 0x0D : "DRONECAN",
- 0x0E : "MSP",
- 0x0F : "ICP101XX",
- 0x10 : "ICP201XX",
- 0x11 : "MS5607",
- 0x12 : "MS5837",
- 0x13 : "MS5637",
- 0x14 : "BMP390",
-}
-
-airspeed_types = {
- 0x01 : "SITL",
- 0x02 : "MS4525",
- 0x03 : "MS5525",
- 0x04 : "DLVR",
- 0x05 : "MSP",
- 0x06 : "SDP3X",
- 0x07 : "DRONECAN",
- 0x08 : "ANALOG",
- 0x09 : "NMEA",
- 0x0A : "ASP5033",
-}
-
-function get(lookup, index) {
- if (lookup[index] != null) {
- return lookup[index]
- }
- return "Unknown"
-}
-
-var name
-switch (type) {
- case DEVICE_TYPE_COMPASS:
- name = "Compass: " + get(compass_types, devtype)
- break
- case DEVICE_TYPE_IMU:
- name = "IMU: " + get(imu_types, devtype)
- break
- case DEVICE_TYPE_BARO:
- name = "Baro: " + get(baro_types, devtype)
- break
- case DEVICE_TYPE_AIRSPEED:
- name = "Airspeed: " + get(airspeed_types, devtype)
- break
- default:
- console.error("Unknown type");
- return
-}
-
-const bus_type_string = get(bustypes, bus_type)
-
-if (bus_type == 3) {
- // dronecan devtype represents sensor_id
- return { bus_type: bus_type_string, bus: bus, address: address, sensor_id: devtype-1, name: name }
-}
-
-return { bus_type: bus_type_string, bus: bus, address: address, devtype: devtype, name: name }
-
-}
diff --git a/Tools/autotest/web-firmware/Tools/FilterReview/FilterReview.js b/Tools/autotest/web-firmware/Tools/FilterReview/FilterReview.js
deleted file mode 100644
index 4475937458..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterReview/FilterReview.js
+++ /dev/null
@@ -1,1196 +0,0 @@
-// A js tool for plotting ArduPilot batch log data
-
-// Generic Class to hold source for notch target
-class NotchTarget {
- constructor(log, msg_name, key_name, name, mode_value) {
- this.name = name
- this.mode_value = mode_value
- this.data = []
-
- // Don't always need log data (static notch)
- if (log == null) {
- return
- }
-
- // Grab data from log
- log.parseAtOffset(msg_name)
- if ((log.messages[msg_name] == null) || (log.messages[msg_name].length == 0)) {
- return
- }
-
- // Convert ket into array if needed
- if (!Array.isArray(key_name)) {
- key_name = [key_name]
- }
-
- // Grab all given keys to data struct
- this.data.time = []
- for (var j=0; j 0) {
- return math.max(config.freq, rpm * config.ref * (1.0/60.0))
- }
- return config.freq
- }
-}
-
-class ESCTarget extends NotchTarget {
- constructor(log) {
- super(null, null, null, "ESC", 3)
-
- // Grab data from log, have to do it a little differently to get instances
- const msg = "ESC"
- log.parseAtOffset(msg)
- if ((log.messages[msg] == null) || (log.messages[msg].length == 0)) {
- return
- }
-
- // Individual RPM
- var instances = 0
- for (let i=0;i<16;i++) {
- const inst_msg = msg + "[" + i + "]"
- if (log.messages[inst_msg] != null) {
- this.data[i] = { time:[], freq:[] }
- for (var j=0; j < log.messages[inst_msg].time_boot_ms.length; j++) {
- this.data[i].time[j] = log.messages[inst_msg].time_boot_ms[j] / 1000
- this.data[i].freq[j] = log.messages[inst_msg].RPM[j] / 60
- }
- instances++
- }
- }
-
- // Average RPM
- this.data.avg_freq = []
- this.data.avg_time = []
- var inst = []
- for (let i=0;i 1000)) {
- inst[j].time_ms = null
- inst[j].rpm = null
- }
- }
-
- // If a full set of valid instances take average
- var expected_count = 0
- var count = 0
- var sum = 0
- for (let j=0;j 0) && (count == expected_count)) {
- this.data.avg_freq.push((sum / count) / 60)
- this.data.avg_time.push(time_ms / 1000)
-
- // Invalidate used values
- for (let j=0;j 0) && (energy_y > 0)) {
- // Weighted by relative energy
- this.data[i].freq[j] = (freq_x*energy_x + freq_y*energy_y) / (energy_x + energy_y)
- } else {
- // Just take average
- this.data[i].freq[j] = (freq_x + freq_y) * 0.5
- }
- this.data[i].time[j] = log.messages[inst_msg].time_boot_ms[j] / 1000
- }
- }
- }
- }
-
- get_target_freq(config) {
- const dynamic = (config.options & (1<<1)) != 0
- if (dynamic) {
- // Tracking multiple peaks
- let freq = []
- let time = []
-
- for (let i = 0; i < this.data.length; i++) {
- const start_index = find_start_index(this.data[i].time)
- const end_index = find_end_index(this.data[i].time)
-
- let inst_freq = this.data[i].freq.slice(start_index, end_index)
- for (let j = 0; j < inst_freq.length; j++) {
- inst_freq[j] = math.max(inst_freq[j], config.freq)
- }
-
- time.push(...this.data[i].time.slice(start_index, end_index))
- freq.push(...inst_freq)
-
- // Add NAN to remove line from end back to the start
- time.push(NaN)
- freq.push(NaN)
- }
- return { freq:freq, time:time }
- }
-
- // Just center peak
- const start_index = find_start_index(this.data.time)
- const end_index = find_end_index(this.data.time)
-
- let freq = this.data.PkAvg.slice(start_index, end_index)
- for (let j = 0; j < freq.length; j++) {
- freq[j] = math.max(freq[j], config.freq)
- }
-
- return { freq:freq, time:this.data.time.slice(start_index, end_index) }
- }
-}
-
-// return hanning window array of given length (in tensorflow format)
-function hanning(len) {
- const half = tf.scalar(0.5)
- return tf.sub(half, tf.mul(half, tf.cos(tf.linspace(0, 2*math.PI, len))))
-}
-
-// Calculate correction factors for linear and energy spectrum (window in tensorflow format)
-// linear: 1 / mean(w)
-// energy: 1 / sqrt(mean(w.^2))
-function window_correction_factors(w) {
- return {
- linear: 1/tf.mean(w).arraySync(),
- energy: 1/tf.sqrt(tf.mean(tf.square(w))).arraySync()
- }
-}
-
-// Length of real half of fft of len points
-function real_length(len) {
- return math.floor(len / 2) + 1
-}
-
-// Frequency bins for given fft length and sample period (real only)
-function rfft_freq(len, d) {
- const real_len = real_length(len)
- freq = []
- for (var i=0;i
"
- document.getElementById("Gyro1_FFT_info").innerHTML = "
"
- document.getElementById("Gyro2_FFT_info").innerHTML = "
"
-
- // FFT plot setup
- fft_plot.data = []
- for (let i=0;i" + name,
- legendgroup: i,
- legendgrouptitle: { text: "" }
- })
- }
- }
-
- // Define Layout
- Spectrogram.layout = {
- xaxis: {title: {text: "Time (s)"}},
- yaxis: {title: {text: ""}, type: "linear"},
- showlegend: true,
- legend: {itemclick: false, itemdoubleclick: false },
- margin: { b: 50, l: 50, r: 50, t: 20 }
- }
-
- var SpectrogramPlot = document.getElementById("Spectrogram")
- Plotly.purge(SpectrogramPlot)
- Plotly.newPlot(SpectrogramPlot, Spectrogram.data, Spectrogram.layout, {displaylogo: false});
-}
-
-// Calculate if needed and re-draw, called from calculate button
-function re_calc() {
-
- calculate()
-
- redraw()
-}
-
-// Force full re-calc on next run, on window size change
-function clear_calculation() {
- if (Gyro_batch == null) {
- return
- }
- for (let i = 0; i < Gyro_batch.length; i++) {
- if (Gyro_batch[i] == null) {
- continue
- }
- Gyro_batch[i].FFT = null
- }
-}
-
-// Re-run all FFT's
-function calculate() {
- for (let i = 0; i < Gyro_batch.length; i++) {
- if (Gyro_batch[i] == null) {
- continue
- }
- if (Gyro_batch[i].FFT == null) {
- Gyro_batch[i].FFT = run_batch_fft(Gyro_batch[i])
- }
- }
-}
-
-// Get configured amplitude scale
-function get_amplitude_scale() {
-
- const use_DB = document.getElementById("ScaleLog").checked;
- const use_PSD = document.getElementById("SpectrumPSD").checked;
-
- var ret = {}
- if (use_DB) {
- if (use_PSD) {
- ret.fun = function (x) { return math.dotMultiply(math.log10(math.dotMultiply(x,x)), 10.0) } // 10 * log10(x.^2)
- ret.label = "PSD (db)"
- } else {
- ret.fun = function (x) { return math.dotMultiply(math.log10(x), 10.0) } // 10 * log10(x)
- ret.label = "Linear amplitude (db)"
- }
- ret.hover = function (axis) { return "%{" + axis + ":.2f} db" }
-
- } else {
- if (use_PSD) {
- ret.fun = function (x) { return math.dotMultiply(x,x) }
- ret.label = "PSD"
- } else {
- ret.fun = function (x) { return x }
- ret.label = "Linear amplitude"
- }
- ret.hover = function (axis) { return "%{" + axis + ":.2f}" }
-
- }
-
- ret.use_PSD = use_PSD
-
- return ret
-}
-
-// Get configured frequency scale object
-function get_frequency_scale() {
-
- const use_RPM = document.getElementById("freq_Scale_RPM").checked;
-
- var ret = {}
- if (use_RPM) {
- ret.fun = function (x) { return math.dotMultiply(x, 60.0) }
- ret.label = "RPM"
- ret.hover = function (axis) { return "%{" + axis + ":.2f} RPM" }
-
- } else {
- ret.fun = function (x) { return x }
- ret.label = "Frequency (Hz)"
- ret.hover = function (axis) { return "%{" + axis + ":.2f} Hz" }
- }
-
- ret.type = document.getElementById("freq_ScaleLog").checked ? "log" : "linear"
-
- return ret
-}
-
-// Look through time array and return first index before start time
-function find_start_index(time) {
- const start_time = parseFloat(document.getElementById("TimeStart").value)
-
- var start_index = 0
- for (j = 0; j" + amplitude_scale.hover("y")
-
- for (let i = 0; i < Gyro_batch.length; i++) {
- if ((Gyro_batch[i] == null) || (Gyro_batch[i].FFT == null)) {
- continue
- }
-
- // Find the start and end index
- const start_index = find_start_index(Gyro_batch[i].FFT.time)
- const end_index = find_end_index(Gyro_batch[i].FFT.time)
-
- // Number of windows to plot
- const plot_length = end_index - start_index
-
- // Windowing amplitude correction depends on spectrum of interest
- const window_correction = amplitude_scale.use_PSD ? (Gyro_batch[i].FFT.correction.energy * math.sqrt(1/2)) : Gyro_batch[i].FFT.correction.linear
-
- // Take mean from start to end
- var fft_mean_x = 0
- var fft_mean_y = 0
- var fft_mean_z = 0
- for (let j=start_index;j" + "%{x:.2f} s
" + frequency_scale.hover("y") + "
" + amplitude_scale.hover("z")
- Spectrogram.data[0].colorbar.title.text = amplitude_scale.label
-
- // Find the start and end index
- const start_index = find_start_index(Gyro_batch[batch_instance].FFT.time)
- const end_index = find_end_index(Gyro_batch[batch_instance].FFT.time)
-
- // Number of windows to plot
- const plot_length = end_index - start_index
-
- // Setup xy data (x and y swapped because transpose flag is set)
- Spectrogram.data[0].x = Gyro_batch[batch_instance].FFT.time.slice(start_index, end_index)
- Spectrogram.data[0].y = frequency_scale.fun(Gyro_batch[batch_instance].FFT.bins)
-
- // Windowing amplitude correction depends on spectrum of interest
- const window_correction = amplitude_scale.use_PSD ? (Gyro_batch[batch_instance].FFT.correction.energy * math.sqrt(1/2)) : Gyro_batch[batch_instance].FFT.correction.linear
-
- // Setup z data
- Spectrogram.data[0].z = []
- for (j = 0; j" + frequency_scale.hover("y")
- for (let i=0;i 0
- for (const [key, value] of Object.entries(HNotch_params[i])) {
- if (key != "enable") {
- document.getElementById(value).disabled = !enable_input
- }
- }
- }
-
- // Load values into HNotch object
- for (let i = 0; i < HNotch_params.length; i++) {
- HNotch_setup[i] = []
- for (const [key, value] of Object.entries(HNotch_params[i])) {
- HNotch_setup[i][key] = parseFloat(document.getElementById(value).value)
- }
- }
-}
-
-var Gyro_batch
-var tracking_methods
-var HNotch_setup = []
-function load(log_file) {
-
- const start = performance.now()
-
- var log = new DataflashParser()
- log.processData(log_file)
-
- // Load batch messages
- log.parseAtOffset("ISBH")
- log.parseAtOffset("ISBD")
- if (log.messages.ISBH == null || log.messages.ISBD == null) {
- console.log("No Batch logging msg")
- return
- }
-
- // Assign batches to each sensor
- // Only interested in gyro here
- const IMU_SENSOR_TYPE_GYRO = 1
- Gyro_batch = []
- let data_index = 0
- for (let i = 0; i < log.messages.ISBH.N.length; i++) {
- // Parse headers
- if (log.messages.ISBH.type[i] != IMU_SENSOR_TYPE_GYRO) {
- continue
- }
-
- const instance = log.messages.ISBH.instance[i]
- if (Gyro_batch[instance] == null) {
- Gyro_batch[instance] = []
- }
-
- let decode_complete = false
-
- // Advance data index until sequence match
- const seq_num = log.messages.ISBH.N[i]
- while (log.messages.ISBD.N[data_index] != seq_num) {
- data_index++
- if (data_index >= log.messages.ISBD.N.length) {
- // This is expected at the end of a log, no more msgs to add, break here
- console.log("Could not find next sequence " + i + " of " + log.messages.ISBH.N.length-1)
- decode_complete = true
- break
- }
- }
- if (decode_complete) {
- break
- }
-
- let x = []
- let y = []
- let z = []
- const num_samples = log.messages.ISBH.smp_cnt[i]
- const num_data_msg = num_samples / 32
- for (let j = 0; j < num_data_msg; j++) {
- // Read in expected number of samples
- if ((log.messages.ISBD.N[data_index] != seq_num) || (log.messages.ISBD.seqno[data_index] != j)) {
- console.log("Missing or extra data msg")
- return
- }
-
- // Accumulate data for this batch
- x.push(...log.messages.ISBD.x[data_index])
- y.push(...log.messages.ISBD.y[data_index])
- z.push(...log.messages.ISBD.z[data_index])
-
- data_index++
- if (data_index >= log.messages.ISBD.N.length) {
- console.log("sequence incomplete " + i + " of " + log.messages.ISBH.N.length-1)
- decode_complete = true
- break
- }
- }
- if (decode_complete) {
- break
- }
-
- if ((x.length != num_samples) || (y.length != num_samples) || (z.length != num_samples)) {
- console.log("sample length wrong")
- return
- }
-
- // Remove logging scale factor
- const mul = 1/log.messages.ISBH.mul[i]
- x = math.dotMultiply(x, mul)
- y = math.dotMultiply(y, mul)
- z = math.dotMultiply(z, mul)
-
- // Add to batches for this instance
- Gyro_batch[instance].push({ sample_time: log.messages.ISBH.SampleUS[i] / 1000000,
- sample_rate: log.messages.ISBH.smp_rate[i],
- x: x,
- y: y,
- z: z })
- }
-
- if (Gyro_batch.length == 0) {
- console.log("no data")
- return
- }
-
- log.parseAtOffset('PARM')
-
- // Try and decode device IDs
- var num_gyro = 0
- for (let i = 0; i < 3; i++) {
- const ID_param = i == 0 ? "INS_GYR_ID" : "INS_GYR" + (i + 1) + "_ID"
- const ID = get_param_value(log.messages.PARM, ID_param)
- if ((ID != null) && (ID > 0)) {
- const decoded = decode_devid(ID, DEVICE_TYPE_IMU)
- if (decoded != null) {
- document.getElementById("Gyro" + i + "_info").innerHTML = decoded.name + " via " + decoded.bus_type
- }
- num_gyro++
- }
- }
-
- // Work out if logging is pre/post from param value
- const INS_LOG_BAT_OPT = get_param_value(log.messages.PARM, "INS_LOG_BAT_OPT")
- const _doing_sensor_rate_logging = (INS_LOG_BAT_OPT & (1 << 0)) != 0
- const _doing_post_filter_logging = (INS_LOG_BAT_OPT & (1 << 1)) != 0
- const _doing_pre_post_filter_logging = (INS_LOG_BAT_OPT & (1 << 2)) != 0
- const use_instance_offset = _doing_pre_post_filter_logging || (_doing_post_filter_logging && _doing_sensor_rate_logging)
- for (let i = 0; i < Gyro_batch.length; i++) {
- if (Gyro_batch[i] == null) {
- continue
- }
- if (use_instance_offset && (i >= num_gyro)) {
- Gyro_batch[i].sensor_num = i - num_gyro
- Gyro_batch[i].post_filter = true
- } else {
- Gyro_batch[i].sensor_num = i
- Gyro_batch[i].post_filter = _doing_post_filter_logging && !_doing_pre_post_filter_logging
- }
- }
-
- // setup/reset plot and options
- reset()
-
-
- // Load potential sources of notch tracking targets
- tracking_methods = [new StaticTarget(),
- new ThrottleTarget(log),
- new RPMTarget(log, 1, 2),
- new ESCTarget(log),
- new FFTTarget(log),
- new RPMTarget(log, 2, 5)]
-
- // Read from log into HTML box
- const HNotch_params = get_HNotch_param_names()
- for (let i = 0; i < HNotch_params.length; i++) {
- for (const param of Object.values(HNotch_params[i])) {
- const value = get_param_value(log.messages.PARM, param)
- if (value != null) {
- document.getElementById(param).value = value
- }
- }
- // Allow enable values to be changed
- document.getElementById(HNotch_params[i].enable).disabled = false
- }
-
- // Load notch params
- HNotch_param_read()
-
- // Update ranges of start and end time
- var start_time
- var end_time
- for (let i = 0; i < Gyro_batch.length; i++) {
- if (Gyro_batch[i] == null) {
- continue
- }
-
- const batch_start = Gyro_batch[i][0].sample_time
- if ((start_time == null) || (batch_start < start_time)) {
- start_time = batch_start
- }
-
- const batch_end = Gyro_batch[i][Gyro_batch[i].length - 1].sample_time
- if ((end_time == null) || (batch_end > end_time)) {
- end_time = batch_end
- }
- }
- start_time = math.floor(start_time)
- end_time = math.ceil(end_time)
-
- var start_input = document.getElementById("TimeStart")
- start_input.disabled = false;
- start_input.min = start_time
- start_input.value = start_time
- start_input.max = end_time
-
- var end_input = document.getElementById("TimeEnd")
- end_input.disabled = false;
- end_input.min = start_time
- end_input.value = end_time
- end_input.max = end_time
-
- // Enable checkboxes for sensors which are present
- var first_gyro
- var have_pre = false
- for (let i = 0; i < Gyro_batch.length; i++) {
- if (Gyro_batch[i] == null) {
- continue
- }
- const prepost = Gyro_batch[i].post_filter ? "Post" : "Pre"
- let axis = ["X" , "Y", "Z"]
- for (let j = 0; j < 3; j++) {
- var fft_check = document.getElementById("Gyro" + Gyro_batch[i].sensor_num + prepost + axis[j])
- fft_check.disabled = false
- fft_check.checked = true
- }
-
- // Track which sensors are present for spectrogram
- if (first_gyro == null || (Gyro_batch[i].sensor_num < first_gyro)) {
- first_gyro = Gyro_batch[i].sensor_num
- }
- if (Gyro_batch[i].post_filter == false) {
- document.getElementById("SpecGyroPre").disabled = false
- have_pre = true
- } else {
- document.getElementById("SpecGyroPost").disabled = false
- }
- document.getElementById("SpecGyroInst" + Gyro_batch[i].sensor_num).disabled = false
- document.getElementById("SpecGyroAxisX").checked = true
- document.getElementById("SpecGyroAxisY").disabled = false
- document.getElementById("SpecGyroAxisZ").disabled = false
- }
-
- // Default spectrograph to first sensor, pre if available and X axis
- document.getElementById("SpecGyroInst" + first_gyro).checked = true
- document.getElementById("SpecGyro" + (have_pre ? "Pre" : "Post")).checked = true
- document.getElementById("SpecGyroAxisX").disabled = false
-
- // Calculate FFT
- calculate()
-
- // Plot
- redraw()
-
- // Enable the calculate button
- document.getElementById("calculate").disabled = false
-
- // Set FFT info
- var set_batch_len_msg = false
- for (let i = 0; i < 3; i++) {
- let sample_rate = 0
- let window_size = 0
- let count = 0
- for (let j = 0; j < Gyro_batch.length; j++) {
- if ((Gyro_batch[j] == null) || Gyro_batch[j].sensor_num != i) {
- continue
- }
- sample_rate += Gyro_batch[j].FFT.average_sample_rate
- window_size += Gyro_batch[j].FFT.window_size
- count++
- }
- if (count == 0) {
- continue
- }
- sample_rate /= count
- window_size /= count
-
- document.getElementById("Gyro" + i + "_FFT_info").innerHTML = "Logging rate : " + (sample_rate).toFixed(2) + " Hz
" +
- "Frequency resolution : " + (sample_rate/window_size).toFixed(2) + " Hz"
-
- if (set_batch_len_msg == false) {
- set_batch_len_msg = true
- document.getElementById("FFTWindowInfo").innerHTML = "Window size: " + window_size
- }
- }
-
-
- const end = performance.now();
- console.log(`Load took: ${end - start} ms`);
-}
diff --git a/Tools/autotest/web-firmware/Tools/FilterReview/Readme.md b/Tools/autotest/web-firmware/Tools/FilterReview/Readme.md
deleted file mode 100644
index 041bdd838a..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterReview/Readme.md
+++ /dev/null
@@ -1,6 +0,0 @@
-Test with `python -m http.server --bind 127.0.0.1`
-
-Uses log parser from https://github.com/Williangalvani/JsDataflashParser
-
-WIP!
-
diff --git a/Tools/autotest/web-firmware/Tools/FilterReview/index.html b/Tools/autotest/web-firmware/Tools/FilterReview/index.html
deleted file mode 100644
index 7dc0101805..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterReview/index.html
+++ /dev/null
@@ -1,354 +0,0 @@
-
-
-
-
-ArduPilot Filter Review Tool
-
-
-
-
-
-
-
-
-ArduPilot Filter Review Tool
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/Tools/autotest/web-firmware/Tools/FilterReview/parser.js b/Tools/autotest/web-firmware/Tools/FilterReview/parser.js
deleted file mode 100644
index 439ca5c8a7..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterReview/parser.js
+++ /dev/null
@@ -1,882 +0,0 @@
-const MAV_TYPE_GENERIC = 0 // Generic micro air vehicle.
-const MAV_TYPE_FIXED_WING = 1 // Fixed wing aircraft.
-const MAV_TYPE_QUADROTOR = 2 // Quadrotor
-const MAV_TYPE_COAXIAL = 3 // Coaxial helicopter
-const MAV_TYPE_HELICOPTER = 4 // Normal helicopter with tail rotor.
-const MAV_TYPE_ANTENNA_TRACKER = 5 // Ground installation
-const MAV_TYPE_GCS = 6 // Operator control unit / ground control station
-const MAV_TYPE_AIRSHIP = 7 // Airship, controlled
-const MAV_TYPE_FREE_BALLOON = 8 // Free balloon, uncontrolled
-const MAV_TYPE_ROCKET = 9 // Rocket
-const MAV_TYPE_GROUND_ROVER = 10 // Ground rover
-const MAV_TYPE_SURFACE_BOAT = 11 // Surface vessel, boat, ship
-const MAV_TYPE_SUBMARINE = 12 // Submarine
-const MAV_TYPE_HEXAROTOR = 13 // Hexarotor
-const MAV_TYPE_OCTOROTOR = 14 // Octorotor
-const MAV_TYPE_TRICOPTER = 15 // Tricopter
-const MAV_TYPE_FLAPPING_WING = 16 // Flapping wing
-const MAV_TYPE_KITE = 17 // Kite
-const MAV_TYPE_ONBOARD_CONTROLLER = 18 // Onboard companion controller
-const MAV_TYPE_VTOL_DUOROTOR = 19 // Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
-const MAV_TYPE_VTOL_QUADROTOR = 20 // Quad-rotor VTOL using a V-shaped quad config in vertical operation.
-// Tailsitter.
-const MAV_TYPE_VTOL_TILTROTOR = 21 // Tiltrotor VTOL
-const MAV_TYPE_VTOL_RESERVED2 = 22 // VTOL reserved 2
-const MAV_TYPE_VTOL_RESERVED3 = 23 // VTOL reserved 3
-const MAV_TYPE_VTOL_RESERVED4 = 24 // VTOL reserved 4
-const MAV_TYPE_VTOL_RESERVED5 = 25 // VTOL reserved 5
-const MAV_TYPE_GIMBAL = 26 // Onboard gimbal
-const MAV_TYPE_ADSB = 27 // Onboard ADSB peripheral
-const MAV_TYPE_PARAFOIL = 28 // Steerable, nonrigid airfoil
-const MAV_TYPE_DODECAROTOR = 29 // Dodecarotor
-const MAV_TYPE_CAMERA = 30 // Camera
-const MAV_TYPE_CHARGING_STATION = 31 // Charging station
-const MAV_TYPE_FLARM = 32 // Onboard FLARM collision avoidance system
-const MAV_TYPE_ENUM_END = 33 //
-
-
-const modeMappingApm = {
- 0: 'MANUAL',
- 1: 'CIRCLE',
- 2: 'STABILIZE',
- 3: 'TRAINING',
- 4: 'ACRO',
- 5: 'FBWA',
- 6: 'FBWB',
- 7: 'CRUISE',
- 8: 'AUTOTUNE',
- 10: 'AUTO',
- 11: 'RTL',
- 12: 'LOITER',
- 13: 'TAKEOFF',
- 14: 'AVOID_ADSB',
- 15: 'GUIDED',
- 16: 'INITIALISING',
- 17: 'QSTABILIZE',
- 18: 'QHOVER',
- 19: 'QLOITER',
- 20: 'QLAND',
- 21: 'QRTL',
- 22: 'QAUTOTUNE',
- 23: 'QACRO',
- 24: 'THERMAL'
-}
-const modeMappingAcm = {
- 0: 'STABILIZE',
- 1: 'ACRO',
- 2: 'ALT_HOLD',
- 3: 'AUTO',
- 4: 'GUIDED',
- 5: 'LOITER',
- 6: 'RTL',
- 7: 'CIRCLE',
- 9: 'LAND',
- 11: 'DRIFT',
- 13: 'SPORT',
- 14: 'FLIP',
- 15: 'AUTOTUNE',
- 16: 'POSHOLD',
- 17: 'BRAKE',
- 18: 'THROW',
- 19: 'AVOID_ADSB',
- 20: 'GUIDED_NOGPS',
- 21: 'SMART_RTL',
- 22: 'FLOWHOLD',
- 23: 'FOLLOW',
- 24: 'ZIGZAG',
- 25: 'SYSTEMID',
- 26: 'AUTOROTATE'
-}
-const modeMappingRover = {
- 0: 'MANUAL',
- 1: 'ACRO',
- 3: 'STEERING',
- 4: 'HOLD',
- 5: 'LOITER',
- 6: 'FOLLOW',
- 7: 'SIMPLE',
- 10: 'AUTO',
- 11: 'RTL',
- 12: 'SMART_RTL',
- 15: 'GUIDED',
- 16: 'INITIALISING'
-}
-const modeMappingTracker = {
- 0: 'MANUAL',
- 1: 'STOP',
- 2: 'SCAN',
- 3: 'SERVO_TEST',
- 10: 'AUTO',
- 16: 'INITIALISING'
-}
-const modeMappingSub = {
- 0: 'STABILIZE',
- 1: 'ACRO',
- 2: 'ALT_HOLD',
- 3: 'AUTO',
- 4: 'GUIDED',
- 7: 'CIRCLE',
- 9: 'SURFACE',
- 16: 'POSHOLD',
- 19: 'MANUAL',
- 20: 'MOTOR_DETECT'
-}
-
-
-const multipliers = {
- '-': 0, // no multiplier e.g. a string
- '?': 1, // multipliers which haven't been worked out yet....
- //
- '2': 1e2,
- '1': 1e1,
- '0': 1e0,
- 'A': 1e-1,
- 'B': 1e-2,
- 'C': 1e-3,
- 'D': 1e-4,
- 'E': 1e-5,
- 'F': 1e-6,
- 'G': 1e-7,
- //
- '!': 3.6, // (ampere*second => milliampere*hour) and (km/h => m/s)
- '/': 3600 // (ampere*second => ampere*hour)
-}
-
-const multipliersTable = {
- 0.000001: 'n',
- 1000: 'M',
- 0.001: 'm'
-}
-
-const HEAD1 = 163
-const HEAD2 = 149
-
-const units = {
- '-': '', // no units e.g. Pi, or a string
- '?': 'UNKNOWN', // Units which haven't been worked out yet....
- 'A': 'A', // Ampere
- 'd': '°', // of the angular variety, -180 to 180
- 'b': 'B', // bytes
- 'k': '°/s', // degrees per second. Degrees are NOT SI, but is some situations more user-friendly than radians
- 'D': '°', // degrees of latitude
- 'e': '°/s/s', // degrees per second per second. Degrees are NOT SI, but is some situations more user-friendly
- 'E': 'rad/s', // radians per second
- 'G': 'Gauss', // Gauss is not an SI unit, but 1 tesla = 10000 gauss so a simple replacement is not possible here
- 'h': '°', // 0.? to 359.?
- 'i': 'A.s', // Ampere second
- 'J': 'W.s', // Joule (Watt second)
- // { 'l', "l" }, // litres
- 'L': 'rad/s/s', // radians per second per second
- 'm': 'm', // metres
- 'n': 'm/s', // metres per second
- // { 'N', "N" }, // Newton
- 'o': 'm/s/s', // metres per second per second
- 'O': '°C', // degrees Celsius. Not SI, but Kelvin is too cumbersome for most users
- '%': '%', // percent
- 'S': 'satellites', // number of satellites
- 's': 's', // seconds
- 'q': 'rpm', // rounds per minute. Not SI, but sometimes more intuitive than Hertz
- 'r': 'rad', // radians
- 'U': '°', // degrees of longitude
- 'u': 'ppm', // pulses per minute
- 'v': 'V', // Volt
- 'P': 'Pa', // Pascal
- 'w': 'Ohm', // Ohm
- 'Y': 'us', // pulse width modulation in microseconds
- 'z': 'Hz', // Hertz
- '#': 'instance' // instance number for message
-}
-
-function getModeMap (mavType) {
- let map
- if ([MAV_TYPE_QUADROTOR,
- MAV_TYPE_HELICOPTER,
- MAV_TYPE_HEXAROTOR,
- MAV_TYPE_OCTOROTOR,
- MAV_TYPE_COAXIAL,
- MAV_TYPE_TRICOPTER].includes(mavType)) {
- map = modeMappingAcm
- }
- if (mavType === MAV_TYPE_FIXED_WING) {
- map = modeMappingApm
- }
- if (mavType === MAV_TYPE_GROUND_ROVER) {
- map = modeMappingRover
- }
- if (mavType === MAV_TYPE_ANTENNA_TRACKER) {
- map = modeMappingTracker
- }
- if (mavType === MAV_TYPE_SUBMARINE) {
- map = modeMappingSub
- }
- if (map == null) {
- return null
- }
- return map
-}
-
-function assignColumn (obj) {
- var ArrayOfString = obj.split(',')
- return ArrayOfString
-}
-
-// Converts from degrees to radians.
-Math.radians = function (degrees) {
- return degrees * Math.PI / 180
-}
-
-// Converts from radians to degrees.
-Math.degrees = function (radians) {
- return radians * 180 / Math.PI
-}
-
-class DataflashParser {
- constructor () {
- this.time = null
- this.timebase = null
- this.buffer = null
- this.data = null
- this.FMT = []
- this.FMT[128] = {
- 'Type': '128',
- 'length': '89',
- 'Name': 'FMT',
- 'Format': 'BBnNZ',
- 'Columns': 'Type,Length,Name,Format,Columns'
- }
- this.offset = 0
- this.msgType = []
- this.offsetArray = []
- this.totalSize = null
- this.messages = {}
- this.lastPercentage = 0
- this.sent = false
- this.maxPercentageInterval = 0.05
- this.messageTypes = {}
- this.alreadyParsed = []
- }
-
- FORMAT_TO_STRUCT (obj) {
- var temp
- var dict = {
- name: obj.Name,
- fieldnames: obj.Columns.split(',')
- }
-
- let 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
- }
- 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
- }
-
- gpstimetoTime (week, msec) {
- let epoch = 86400 * (10 * 365 + (1980 - 1969) / 4 + 1 + 6 - 2)
- return epoch + 86400 * 7 * week + msec * 0.001 - 15
- }
-
- setTimeBase (base) {
- this.timebase = base
- }
-
- findTimeBase (gps) {
- const temp = this.gpstimetoTime(parseInt(gps['GWk']), parseInt(gps['GMS']))
- this.setTimeBase(parseInt(temp - gps['TimeUS'] * 0.000001))
- }
-
- getMsgType (element) {
- for (let i = 0; i < this.FMT.length; i++) {
- if (this.FMT[i] != null) {
- // eslint-disable-next-line
- if (this.FMT[i].Name == element) {
- return i
- }
- }
- }
- }
-
- onMessage (message) {
- if (this.totalSize == null) { // for percentage calculation
- this.totalSize = this.buffer.byteLength
- }
- if (message.name in this.messages) {
- this.messages[message.name].push(this.fixData(message))
- } else {
- this.messages[message.name] = [this.fixData(message)]
- }
- let percentage = 100 * this.offset / this.totalSize
- if ((percentage - this.lastPercentage) > this.maxPercentageInterval) {
- self.postMessage({percentage: percentage})
- this.lastPercentage = percentage
- }
- }
-
- messageHasInstances (name) {
- let type = this.FMT.find(msg => msg !== undefined && msg.Name === name)
- return type !== undefined && type.units !== undefined && type.units.includes('instance')
- }
-
- getInstancesFieldName (name) {
- let type = this.FMT.find(msg => msg !== undefined && msg.Name === name)
- if (type.units === undefined) {
- return null
- }
- return type.Columns.split(',')[type.units.indexOf('instance')]
- }
-
- // Next three functions are used for transfering data on postmessage, instead of cloning
- isTypedArray (arr) {
- return ArrayBuffer.isView(arr) && !(arr instanceof DataView)
- }
-
- getType (arr) {
- return this.isTypedArray(arr) && arr.constructor.name
- }
-
- postData (data) {
- data['dataType'] = {}
- const transferables = []
- for (let field of Object.keys(data.messageList)) {
- const arrayType = this.getType(data.messageList[field])
- if (arrayType) {
- transferables.push(data.messageList[field].buffer)
- }
- // Apparently it is magically decoded on the other end, no need for metadata
- // data['dataType'][field] = arrayType
- }
- self.postMessage(data, transferables)
- }
-
- parseAtOffset (name) {
- let type = this.getMsgType(name)
- var parsed = []
- for (var i = 0; i < this.msgType.length; i++) {
- if (type === this.msgType[i]) {
- this.offset = this.offsetArray[i]
- try {
- let temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]])
- if (temp['name'] != null) {
- parsed.push(this.fixData(temp))
- }
- } catch (e) {
- console.log('reached log end?')
- console.log(e)
- }
- }
- if (i % 100000 === 0) {
- let 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)) {
- let instanceField = this.getInstancesFieldName(name)
- let instances = {}
- for (let 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 (let [index, messages] of Object.entries(instances)) {
- let 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]})
- }
- this.alreadyParsed.push(name)
- return parsed
- }
-
- checkNumberOfInstances (name) {
- // Similar to parseOffset, but finishes earlier and updates messageTypes
- let type = this.getMsgType(name)
- let availableInstances = []
- let instanceField = this.getInstancesFieldName(name)
- if (instanceField === null) {
- return [1]
- }
- let repeats = 0
- for (var i = 0; i < this.msgType.length; i++) {
- if (type === this.msgType[i]) {
- this.offset = this.offsetArray[i]
- try {
- let temp = this.FORMAT_TO_STRUCT(this.FMT[this.msgType[i]])
- if (temp['name'] != null) {
- let msg = temp
- if (!msg.hasOwnProperty(instanceField)) {
- break
- }
- // we do an early return after we get 20 repeated instance numbers. should we?
- const instance = msg[instanceField]
- if (availableInstances.includes(instance)) {
- repeats += 1
- if (repeats > 20) {
- return availableInstances
- }
- } else {
- availableInstances.push(instance)
- }
- }
- } catch (e) {
- console.log(e)
- }
- }
- }
- return availableInstances
- }
-
- timestamp (TimeUs) {
- let temp = this.timebase + TimeUs * 0.000001
- if (temp > 0) {
- TimeUs = temp
- }
- let date = new Date(TimeUs * 1000)
- let hours = date.getHours()
- let minutes = '0' + date.getMinutes()
- let seconds = '0' + date.getSeconds()
- let formattedTime = hours + ':' + minutes.substr(-2) + ':' + seconds.substr(-2)
- date = date.toString()
- let time = date.split(' ')
- if (time[0] !== 'Invalid') {
- this.time = time[0] + ' ' + time[1] + ' ' + time[2] + ' ' + time[3]
- }
- return formattedTime
- }
-
- DfReader () {
- let lastOffset = 0
- while (this.offset < (this.buffer.byteLength - 3)) {
- if (this.data.getUint8(this.offset) !== HEAD1 || this.data.getUint8(this.offset + 1) !== HEAD2) {
- this.offset += 1
- continue
- }
- this.offset += 2
-
- let attribute = this.data.getUint8(this.offset)
- if (this.FMT[attribute] != null) {
- this.offset += 1
- this.offsetArray.push(this.offset)
- this.msgType.push(attribute)
- try {
- var value = this.FORMAT_TO_STRUCT(this.FMT[attribute])
- if (this.FMT[attribute].Name === 'GPS') {
- this.findTimeBase(value)
- }
- } catch (e) {
- // console.log('reached log end?')
- // console.log(e)
- this.offset += 1
- }
- if (attribute === 128) {
- this.FMT[value['Type']] = {
- 'Type': value['Type'],
- 'length': value['Length'],
- 'Name': value['Name'],
- 'Format': value['Format'],
- 'Columns': value['Columns']
- }
- }
- // this.onMessage(value)
- } else {
- this.offset += 1
- }
- if (this.offset - lastOffset > 50000) {
- let perc = 100 * this.offset / this.buffer.byteLength
- self.postMessage({percentage: perc})
- lastOffset = this.offset
- }
- }
- self.postMessage({percentage: 100})
- self.postMessage({messages: this.messages})
- this.sent = true
- }
-
- getModeString (cmode) {
- let mavtype
- let msgs = this.messages['MSG']
- for (let 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]
- }
- }
- console.log('defaulting to quadcopter')
- return getModeMap(MAV_TYPE_QUADROTOR)[cmode]
- }
-
- fixData (message) {
- if (message.name === 'MODE') {
- message.asText = this.getModeString(message['Mode'])
- }
- // eslint-disable-next-line
- message.time_boot_ms = message.TimeUS / 1000
- delete message.TimeUS
- delete message.fieldnames
- return message
- }
-
- fixDataOnce (name) {
- if (!['GPS', 'ATT', 'AHR2', 'MODE'].includes(name)) {
- if (this.messageTypes.hasOwnProperty(name)) {
- let fields = this.messages[name][0].fieldnames
- if (this.messageTypes[name].hasOwnProperty('multipliers')) {
- for (let message in this.messages[name]) {
- for (let i = 1; i < fields.length; i++) {
- let fieldname = fields[i]
- if (!isNaN(this.messageTypes[name].multipliers[i])) {
- this.messages[name][message][fieldname] *= this.messageTypes[name].multipliers[i]
- }
- }
- }
- }
- }
- }
- }
-
- concatTypedArrays (a, b) { // a, b TypedArray of same type
- var c = new (a.constructor)(a.length + b.length)
- c.set(a, 0)
- c.set(b, a.length)
- return c
- }
-
- createUint8ArrayFromString (str) {
- const array = new Uint8Array(str.length)
- for (let i = 0, strLen = str.length; i < strLen; i++) {
- array[i] = str.charCodeAt(i)
- }
- return array
- }
-
- processFiles () {
- this.files = {}
- for (let msg of this.messages['FILE']) {
- if (!this.files.hasOwnProperty(msg.FileName)) {
- this.files[msg.FileName] = this.createUint8ArrayFromString(msg.Data)
- } else {
- this.files[msg.FileName] = this.concatTypedArrays(
- this.files[msg.FileName], this.createUint8ArrayFromString(msg.Data)
- )
- }
- }
- self.postMessage({files: this.files})
- }
-
- simplifyData (name) {
- if (name === 'MODE') {
- this.messageTypes[name].expressions.push('asText')
- }
- if (name === 'FILE') {
- return
- }
- if (!['FMTU'].includes(name)) {
- if (this.messageTypes.hasOwnProperty(name)) {
- let fields = this.messageTypes[name].expressions
- if (!fields.includes('time_boot_ms')) {
- fields.push('time_boot_ms')
- }
- let mergedData = {}
- for (let field of fields) {
- mergedData[field] = []
- }
- for (let message of this.messages[name]) {
- for (let i = 1; i < fields.length; i++) {
- let fieldname = fields[i]
- mergedData[fieldname].push(message[fieldname])
- }
- }
- delete this.messages[name]
- this.messages[name] = mergedData
- for (const field of this.messageTypes[name].expressions) {
- if (this.messages[name][field] && !isNaN(this.messages[name][field][0])) {
- const newData = new Float64Array(this.messages[name][field])
- delete this.messages[name][field]
- this.messages[name][field] = newData
- }
- }
- }
- }
- }
-
- populateUnits () {
- // console.log(this.messages['FMTU'])
- for (let msg of this.messages['FMTU']) {
- this.FMT[msg.FmtType]['units'] = []
- for (let unit of msg.UnitIds) {
- this.FMT[msg.FmtType]['units'].push(units[unit])
- }
- this.FMT[msg.FmtType]['multipliers'] = []
- for (let mult of msg.MultIds) {
- this.FMT[msg.FmtType]['multipliers'].push(multipliers[mult])
- }
- }
- }
-
- extractStartTime () {
- let msgs = this.messages['GPS']
- for (let i in msgs.time_boot_ms) {
- if (msgs.GWk[i] > 1000) { // lousy validation
- let weeks = msgs.GWk[i]
- let ms = msgs.GMS[i]
- let d = new Date((315964800.0 + ((60 * 60 * 24 * 7) * weeks) + ms / 1000.0) * 1000.0)
- // adjusting for leap seconds
- d = new Date(d.getTime() - this.leapSecondsGPS(d.getUTCFullYear(), d.getUTCMonth() + 1) * 1000)
- return d
- }
- }
- }
-
- leapSecondsGPS (year, month) {
- return this.leapSecondsTAI(year, month) - 19
- }
-
- leapSecondsTAI (year, month) {
- const yyyymm = year * 100 + month
- if (yyyymm >= 201701) return 37
- if (yyyymm >= 201507) return 36
- if (yyyymm >= 201207) return 35
- if (yyyymm >= 200901) return 34
- if (yyyymm >= 200601) return 33
- if (yyyymm >= 199901) return 32
- if (yyyymm >= 199707) return 31
- if (yyyymm >= 199601) return 30
-
- return 0
- }
-
- processData (data) {
- this.buffer = data
- this.data = new DataView(this.buffer)
- this.DfReader()
- let messageTypes = {}
- this.parseAtOffset('FMTU')
- this.populateUnits()
- let typeSet = new Set(this.msgType)
- for (let msg of this.FMT) {
- if (msg) {
- if (typeSet.has(msg.Type)) {
- let fields = msg.Columns.split(',')
- // expressions = expressions.filter(e => e !== 'TimeUS')
- let complexFields = {}
- if (msg.hasOwnProperty('units')) {
- for (let field in fields) {
- complexFields[fields[field]] = {
- name: fields[field],
- units: (multipliersTable[msg.multipliers[field]] || '') + msg.units[field],
- multiplier: msg.multipliers[field]
- }
- }
- } else {
- for (let field in fields) {
- complexFields[fields[field]] = {
- name: fields[field],
- units: '?',
- multiplier: 1
- }
- }
- }
- let availableInstances = this.checkNumberOfInstances(msg.Name)
- if (availableInstances.length > 1) {
- for (let instance of availableInstances) {
- messageTypes[msg.Name + '[' + instance + ']'] = {
- expressions: fields,
- units: msg.units,
- multipiers: msg.multipliers,
- complexFields: complexFields
- }
- }
- } else {
- messageTypes[msg.Name] = {
- expressions: fields,
- units: msg.units,
- multipiers: msg.multipliers,
- complexFields: complexFields
- }
- }
- }
- }
- }
- self.postMessage({availableMessages: messageTypes})
- this.messageTypes = messageTypes
- this.parseAtOffset('CMD')
- this.parseAtOffset('MSG')
- this.parseAtOffset('FILE')
- this.processFiles()
- this.parseAtOffset('MODE')
- this.parseAtOffset('AHR2')
- this.parseAtOffset('ATT')
- this.parseAtOffset('GPS')
- this.parseAtOffset('POS')
- this.parseAtOffset('XKQ1')
- this.parseAtOffset('XKQ')
- this.parseAtOffset('NKQ1')
- this.parseAtOffset('NKQ2')
- this.parseAtOffset('XKQ2')
- this.parseAtOffset('PARM')
- this.parseAtOffset('MSG')
- this.parseAtOffset('STAT')
- this.parseAtOffset('EV')
- let 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')
- }
-}
-
-self.addEventListener('message', function (event) {
- if (event.data === null) {
- console.log('got bad file message!')
- } else if (event.data.action === 'parse') {
- parser = new DataflashParser()
- let 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)
- }
-})
diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js b/Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js
deleted file mode 100644
index 5d204aee15..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js
+++ /dev/null
@@ -1,171 +0,0 @@
-/*
-* FileSaver.js
-* A saveAs() FileSaver implementation.
-*
-* By Eli Grey, http://eligrey.com
-*
-* License : https://github.com/eligrey/FileSaver.js/blob/master/LICENSE.md (MIT)
-* source : http://purl.eligrey.com/github/FileSaver.js
-*/
-
-// The one and only way of getting global scope in all environments
-// https://stackoverflow.com/q/3277182/1008999
-var _global = typeof window === 'object' && window.window === window
- ? window : typeof self === 'object' && self.self === self
- ? self : typeof global === 'object' && global.global === global
- ? global
- : this
-
-function bom (blob, opts) {
- if (typeof opts === 'undefined') opts = { autoBom: false }
- else if (typeof opts !== 'object') {
- console.warn('Deprecated: Expected third argument to be a object')
- opts = { autoBom: !opts }
- }
-
- // prepend BOM for UTF-8 XML and text/* types (including HTML)
- // note: your browser will automatically convert UTF-16 U+FEFF to EF BB BF
- if (opts.autoBom && /^\s*(?:text\/\S*|application\/xml|\S*\/\S*\+xml)\s*;.*charset\s*=\s*utf-8/i.test(blob.type)) {
- return new Blob([String.fromCharCode(0xFEFF), blob], { type: blob.type })
- }
- return blob
-}
-
-function download (url, name, opts) {
- var xhr = new XMLHttpRequest()
- xhr.open('GET', url)
- xhr.responseType = 'blob'
- xhr.onload = function () {
- saveAs(xhr.response, name, opts)
- }
- xhr.onerror = function () {
- console.error('could not download file')
- }
- xhr.send()
-}
-
-function corsEnabled (url) {
- var xhr = new XMLHttpRequest()
- // use sync to avoid popup blocker
- xhr.open('HEAD', url, false)
- try {
- xhr.send()
- } catch (e) {}
- return xhr.status >= 200 && xhr.status <= 299
-}
-
-// `a.click()` doesn't work for all browsers (#465)
-function click (node) {
- try {
- node.dispatchEvent(new MouseEvent('click'))
- } catch (e) {
- var evt = document.createEvent('MouseEvents')
- evt.initMouseEvent('click', true, true, window, 0, 0, 0, 80,
- 20, false, false, false, false, 0, null)
- node.dispatchEvent(evt)
- }
-}
-
-// Detect WebView inside a native macOS app by ruling out all browsers
-// We just need to check for 'Safari' because all other browsers (besides Firefox) include that too
-// https://www.whatismybrowser.com/guides/the-latest-user-agent/macos
-var isMacOSWebView = _global.navigator && /Macintosh/.test(navigator.userAgent) && /AppleWebKit/.test(navigator.userAgent) && !/Safari/.test(navigator.userAgent)
-
-var saveAs = _global.saveAs || (
- // probably in some web worker
- (typeof window !== 'object' || window !== _global)
- ? function saveAs () { /* noop */ }
-
- // Use download attribute first if possible (#193 Lumia mobile) unless this is a macOS WebView
- : ('download' in HTMLAnchorElement.prototype && !isMacOSWebView)
- ? function saveAs (blob, name, opts) {
- var URL = _global.URL || _global.webkitURL
- var a = document.createElement('a')
- name = name || blob.name || 'download'
-
- a.download = name
- a.rel = 'noopener' // tabnabbing
-
- // TODO: detect chrome extensions & packaged apps
- // a.target = '_blank'
-
- if (typeof blob === 'string') {
- // Support regular links
- a.href = blob
- if (a.origin !== location.origin) {
- corsEnabled(a.href)
- ? download(blob, name, opts)
- : click(a, a.target = '_blank')
- } else {
- click(a)
- }
- } else {
- // Support blobs
- a.href = URL.createObjectURL(blob)
- setTimeout(function () { URL.revokeObjectURL(a.href) }, 4E4) // 40s
- setTimeout(function () { click(a) }, 0)
- }
- }
-
- // Use msSaveOrOpenBlob as a second approach
- : 'msSaveOrOpenBlob' in navigator
- ? function saveAs (blob, name, opts) {
- name = name || blob.name || 'download'
-
- if (typeof blob === 'string') {
- if (corsEnabled(blob)) {
- download(blob, name, opts)
- } else {
- var a = document.createElement('a')
- a.href = blob
- a.target = '_blank'
- setTimeout(function () { click(a) })
- }
- } else {
- navigator.msSaveOrOpenBlob(bom(blob, opts), name)
- }
- }
-
- // Fallback to using FileReader and a popup
- : function saveAs (blob, name, opts, popup) {
- // Open a popup immediately do go around popup blocker
- // Mostly only available on user interaction and the fileReader is async so...
- popup = popup || open('', '_blank')
- if (popup) {
- popup.document.title =
- popup.document.body.innerText = 'downloading...'
- }
-
- if (typeof blob === 'string') return download(blob, name, opts)
-
- var force = blob.type === 'application/octet-stream'
- var isSafari = /constructor/i.test(_global.HTMLElement) || _global.safari
- var isChromeIOS = /CriOS\/[\d]+/.test(navigator.userAgent)
-
- if ((isChromeIOS || (force && isSafari) || isMacOSWebView) && typeof FileReader !== 'undefined') {
- // Safari doesn't allow downloading of blob URLs
- var reader = new FileReader()
- reader.onloadend = function () {
- var url = reader.result
- url = isChromeIOS ? url : url.replace(/^data:[^;]*;/, 'data:attachment/file;')
- if (popup) popup.location.href = url
- else location = url
- popup = null // reverse-tabnabbing #460
- }
- reader.readAsDataURL(blob)
- } else {
- var URL = _global.URL || _global.webkitURL
- var url = URL.createObjectURL(blob)
- if (popup) popup.location = url
- else location.href = url
- popup = null // reverse-tabnabbing #460
- setTimeout(function () { URL.revokeObjectURL(url) }, 4E4) // 40s
- }
- }
-)
-
-_global.saveAs = saveAs.saveAs = saveAs
-
-if (typeof module !== 'undefined') {
- module.exports = saveAs;
-}
diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/app.py b/Tools/autotest/web-firmware/Tools/FilterTool/app.py
deleted file mode 100644
index 76ded1b765..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterTool/app.py
+++ /dev/null
@@ -1,16 +0,0 @@
-import os
-from flask import Flask
-from flask import render_template
-
-# A flask app to allow hosting filter tool locally
-
-this_path = os.path.dirname(os.path.realpath(__file__))
-
-app = Flask(__name__, template_folder=this_path, static_folder=this_path)
-
-@app.route('/')
-def index():
- return render_template('index.html')
-
-if __name__ == "__main__":
- app.run()
diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/filters.js b/Tools/autotest/web-firmware/Tools/FilterTool/filters.js
deleted file mode 100644
index b68bc3b673..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterTool/filters.js
+++ /dev/null
@@ -1,1196 +0,0 @@
-function calc_lowpass_alpha_dt(dt, cutoff_freq)
-{
- if (dt <= 0.0 || cutoff_freq <= 0.0) {
- return 1.0;
- }
- var rc = 1.0/(Math.PI*2*cutoff_freq);
- return dt/(dt+rc);
-}
-
-function PID(sample_rate,kP,kI,kD,filtE,filtD) {
-
- this._kP = kP;
- this._kI = kI;
- this._kD = kD;
-
- this._dt = 1.0/sample_rate;
- this.E_alpha = calc_lowpass_alpha_dt(this._dt,filtE)
- this.D_alpha = calc_lowpass_alpha_dt(this._dt,filtD)
-
- this._error = 0.0;
- this._derivative = 0.0;
- this._integrator = 0.0;
-
- this.reset = function(sample) {
- this._error = 0.0;
- this._derivative = 0.0;
- this._integrator = 0.0;
- }
-
- this.apply = function(error) {
-
- var error_last = this._error;
- this._error += this.E_alpha * (error - this._error);
-
- var derivative = (this._error - error_last) / this._dt;
- this._derivative += this.D_alpha * (derivative - this._derivative)
-
- this._integrator += this._error * this._kI * this._dt;
-
- var P_out = this._error * this._kP;
- var D_out = this._derivative * this._kD;
-
- return P_out + this._integrator + D_out;
- }
- return this;
-}
-
-function LPF_1P(sample_rate,cutoff) {
- this.reset = function(sample) {
- this.value = sample;
- }
- if (cutoff <= 0) {
- this.apply = function(sample) {
- return sample;
- }
- return this;
- }
- this.alpha = calc_lowpass_alpha_dt(1.0/sample_rate,cutoff)
- this.value = 0.0;
- this.apply = function(sample) {
- this.value += this.alpha * (sample - this.value);
- return this.value;
- }
- return this;
-}
-
-function DigitalBiquadFilter(sample_freq, cutoff_freq) {
- this.delay_element_1 = 0;
- this.delay_element_2 = 0;
- this.cutoff_freq = cutoff_freq;
-
- if (cutoff_freq <= 0) {
- // zero cutoff means pass-thru
- this.reset = function(sample) {
- }
- this.apply = function(sample) {
- return sample;
- }
- return this;
- }
-
- var fr = sample_freq/cutoff_freq;
- var ohm = Math.tan(Math.PI/fr);
- var c = 1.0+2.0*Math.cos(Math.PI/4.0)*ohm + ohm*ohm;
-
- this.b0 = ohm*ohm/c;
- this.b1 = 2.0*this.b0;
- this.b2 = this.b0;
- this.a1 = 2.0*(ohm*ohm-1.0)/c;
- this.a2 = (1.0-2.0*Math.cos(Math.PI/4.0)*ohm+ohm*ohm)/c;
- this.initialised = false;
-
- this.apply = function(sample) {
- if (!this.initialised) {
- this.reset(sample);
- this.initialised = true;
- }
- var delay_element_0 = sample - this.delay_element_1 * this.a1 - this.delay_element_2 * this.a2;
- var output = delay_element_0 * this.b0 + this.delay_element_1 * this.b1 + this.delay_element_2 * this.b2;
-
- this.delay_element_2 = this.delay_element_1;
- this.delay_element_1 = delay_element_0;
- return output;
- }
-
- this.reset = function(sample) {
- this.delay_element_1 = this.delay_element_2 = sample * (1.0 / (1 + this.a1 + this.a2));
- }
-
- return this;
-}
-
-function sq(v) {
- return v*v;
-}
-
-function constrain_float(v,vmin,vmax) {
- if (v < vmin) {
- return vmin;
- }
- if (v > vmax) {
- return vmax;
- }
- return v;
-}
-
-function NotchFilter(sample_freq,center_freq_hz,bandwidth_hz,attenuation_dB) {
- this.sample_freq = sample_freq;
- this.center_freq_hz = center_freq_hz;
- this.bandwidth_hz = bandwidth_hz;
- this.attenuation_dB = attenuation_dB;
- this.need_reset = true;
- this.initialised = false;
-
- this.calculate_A_and_Q = function() {
- this.A = Math.pow(10.0, -this.attenuation_dB / 40.0);
- if (this.center_freq_hz > 0.5 * this.bandwidth_hz) {
- var octaves = Math.log2(this.center_freq_hz / (this.center_freq_hz - this.bandwidth_hz / 2.0)) * 2.0;
- this.Q = Math.sqrt(Math.pow(2.0, octaves)) / (Math.pow(2.0, octaves) - 1.0);
- } else {
- this.Q = 0.0;
- }
- }
-
- this.init_with_A_and_Q = function() {
- if ((this.center_freq_hz > 0.0) && (this.center_freq_hz < 0.5 * this.sample_freq) && (this.Q > 0.0)) {
- var omega = 2.0 * Math.PI * this.center_freq_hz / this.sample_freq;
- var alpha = Math.sin(omega) / (2 * this.Q);
- this.b0 = 1.0 + alpha*sq(this.A);
- this.b1 = -2.0 * Math.cos(omega);
- this.b2 = 1.0 - alpha*sq(this.A);
- this.a0_inv = 1.0/(1.0 + alpha);
- this.a1 = this.b1;
- this.a2 = 1.0 - alpha;
- this.initialised = true;
- } else {
- this.initialised = false;
- }
- }
-
- // check center frequency is in the allowable range
- if ((center_freq_hz > 0.5 * bandwidth_hz) && (center_freq_hz < 0.5 * sample_freq)) {
- this.calculate_A_and_Q();
- this.init_with_A_and_Q();
- } else {
- this.initialised = false;
- }
-
- this.apply = function(sample) {
- if (!this.initialised || this.need_reset) {
- // if we have not been initialised when return the input
- // sample as output and update delayed samples
- this.signal1 = sample;
- this.signal2 = sample;
- this.ntchsig = sample;
- this.ntchsig1 = sample;
- this.ntchsig2 = sample;
- this.need_reset = false;
- return sample;
- }
- this.ntchsig2 = this.ntchsig1;
- this.ntchsig1 = this.ntchsig;
- this.ntchsig = sample;
- var output = (this.ntchsig*this.b0 + this.ntchsig1*this.b1 + this.ntchsig2*this.b2 - this.signal1*this.a1 - this.signal2*this.a2) * this.a0_inv;
- this.signal2 = this.signal1;
- this.signal1 = output;
- return output;
- }
-
- this.reset = function(sample) {
- this.need_reset = true;
- this.apply(sample);
- }
-
- return this;
-}
-
-function HarmonicNotchFilter(sample_freq,enable,mode,freq,bw,att,ref,fm_rat,hmncs,opts) {
- this.notches = []
- var chained = 1;
- var dbl = false;
- var triple = false;
- var composite_notches = 1;
- if (opts & 1) {
- dbl = true;
- composite_notches = 2;
- } else if (opts & 16) {
- triple = true;
- composite_notches = 3;
- }
-
- this.reset = function(sample) {
- for (n in this.notches) {
- this.notches[n].reset(sample);
- }
- }
-
- if (enable <= 0) {
- this.apply = function(sample) {
- return sample;
- }
- return this;
- }
-
- if (mode == 0) {
- // fixed notch
- }
- if (mode == 1) {
- var motors_throttle = Math.max(0,get_form("Throttle"));
- var throttle_freq = freq * Math.max(fm_rat,Math.sqrt(motors_throttle / ref));
- freq = throttle_freq;
- }
- if (mode == 2) {
- var rpm = get_form("RPM1");
- freq = Math.max(rpm/60.0,freq) * ref;
- }
- if (mode == 5) {
- var rpm = get_form("RPM2");
- freq = Math.max(rpm/60.0,freq) * ref;
- }
- if (mode == 3) {
- if (opts & 2) {
- chained = get_form("NUM_MOTORS");
- }
- var rpm = get_form("ESC_RPM");
- freq = Math.max(rpm/60.0,freq) * ref;
- }
- for (var n=0;n<8;n++) {
- var fmul = n+1;
- if (hmncs & (1< 1) {
- var notch_center_double;
- // only enable the filter if its center frequency is below the nyquist frequency
- notch_center_double = notch_center * (1.0 - notch_spread);
- if (notch_center_double < nyquist_limit) {
- this.notches.push(new NotchFilter(sample_freq,notch_center_double,bandwidth_hz/composite_notches,att));
- }
- // only enable the filter if its center frequency is below the nyquist frequency
- notch_center_double = notch_center * (1.0 + notch_spread);
- if (notch_center_double < nyquist_limit) {
- this.notches.push(new NotchFilter(sample_freq,notch_center_double,bandwidth_hz/composite_notches,att));
- }
- }
- }
- }
- }
- this.apply = function(sample) {
- for (n in this.notches) {
- sample = this.notches[n].apply(sample);
- }
- return sample;
- }
-}
-
-function get_form(vname) {
- var v = parseFloat(document.getElementById(vname).value);
- setCookie(vname, v);
- return v;
-}
-
-function run_filters(filters,freq,sample_rate,samples,fast_filters = null,fast_sample_rate = null) {
-
- for (var j=0;j= best_fit_offset) {
- var index = i - best_fit_offset;
- X.data[index][0] = Math.sin(t * kt);
- X.data[index][1] = Math.cos(t * kt);
- y.data[index][0] = output;
- }
- }
-
- // Z = a*sin(t*kt + p) + O
- var ABO = ML.MatrixLib.solve(X, y);
-
- var amplitude = Math.sqrt(ABO.get(0,0)*ABO.get(0,0) + ABO.get(1,0)*ABO.get(1,0));
- var phase = Math.atan2(ABO.get(1,0),ABO.get(0,0)) * (-180.0 / Math.PI);
- // var DC_offset = ABO.get(2,0);
-
- return [amplitude,phase];
-}
-
-var chart_attenuation;
-var chart_phase;
-var freq_log_scale;
-
-function get_filters(sample_rate) {
- var filters = []
- filters.push(new HarmonicNotchFilter(sample_rate,
- get_form("INS_HNTCH_ENABLE"),
- get_form("INS_HNTCH_MODE"),
- get_form("INS_HNTCH_FREQ"),
- get_form("INS_HNTCH_BW"),
- get_form("INS_HNTCH_ATT"),
- get_form("INS_HNTCH_REF"),
- get_form("INS_HNTCH_FM_RAT"),
- get_form("INS_HNTCH_HMNCS"),
- get_form("INS_HNTCH_OPTS")));
- filters.push(new HarmonicNotchFilter(sample_rate,
- get_form("INS_HNTC2_ENABLE"),
- get_form("INS_HNTC2_MODE"),
- get_form("INS_HNTC2_FREQ"),
- get_form("INS_HNTC2_BW"),
- get_form("INS_HNTC2_ATT"),
- get_form("INS_HNTC2_REF"),
- get_form("INS_HNTC2_FM_RAT"),
- get_form("INS_HNTC2_HMNCS"),
- get_form("INS_HNTC2_OPTS")));
- filters.push(new DigitalBiquadFilter(sample_rate,get_form("INS_GYRO_FILTER")));
-
- return filters;
-}
-
-function calculate_filter() {
- var sample_rate = get_form("GyroSampleRate");
- var freq_max = get_form("MaxFreq");
- var samples = 1000;
- var freq_step = 0.1;
- var filters = get_filters(sample_rate);
-
- var use_dB = document.getElementById("ScaleLog").checked;
- setCookie("Scale", use_dB ? "Log" : "Linear");
- var use_RPM = document.getElementById("freq_Scale_RPM").checked;
- setCookie("feq_unit", use_RPM ? "RPM" : "Hz");
- var unwrap_pahse = document.getElementById("ScaleUnWrap").checked;
- setCookie("PhaseScale", unwrap_pahse ? "unwrap" : "wrap");
- var attenuation = []
- var phase_lag = []
- var min_phase_lag = 0.0;
- var max_phase_lag = 0.0;
- var phase_wrap = 0.0;
- var min_atten = 0.0;
- var max_atten = 1.0;
- var last_phase = 0.0;
- var atten_string = "Magnitude";
- if (use_dB) {
- max_atten = 0;
- min_atten = -10;
- atten_string = "Magnitude (dB)";
- }
- var freq_string = "Frequency (Hz)";
- if (use_RPM) {
- freq_string = "Frequency (RPM)";
- }
-
- // start at zero
- attenuation.push({x:0, y:1});
- phase_lag.push({x:0, y:0});
-
- for (freq=freq_step; freq<=freq_max; freq+=freq_step) {
- var v = run_filters(filters, freq, sample_rate, samples);
- var aten = v[0];
- var phase = v[1] + phase_wrap;
- if (use_dB) {
- // show power in decibels
- aten = 20 * Math.log10(aten);
- }
- var freq_value = freq;
- if (use_RPM) {
- freq_value *= 60;
- }
- if (unwrap_pahse) {
- var phase_diff = phase - last_phase;
- if (phase_diff > 180) {
- phase_wrap -= 360.0;
- phase -= 360.0;
- } else if (phase_diff < -180) {
- phase_wrap += 360.0;
- phase += 360.0;
- }
- }
- attenuation.push({x:freq_value, y:aten});
- phase_lag.push({x:freq_value, y:-phase});
-
- min_atten = Math.min(min_atten, aten);
- max_atten = Math.max(max_atten, aten);
- min_phase_lag = Math.min(min_phase_lag, phase)
- max_phase_lag = Math.max(max_phase_lag, phase)
- last_phase = phase;
- }
-
- if (unwrap_pahse) {
- min_phase_lag = Math.floor((min_phase_lag-10)/10)*10;
- min_phase_lag = Math.min(Math.max(-get_form("MaxPhaseLag"), min_phase_lag), 0);
- max_phase_lag = Math.ceil((max_phase_lag+10)/10)*10;
- max_phase_lag = Math.min(get_form("MaxPhaseLag"), max_phase_lag);
- } else {
- min_phase_lag = -180;
- max_phase_lag = 180;
- }
-
- if (use_RPM) {
- freq_max *= 60.0;
- }
-
- var freq_log = document.getElementById("freq_ScaleLog").checked;
- setCookie("feq_scale", freq_log ? "Log" : "Linear");
- if ((freq_log_scale != null) && (freq_log_scale != freq_log)) {
- // Scale changed, no easy way to update, delete chart and re-draw
- chart_attenuation.clear();
- chart_attenuation.destroy();
- chart_attenuation = null;
- chart_phase.clear();
- chart_phase.destroy();
- chart_phase = null;
- }
- freq_log_scale = freq_log;
-
- if (chart_attenuation) {
- chart_attenuation.data.datasets[0].data = attenuation;
- chart_attenuation.options.scales.xAxes[0].ticks.max = freq_max;
- chart_attenuation.options.scales.xAxes[0].scaleLabel.labelString = freq_string
- chart_attenuation.options.scales.yAxes[0].ticks.min = min_atten
- chart_attenuation.options.scales.yAxes[0].ticks.max = max_atten;
- chart_attenuation.options.scales.yAxes[0].scaleLabel.labelString = atten_string;
- chart_attenuation.update();
- } else {
- chart_attenuation = new Chart("Attenuation", {
- type : "scatter",
- data: {
- datasets: [
- {
- label: 'Magnitude',
- yAxisID: 'Magnitude',
- pointRadius: 0,
- hitRadius: 8,
- borderColor: "rgba(0,0,255,1.0)",
- pointBackgroundColor: "rgba(0,0,255,1.0)",
- data: attenuation,
- showLine: true,
- fill: false
- },
- ]
- },
- options: {
- aspectRatio: 3,
- legend: {display: false},
- scales: {
- yAxes: [
- {
- scaleLabel: { display: true, labelString: atten_string },
- id: 'Magnitude',
- ticks: {min:min_atten, max:max_atten}
- },
- ],
- xAxes: [
- {
- type: (freq_log ? "logarithmic" : "linear"),
- scaleLabel: { display: true, labelString: freq_string },
- ticks:
- {
- min:0.0,
- max:freq_max,
- callback: function(value, index, ticks) {
- return value;
- },
- }
- }
- ],
- },
- tooltips: {
- callbacks: {
- label: function(tooltipItem, data) {
- // round tooltip to two decimal places
- return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2);
- }
- }
- }
- }
- });
- }
-
-
- if (chart_phase) {
- chart_phase.data.datasets[0].data = phase_lag;
- chart_phase.options.scales.xAxes[0].ticks.max = freq_max;
- chart_phase.options.scales.xAxes[0].scaleLabel.labelString = freq_string
- chart_phase.options.scales.yAxes[0].ticks.min = -max_phase_lag;
- chart_phase.options.scales.yAxes[0].ticks.max = -min_phase_lag;
- chart_phase.update();
- } else {
- chart_phase = new Chart("Phase", {
- type : "scatter",
- data: {
- datasets: [
- {
- label: 'Phase',
- yAxisID: 'Phase',
- pointRadius: 0,
- hitRadius: 8,
- borderColor: "rgba(255,0,0,1.0)",
- pointBackgroundColor: "rgba(255,0,0,1.0)",
- data: phase_lag,
- showLine: true,
- fill: false
- }
- ]
- },
- options: {
- aspectRatio: 3,
- legend: {display: false},
- scales: {
- yAxes: [
- {
- scaleLabel: { display: true, labelString: "Phase (deg)" },
- id: 'Phase',
- ticks: {min:-max_phase_lag, max:-min_phase_lag}
- }
- ],
- xAxes: [
- {
- type: (freq_log ? "logarithmic" : "linear"),
- scaleLabel: { display: true, labelString: freq_string },
- ticks:
- {
- min:0.0,
- max:freq_max,
- callback: function(value, index, ticks) {
- return value;
- },
- }
- }
- ],
- },
- tooltips: {
- callbacks: {
- label: function(tooltipItem, data) {
- // round tooltip to two decimal places
- return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2);
- }
- }
- }
- }
- });
- }
-}
-
-var PID_attenuation;
-var PID_phase;
-var PID_freq_log_scale;
-
-function calculate_pid(axis_id) {
- //var sample_rate = get_form("GyroSampleRate");
- var PID_rate = get_form("SCHED_LOOP_RATE")
- var filters = []
- var freq_max = get_form("PID_MaxFreq");
- var samples = 1000;
- var freq_step = 0.1;
-
- // default to roll axis
- var axis_prefix = "ATC_RAT_RLL_";
- if (axis_id == "CalculatePitch") {
- var axis_prefix = "ATC_RAT_PIT_";
- document.getElementById("PID_title").innerHTML = "Pitch axis";
- } else if (axis_id == "CalculateYaw") {
- var axis_prefix = "ATC_RAT_YAW_";
- document.getElementById("PID_title").innerHTML = "Yaw axis";
- } else {
- document.getElementById("PID_title").innerHTML = "Roll axis";
- }
-
- filters.push(new PID(PID_rate,
- get_form(axis_prefix + "P"),
- get_form(axis_prefix + "I"),
- get_form(axis_prefix + "D"),
- get_form(axis_prefix + "FLTE"),
- get_form(axis_prefix + "FLTD")));
-
- var use_dB = document.getElementById("PID_ScaleLog").checked;
- setCookie("PID_Scale", use_dB ? "Log" : "Linear");
- var use_RPM = document.getElementById("PID_freq_Scale_RPM").checked;
- setCookie("PID_feq_unit", use_RPM ? "RPM" : "Hz");
- var unwrap_pahse = document.getElementById("PID_ScaleUnWrap").checked;
- setCookie("PID_PhaseScale", unwrap_pahse ? "unwrap" : "wrap");
- var attenuation = []
- var phase_lag = []
- var min_phase_lag = 0.0;
- var max_phase_lag = 0.0;
- var phase_wrap = 0.0;
- var min_atten = Infinity;
- var max_atten = -Infinity;
- var last_phase = 0.0;
- var atten_string = "Gain";
- if (use_dB) {
- max_atten = 0;
- min_atten = -10;
- atten_string = "Gain (dB)";
- }
- var freq_string = "Frequency (Hz)";
- if (use_RPM) {
- freq_string = "Frequency (RPM)";
- }
-
- var fast_filters = null;
- var fast_sample_rate = null;
- if (document.getElementById("PID_filtering_Post").checked) {
- fast_sample_rate = get_form("GyroSampleRate");
- fast_filters = get_filters(fast_sample_rate);
- }
- setCookie("filtering", fast_filters == null ? "Pre" : "Post");
-
-
- for (freq=freq_step; freq<=freq_max; freq+=freq_step) {
- var v = run_filters(filters, freq, PID_rate, samples, fast_filters, fast_sample_rate);
- var aten = v[0];
- var phase = v[1] + phase_wrap;
- if (use_dB) {
- // show power in decibels
- aten = 20 * Math.log10(aten);
- }
- var freq_value = freq;
- if (use_RPM) {
- freq_value *= 60;
- }
- if (unwrap_pahse) {
- var phase_diff = phase - last_phase;
- if (phase_diff > 180) {
- phase_wrap -= 360.0;
- phase -= 360.0;
- } else if (phase_diff < -180) {
- phase_wrap += 360.0;
- phase += 360.0;
- }
- }
- attenuation.push({x:freq_value, y:aten});
- phase_lag.push({x:freq_value, y:-phase});
-
- min_atten = Math.min(min_atten, aten);
- max_atten = Math.max(max_atten, aten);
- min_phase_lag = Math.min(min_phase_lag, phase)
- max_phase_lag = Math.max(max_phase_lag, phase)
- last_phase = phase;
- }
-
- if (use_RPM) {
- freq_max *= 60.0;
- }
-
- var mean_atten = (min_atten + max_atten) * 0.5;
- var atten_range = Math.max((max_atten - min_atten) * 0.5 * 1.1, 1.0);
- min_atten = mean_atten - atten_range;
- max_atten = mean_atten + atten_range;
-
- if (unwrap_pahse) {
- min_phase_lag = Math.floor((min_phase_lag-10)/10)*10;
- min_phase_lag = Math.min(Math.max(-get_form("PID_MaxPhaseLag"), min_phase_lag), 0);
- max_phase_lag = Math.ceil((max_phase_lag+10)/10)*10;
- max_phase_lag = Math.min(get_form("PID_MaxPhaseLag"), max_phase_lag);
- } else {
- min_phase_lag = -180;
- max_phase_lag = 180;
- }
-
- var freq_log = document.getElementById("PID_freq_ScaleLog").checked;
- setCookie("PID_feq_scale", use_dB ? "Log" : "Linear");
- if ((PID_freq_log_scale != null) && (PID_freq_log_scale != freq_log)) {
- // Scale changed, no easy way to update, delete chart and re-draw
- PID_attenuation.clear();
- PID_attenuation.destroy();
- PID_attenuation = null;
- PID_phase.clear();
- PID_phase.destroy();
- PID_phase = null;
- }
- PID_freq_log_scale = freq_log;
-
- if (PID_attenuation) {
- PID_attenuation.data.datasets[0].data = attenuation;
- PID_attenuation.options.scales.xAxes[0].ticks.max = freq_max;
- PID_attenuation.options.scales.xAxes[0].scaleLabel.labelString = freq_string
- PID_attenuation.options.scales.yAxes[0].ticks.min = min_atten
- PID_attenuation.options.scales.yAxes[0].ticks.max = max_atten;
- PID_attenuation.options.scales.yAxes[0].scaleLabel.labelString = atten_string;
- PID_attenuation.update();
- } else {
- PID_attenuation = new Chart("PID_Attenuation", {
- type : "scatter",
- data: {
- datasets: [
- {
- label: 'Gain',
- yAxisID: 'Gain',
- pointRadius: 0,
- hitRadius: 8,
- borderColor: "rgba(0,0,255,1.0)",
- pointBackgroundColor: "rgba(0,0,255,1.0)",
- data: attenuation,
- showLine: true,
- fill: false
- },
- ]
- },
- options: {
- aspectRatio: 3,
- legend: {display: false},
- scales: {
- yAxes: [
- {
- scaleLabel: { display: true, labelString: atten_string },
- id: 'Gain',
- position: 'left',
- ticks: {min:min_atten, max:max_atten}
- },
- ],
- xAxes: [
- {
- type: (freq_log ? "logarithmic" : "linear"),
- scaleLabel: { display: true, labelString: freq_string },
- ticks:
- {
- min:0.0,
- max:freq_max,
- callback: function(value, index, ticks) {
- return value;
- },
- }
- }
- ],
- },
- tooltips: {
- callbacks: {
- label: function(tooltipItem, data) {
- // round tooltip to two decimal places
- return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2);
- }
- }
- }
- }
- });
- }
-
-
- if (PID_phase) {
- PID_phase.data.datasets[0].data = phase_lag;
- PID_phase.options.scales.xAxes[0].ticks.max = freq_max;
- PID_phase.options.scales.xAxes[0].scaleLabel.labelString = freq_string
- PID_phase.options.scales.yAxes[0].ticks.min = -max_phase_lag;
- PID_phase.options.scales.yAxes[0].ticks.max = -min_phase_lag;
- PID_phase.update();
- } else {
- PID_phase = new Chart("PID_Phase", {
- type : "scatter",
- data: {
- datasets: [
- {
- label: 'PhaseLag',
- yAxisID: 'PhaseLag',
- pointRadius: 0,
- hitRadius: 8,
- borderColor: "rgba(255,0,0,1.0)",
- pointBackgroundColor: "rgba(255,0,0,1.0)",
- data: phase_lag,
- showLine: true,
- fill: false
- }
- ]
- },
- options: {
- aspectRatio: 3,
- legend: {display: false},
- scales: {
- yAxes: [
- {
- scaleLabel: { display: true, labelString: "Phase (deg)" },
- id: 'PhaseLag',
- ticks: {min:-max_phase_lag, max:-min_phase_lag}
- }
- ],
- xAxes: [
- {
- type: (freq_log ? "logarithmic" : "linear"),
- scaleLabel: { display: true, labelString: freq_string },
- ticks:
- {
- min:0.0,
- max:freq_max,
- callback: function(value, index, ticks) {
- return value;
- },
- }
- }
- ],
- },
- tooltips: {
- callbacks: {
- label: function(tooltipItem, data) {
- // round tooltip to two decimal places
- return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2);
- }
- }
- }
- }
- });
- }
-}
-
-function load() {
- var url_string = (window.location.href).toLowerCase();
- if (url_string.indexOf('?') == -1) {
- // no query params, load from cookies
- load_cookies();
- return;
- }
-
- // populate from query's
- var params = new URL(url_string).searchParams;
- var sections = ["params", "PID_params"];
- for (var j = 0; j -1 ? cookie.substr(0, eqPos) : cookie;
- document.cookie = name + "=;expires=Thu, 01 Jan 1970 00:00:00 GMT";
- }
-}
-
-function save_parameters() {
- var params = "";
- var inputs = document.forms["params"].getElementsByTagName("input");
- for (const v in inputs) {
- var name = "" + inputs[v].name;
- if (name.startsWith("INS_")) {
- var value = inputs[v].value;
- params += name + "," + value + "\n";
- }
- }
- var blob = new Blob([params], { type: "text/plain;charset=utf-8" });
- saveAs(blob, "filter.param");
-}
-
-async function load_parameters(file) {
- var text = await file.text();
- var lines = text.split('\n');
- for (i in lines) {
- var line = lines[i];
- line = line.replace("Q_A_RAT_","ATC_RAT_");
- v = line.split(/[\s,=\t]+/);
- if (v.length >= 2) {
- var vname = v[0];
- var value = v[1];
- var fvar = document.getElementById(vname);
- if (fvar) {
- fvar.value = value;
- console.log("set " + vname + "=" + value);
- }
- }
- }
- fill_docs();
- update_all_hidden();
- calculate_filter();
-}
-
-function fill_docs()
-{
- var inputs = document.forms["params"].getElementsByTagName("input");
- for (const v in inputs) {
- var name = inputs[v].name;
- var doc = document.getElementById(name + ".doc");
- if (!doc) {
- continue;
- }
- if (inputs[v].onchange == null) {
- inputs[v].onchange = fill_docs;
- }
- var value = parseFloat(inputs[v].value);
- if (name.endsWith("_ENABLE")) {
- if (value >= 1) {
- doc.innerHTML = "Enabled";
- } else {
- doc.innerHTML = "Disabled";
- }
- } else if (name.endsWith("_MODE")) {
- switch (Math.floor(value)) {
- case 0:
- doc.innerHTML = "Fixed notch";
- break;
- case 1:
- doc.innerHTML = "Throttle";
- break;
- case 2:
- doc.innerHTML = "RPM Sensor 1";
- break;
- case 3:
- doc.innerHTML = "ESC Telemetry";
- break;
- case 4:
- doc.innerHTML = "Dynamic FFT";
- break;
- case 5:
- doc.innerHTML = "RPM Sensor 2";
- break;
- default:
- doc.innerHTML = "INVALID";
- break;
- }
- } else if (name.endsWith("_OPTS")) {
- var ival = Math.floor(value);
- var bits = [];
- if (ival & 1) {
- bits.push("Double Notch");
- }
- if (ival & 2) {
- bits.push("Dynamic Harmonic");
- }
- if (ival & 4) {
- bits.push("Loop Rate");
- }
- if (ival & 8) {
- bits.push("All IMUs Rate");
- }
- if ((ival & 16) && (ival & 1) == 0) {
- bits.push("Triple Notch");
- }
- doc.innerHTML = bits.join(", ");
- } else if (name.endsWith("_HMNCS")) {
- var ival = Math.floor(value);
- var bits = [];
- if (ival & 1) {
- bits.push("Fundamental");
- }
- if (ival & 2) {
- bits.push("1st Harmonic");
- }
- if (ival & 4) {
- bits.push("2nd Harmonic");
- }
- if (ival & 8) {
- bits.push("3rd Harmonic");
- }
- if (ival & 16) {
- bits.push("4th Harmonic");
- }
- if (ival & 32) {
- bits.push("5th Harmonic");
- }
- if (ival & 64) {
- bits.push("6th Harmonic");
- }
- doc.innerHTML = bits.join(", ");
- }
-
- }
-}
-
-// update all hidden params, to be called at init
-function update_all_hidden()
-{
- var enable_params = ["INS_HNTCH_ENABLE", "INS_HNTC2_ENABLE"];
- for (var i=-0;i 0;
- var prefix = enable_param.split("_ENABLE")[0];
-
- // find all elements with same prefix
- var inputs = document.forms["params"].getElementsByTagName("*");
- for (var i=-0;i 0)) {
- continue;
- }
-
- var mode = Math.floor(get_form(mode_params[j]))
- for (var k =0; k < mode_options[i][0].length; k++) {
- if (mode == mode_options[i][0][k]) {
- hide = false;
- }
- }
- }
- document.getElementById(mode_options[i][1]).hidden = hide;
- }
-}
-
-function check_nyquist()
-{
- var checks = [["GyroSampleRate", "MaxFreq", "MaxFreq_warning"],
- ["SCHED_LOOP_RATE", "PID_MaxFreq", "PID_MaxFreq_warning"]];
-
- for (var i = 0; i < checks.length; i++) {
- var freq_limit = get_form(checks[i][0]) * 0.5;
- var sample_rate = document.getElementById(checks[i][1]);
- if (parseFloat(sample_rate.value) > freq_limit) {
- sample_rate.value = freq_limit;
- document.getElementById(checks[i][2]).innerHTML = "Nyquist limit of half sample rate";
- } else {
- document.getElementById(checks[i][2]).innerHTML = "";
- }
- }
-}
diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/index.html b/Tools/autotest/web-firmware/Tools/FilterTool/index.html
deleted file mode 100644
index c092d1b8b9..0000000000
--- a/Tools/autotest/web-firmware/Tools/FilterTool/index.html
+++ /dev/null
@@ -1,378 +0,0 @@
-
-
-
-
-ArduPilot Filter Analysis
-
-
-
-
-
-
-
-
-ArduPilot Filter Analysis
-
-The following form will display the attenuation and phase lag for an
-ArduPilot 4.2 filter setup.
-
-
-
-
-
-
-
-
-
-
-
-
-PIDs
-
-
-
-
-
-
-
-
-
-
-
-
-
-