Tools: FilterTool: add support for log scale frequency and RPM scale
This commit is contained in:
parent
e49607db54
commit
987ffbb00f
@ -424,9 +424,10 @@ function calculate_filter() {
|
||||
if (use_dB) {
|
||||
// show power in decibels
|
||||
aten = 20 * Math.log10(aten);
|
||||
} else {
|
||||
// attenuation is opposite of ratio
|
||||
aten = 1.0 - aten;
|
||||
}
|
||||
var freq_value = freq;
|
||||
if (use_RPM) {
|
||||
freq_value *= 60;
|
||||
}
|
||||
var phase_diff = phase - last_phase;
|
||||
if (phase_diff > 180) {
|
||||
@ -436,8 +437,8 @@ function calculate_filter() {
|
||||
phase_wrap += 360.0;
|
||||
phase += 360.0;
|
||||
}
|
||||
attenuation.push({x:freq, y:aten});
|
||||
phase_lag.push({x:freq, y:-phase});
|
||||
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);
|
||||
@ -449,14 +450,28 @@ function calculate_filter() {
|
||||
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);
|
||||
|
||||
if (use_RPM) {
|
||||
freq_max *= 60.0;
|
||||
}
|
||||
|
||||
var freq_log = document.getElementById("freq_ScaleLog").checked;
|
||||
if ((freq_log_scale != null) && (freq_log_scale != freq_log)) {
|
||||
// Scale changed, no easy way to update, delete chart and re-draw
|
||||
chart.clear();
|
||||
chart.destroy();
|
||||
chart = null;
|
||||
}
|
||||
freq_log_scale = freq_log;
|
||||
|
||||
if (chart) {
|
||||
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.xAxes[0].scaleLabel.labelString = freq_string
|
||||
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[0].ticks.reverse = !use_dB;
|
||||
chart.options.scales.yAxes[1].ticks.min = -max_phase_lag;
|
||||
chart.options.scales.yAxes[1].ticks.max = -min_phase_lag;
|
||||
chart.update();
|
||||
|
@ -25,12 +25,40 @@ ArduPilot 4.2 filter setup.
|
||||
<form id="params" action="">
|
||||
<fieldset style="max-width:1200px">
|
||||
<legend>Graph Settings</legend>
|
||||
<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>
|
||||
<table>
|
||||
<tr>
|
||||
<td>
|
||||
<fieldset style="width:150px">
|
||||
<legend>Magnitude scale</legend>
|
||||
<input type="radio" id="ScaleLog" name="Scale" value="Log" checked>
|
||||
<label for="LogScale">dB</label><br>
|
||||
<input type="radio" id="ScaleLinear" name="Scale" value="Linear">
|
||||
<label for="LinearScale">Linear</label><br>
|
||||
</fieldset>
|
||||
</td>
|
||||
<td>
|
||||
<fieldset style="width:150px">
|
||||
<legend>Frequency scale</legend>
|
||||
<table>
|
||||
<tr>
|
||||
<td>
|
||||
<input type="radio" id="freq_ScaleLog" name="feq_scale" value="Log" checked>
|
||||
<label for="LogScale">Log</label><br>
|
||||
<input type="radio" id="freq_ScaleLinear" name="feq_scale" value="Linear">
|
||||
<label for="LinearScale">Linear</label><br>
|
||||
</td>
|
||||
<td>
|
||||
<input type="radio" id="freq_Scale_Hz" name="feq_unit" value="Hz" checked>
|
||||
<label for="Scale_unit_Hz">Hz</label><br>
|
||||
<input type="radio" id="freq_Scale_RPM" name="feq_unit" value="RPM">
|
||||
<label for="Scale_unit_RPM">RPM</label><br>
|
||||
</td>
|
||||
</tr>
|
||||
</table>
|
||||
</fieldset>
|
||||
</td>
|
||||
</tr>
|
||||
</table>
|
||||
<p>
|
||||
<label for="MaxFreq">Maximum Displayed Frequency</label>
|
||||
<input id="MaxFreq" name="MaxFreq" type="number" step="1" value="150"/>
|
||||
|
Loading…
Reference in New Issue
Block a user