Tools: FilterTool: hide disabled params

This commit is contained in:
Iampete1 2022-07-30 13:34:04 +01:00 committed by Andrew Tridgell
parent b468c49a39
commit 6cac879bae
2 changed files with 42 additions and 4 deletions

View File

@ -581,7 +581,9 @@ function fill_docs()
if (!doc) {
continue;
}
inputs[v].onchange = fill_docs;
if (inputs[v].onchange == null) {
inputs[v].onchange = fill_docs;
}
var value = parseFloat(inputs[v].value);
if (name.endsWith("_ENABLE")) {
if (value >= 1) {
@ -661,3 +663,39 @@ function fill_docs()
}
}
// 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<enable_params.length;i++) {
update_hidden(enable_params[i])
}
}
// update hidden inputs based on param value
function update_hidden(enable_param)
{
var enabled = parseFloat(document.getElementById(enable_param).value) > 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<inputs.length;i++) {
var key = inputs[i].id;
if (key.length == 0) {
// no id, but bound to a valid one
if (inputs[i].htmlFor == null) {
continue;
}
key = inputs[i].htmlFor
}
if (key.startsWith(enable_param)) {
// found original param, don't change
continue;
}
if (key.startsWith(prefix)) {
inputs[i].hidden = !enabled;
}
}
}

View File

@ -14,7 +14,7 @@
The following form will display the attenuation and phase lag for an
ArduPilot 4.2 filter setup.
<body onload="load_cookies(); calculate_filter(); fill_docs();">
<body onload="load_cookies(); calculate_filter(); fill_docs(); update_all_hidden();">
<canvas id="Attenuation" style="width:100%;max-width:1200px"></canvas>
<p>
<input type="button" id="calculate" value="Calculate">
@ -91,7 +91,7 @@ ArduPilot 4.2 filter setup.
<legend>First Notch Filter</legend>
<p>
<label for="INS_HNTCH_ENABLE">INS_HNTCH_ENABLE</label>
<input id="INS_HNTCH_ENABLE" name="INS_HNTCH_ENABLE" type="number" step="1" value="0"/>
<input id="INS_HNTCH_ENABLE" name="INS_HNTCH_ENABLE" type="number" step="1" value="0" onchange="update_hidden(this.id); fill_docs();"/>
<label id="INS_HNTCH_ENABLE.doc"></label>
</p>
<p>
@ -134,7 +134,7 @@ ArduPilot 4.2 filter setup.
<legend>Second Notch Filter</legend>
<p>
<label for="INS_HNTC2_ENABLE">INS_HNTC2_ENABLE</label>
<input id="INS_HNTC2_ENABLE" name="INS_HNTC2_ENABLE" type="number" step="1" value="0"/>
<input id="INS_HNTC2_ENABLE" name="INS_HNTC2_ENABLE" type="number" step="1" value="0" onchange="update_hidden(this.id); fill_docs();"/>
<label id="INS_HNTC2_ENABLE.doc"></label>
</p>
<p>