Tools: FilterTool: allow query string param config and add get link

This commit is contained in:
Iampete1 2022-07-28 19:00:43 +01:00 committed by Andrew Tridgell
parent ea3f5877c9
commit a209a391df
2 changed files with 64 additions and 1 deletions

View File

@ -760,6 +760,68 @@ function calculate_pid(axis_id) {
}
}
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<sections.length; j++) {
var items = document.forms[sections[j]].getElementsByTagName("input");
for (var i=-0;i<items.length;i++) {
var name = items[i].name.toLowerCase();
if (params.has(name)) {
if (items[i].type == "radio") {
// only checked buttons are included
if (items[i].value.toLowerCase() == params.get(name)) {
items[i].checked = true;
}
continue;
}
var value = parseFloat(params.get(name));
if (!isNaN(value)) {
items[i].value = value;
}
}
}
}
}
// build url and query string for current view and copy to clipboard
function get_link() {
if (!(navigator && navigator.clipboard && navigator.clipboard.writeText)) {
// copy not available
return
}
// get base url
var url = new URL((window.location.href).split('?')[0]);
// Add all query strings
var sections = ["params", "PID_params"];
for (var j = 0; j<sections.length; j++) {
var items = document.forms[sections[j]].getElementsByTagName("input");
for (var i=-0;i<items.length;i++) {
if (items[i].type == "radio" && !items[i].checked) {
// Only add checked radio buttons
continue;
}
url.searchParams.append(items[i].name, items[i].value);
}
}
// copy to clipboard
navigator.clipboard.writeText(url.toString());
}
function setCookie(c_name, value) {
var exdate = new Date();
var exdays = 365;

View File

@ -15,13 +15,14 @@
The following form will display the attenuation and phase lag for an
ArduPilot 4.2 filter setup.
<body onload="load_cookies(); fill_docs(); update_all_hidden(); calculate_filter(); calculate_pid(); ">
<body onload="load(); fill_docs(); update_all_hidden(); calculate_filter(); calculate_pid();">
<canvas id="Attenuation" style="width:100%;max-width:1200px"></canvas>
<p>
<input type="button" id="calculate" value="Calculate">
<input type="button" id="SaveParams" value="Save Parameters" onclick="save_parameters();">
<button class="styleClass" onclick="document.getElementById('param_file').click()">Load Parameters</button>
<input type='file' id="param_file" style="display:none" onchange="load_parameters(this.files[0]);">
<input type="button" id="GetLink" value="Get Link" onclick="get_link();">
<form id="params" action="">
<fieldset style="max-width:1200px">