mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Tools: added log scale option to FilterTool
This commit is contained in:
parent
7b8da9385d
commit
a554ac3500
@ -320,13 +320,30 @@ function calculate_filter() {
|
||||
samples /= Math.max(1, freq_max/150.0);
|
||||
// console.log("samples: " + samples)
|
||||
|
||||
var scale = document.getElementById("ScaleLog");
|
||||
var use_dB = scale.checked;
|
||||
var attenuation = []
|
||||
var phase_lag = []
|
||||
var max_phase_lag = 0.0;
|
||||
var phase_wrap = 0.0;
|
||||
var min_atten = 0.0;
|
||||
var max_atten = 1.0;
|
||||
var atten_string = "Attenuation";
|
||||
if (use_dB) {
|
||||
max_atten = 0;
|
||||
min_atten = -10;
|
||||
atten_string = "Attenuation (dB)";
|
||||
}
|
||||
for (freq=1; freq<=freq_max; freq++) {
|
||||
var v = run_filters(filters, freq, sample_rate, samples);
|
||||
attenuation.push({x:freq, y:v[0]});
|
||||
var aten = v[0];
|
||||
if (use_dB) {
|
||||
// show power in decibels
|
||||
aten = 20 * Math.log10(aten);
|
||||
}
|
||||
min_atten = Math.min(min_atten, aten);
|
||||
max_atten = Math.max(max_atten, aten);
|
||||
attenuation.push({x:freq, y:aten});
|
||||
var phase = v[1] + phase_wrap;
|
||||
if (phase < max_phase_lag-100) {
|
||||
// we have wrapped
|
||||
@ -344,6 +361,9 @@ function calculate_filter() {
|
||||
chart.data.datasets[0].data = attenuation;
|
||||
chart.data.datasets[1].data = phase_lag;
|
||||
chart.options.scales.xAxes[0].ticks.max = freq_max;
|
||||
chart.options.scales.yAxes[0].ticks.min = min_atten
|
||||
chart.options.scales.yAxes[0].ticks.max = max_atten;
|
||||
chart.options.scales.yAxes[0].scaleLabel.labelString = atten_string;
|
||||
chart.options.scales.yAxes[1].ticks.min = -max_phase_lag;
|
||||
chart.options.scales.yAxes[1].ticks.max = 0;
|
||||
chart.update();
|
||||
@ -379,10 +399,10 @@ function calculate_filter() {
|
||||
scales: {
|
||||
yAxes: [
|
||||
{
|
||||
scaleLabel: { display: true, labelString: "Attenuation" },
|
||||
scaleLabel: { display: true, labelString: atten_string },
|
||||
id: 'Attenuation',
|
||||
position: 'left',
|
||||
ticks: {min:0, max:1.0, stepSize:0.1}
|
||||
ticks: {min:min_atten, max:max_atten, stepSize:0.1}
|
||||
},
|
||||
{
|
||||
scaleLabel: { display: true, labelString: "Phase Lag(deg)" },
|
||||
@ -479,7 +499,7 @@ async function load_parameters(file) {
|
||||
}
|
||||
}
|
||||
if (line.startsWith("ATC_RAT_RLL_FLTD") ||
|
||||
line.startsWith("Q_A_RAT_RLL_FLTD")) {
|
||||
line.startsWith("Q_A_RAT_RLL_FLTD")) {
|
||||
var fvar = document.getElementById("FLTD");
|
||||
if (fvar) {
|
||||
v = line.split(/[\s,=\t]+/);
|
||||
|
@ -22,11 +22,13 @@ ArduPilot 4.2 filter setup.
|
||||
|
||||
<form id="params" action="">
|
||||
<fieldset>
|
||||
<legend>INS Settings</legend>
|
||||
<legend>Graph Settings</legend>
|
||||
<p>
|
||||
<label for="GyroSampleRate">Gyro Sample Rate</label>
|
||||
<input id="GyroSampleRate" name="GYRO_SAMPLE_RATE" type="number" step="1" value="2000"/>
|
||||
</p>
|
||||
<input type="radio" id="ScaleLog" name="Scale" value="Log">
|
||||
<label for="LogScale">Log Scale</label><br>
|
||||
<input type="radio" id="ScaleLinear" name="Scale" value="Linear" checked>
|
||||
<label for="LinearScale">Linear Scale</label><br>
|
||||
</p>
|
||||
<p>
|
||||
<label for="MaxFreq">Maximum Displayed Frequency</label>
|
||||
<input id="MaxFreq" name="MaxFreq" type="number" step="1" value="150"/>
|
||||
@ -35,6 +37,13 @@ ArduPilot 4.2 filter setup.
|
||||
<label for="MaxPhaseLag">Maximum Displayed Phase Lag</label>
|
||||
<input id="MaxPhaseLag" name="MaxPhaseLag" type="number" step="1" value="360"/>
|
||||
</p>
|
||||
</fieldset>
|
||||
<fieldset>
|
||||
<legend>INS Settings</legend>
|
||||
<p>
|
||||
<label for="GyroSampleRate">Gyro Sample Rate</label>
|
||||
<input id="GyroSampleRate" name="GYRO_SAMPLE_RATE" type="number" step="1" value="2000"/>
|
||||
</p>
|
||||
<p>
|
||||
<label for="INS_GYRO_FILTER">INS_GYRO_FILTER</label>
|
||||
<input id="INS_GYRO_FILTER" name="INS_GYRO_FILTER" type="number" step="0.1" value="20.0"/>
|
||||
|
Loading…
Reference in New Issue
Block a user