mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-25 17:25:14 +03:00
dropped PID values scaling and some cleanup
This commit is contained in:
parent
3ab5336135
commit
c6e81d991f
3 changed files with 100 additions and 242 deletions
51
js/msp.js
51
js/msp.js
|
@ -407,31 +407,9 @@ var MSP = {
|
|||
case MSP_codes.MSP_PID:
|
||||
// PID data arrived, we need to scale it and save to appropriate bank / array
|
||||
for (var i = 0, needle = 0; i < (message_length / 3); i++, needle += 3) {
|
||||
// main for loop selecting the pid section
|
||||
switch (i) {
|
||||
case 0:
|
||||
case 1:
|
||||
case 2:
|
||||
case 3:
|
||||
case 7:
|
||||
case 8:
|
||||
case 9:
|
||||
PIDs[i][0] = data.getUint8(needle) / 10;
|
||||
PIDs[i][1] = data.getUint8(needle + 1) / 1000;
|
||||
PIDs[i][0] = data.getUint8(needle);
|
||||
PIDs[i][1] = data.getUint8(needle + 1);
|
||||
PIDs[i][2] = data.getUint8(needle + 2);
|
||||
break;
|
||||
case 4:
|
||||
PIDs[i][0] = data.getUint8(needle) / 100;
|
||||
PIDs[i][1] = data.getUint8(needle + 1) / 100;
|
||||
PIDs[i][2] = data.getUint8(needle + 2) / 1000;
|
||||
break;
|
||||
case 5:
|
||||
case 6:
|
||||
PIDs[i][0] = data.getUint8(needle) / 10;
|
||||
PIDs[i][1] = data.getUint8(needle + 1) / 100;
|
||||
PIDs[i][2] = data.getUint8(needle + 2) / 1000;
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
// Disabled, cleanflight does not use MSP_BOX.
|
||||
|
@ -1268,30 +1246,9 @@ MSP.crunch = function (code) {
|
|||
break;
|
||||
case MSP_codes.MSP_SET_PID:
|
||||
for (var i = 0; i < PIDs.length; i++) {
|
||||
switch (i) {
|
||||
case 0:
|
||||
case 1:
|
||||
case 2:
|
||||
case 3:
|
||||
case 7:
|
||||
case 8:
|
||||
case 9:
|
||||
buffer.push(Math.round(PIDs[i][0] * 10));
|
||||
buffer.push(Math.round(PIDs[i][1] * 1000));
|
||||
buffer.push(parseInt(PIDs[i][0]));
|
||||
buffer.push(parseInt(PIDs[i][1]));
|
||||
buffer.push(parseInt(PIDs[i][2]));
|
||||
break;
|
||||
case 4:
|
||||
buffer.push(Math.round(PIDs[i][0] * 100));
|
||||
buffer.push(Math.round(PIDs[i][1] * 100));
|
||||
buffer.push(parseInt(PIDs[i][2]));
|
||||
break;
|
||||
case 5:
|
||||
case 6:
|
||||
buffer.push(Math.round(PIDs[i][0] * 10));
|
||||
buffer.push(Math.round(PIDs[i][1] * 100));
|
||||
buffer.push(Math.round(PIDs[i][2] * 1000));
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SET_RC_TUNING:
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
<div class="gui_box grey">
|
||||
<table class="pid_titlebar">
|
||||
<tr>
|
||||
<th class="name" i18n="pidTuningName""></th>
|
||||
<th class="name" i18n="pidTuningName"></th>
|
||||
<th class="proportional" i18n="pidTuningProportional"></th>
|
||||
<th class="integral" i18n="pidTuningIntegral"></th>
|
||||
<th class="derivative" i18n="pidTuningDerivative"></th>
|
||||
|
@ -38,22 +38,22 @@
|
|||
<tr class="ROLL">
|
||||
<!-- 0 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
<tr class="PITCH">
|
||||
<!-- 1 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
<tr class="YAW">
|
||||
<!-- 2 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
</table>
|
||||
|
@ -66,15 +66,15 @@
|
|||
<tr class="ALT">
|
||||
<!-- 3 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
<tr class="Vario">
|
||||
<!-- 9 -->
|
||||
<td>VEL</td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
</table>
|
||||
|
@ -87,7 +87,7 @@
|
|||
<tr class="MAG">
|
||||
<!-- 8 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td></td>
|
||||
<td></td>
|
||||
</tr>
|
||||
|
@ -101,23 +101,23 @@
|
|||
<tr class="Pos">
|
||||
<!-- 4 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.01" min="0" max="2.55" /></td>
|
||||
<td><input type="number" name="i" step="0.01" min="0" max="2.55" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td></td>
|
||||
</tr>
|
||||
<tr class="PosR">
|
||||
<!-- 5 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.01" min="0" max="2.55" /></td>
|
||||
<td><input type="number" name="d" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
<tr class="NavR">
|
||||
<!-- 6 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.01" min="0" max="2.55" /></td>
|
||||
<td><input type="number" name="d" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div>
|
||||
|
@ -139,8 +139,8 @@
|
|||
<tr class="LEVEL">
|
||||
<!-- 7 -->
|
||||
<td></td>
|
||||
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
|
||||
<td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
|
||||
<td><input type="number" name="p" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||
</tr>
|
||||
</table>
|
||||
|
|
|
@ -32,136 +32,37 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names);
|
||||
|
||||
function pid_and_rc_to_form() {
|
||||
|
||||
var sectionClasses = [
|
||||
'ROLL', // 0
|
||||
'PITCH', // 1
|
||||
'YAW', // 2
|
||||
'ALT', // 3
|
||||
'Pos', // 4
|
||||
'PosR', // 5
|
||||
'NavR', // 6
|
||||
'LEVEL', // 7
|
||||
'MAG', // 8
|
||||
'Vario' // 9
|
||||
]
|
||||
|
||||
// Fill in the data from PIDs array
|
||||
var i = 0;
|
||||
$('.pid_tuning .ROLL input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[0][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[0][i++].toFixed(3));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[0][i++].toFixed(0));
|
||||
break;
|
||||
var i;
|
||||
/*
|
||||
* Iterate over registered sections/PID controllers
|
||||
*/
|
||||
for (var sectionId = 0; sectionId < sectionClasses.length; sectionId++) {
|
||||
|
||||
i = 0;
|
||||
/*
|
||||
* Now, iterate over inputs inside PID constroller section
|
||||
*/
|
||||
$('.pid_tuning .' + sectionClasses[sectionId] + ' input').each(function () {
|
||||
$(this).val(PIDs[sectionId][i].toFixed(0));
|
||||
i++;
|
||||
});
|
||||
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .PITCH input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[1][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[1][i++].toFixed(3));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[1][i++].toFixed(0));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .YAW input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[2][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[2][i++].toFixed(3));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[2][i++].toFixed(0));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .ALT input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[3][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[3][i++].toFixed(3));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[3][i++].toFixed(0));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .Pos input').each(function () {
|
||||
$(this).val(PIDs[4][i++].toFixed(2));
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .PosR input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[5][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[5][i++].toFixed(2));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[5][i++].toFixed(3));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .NavR input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[6][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[6][i++].toFixed(2));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[6][i++].toFixed(3));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .LEVEL input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[7][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[7][i++].toFixed(3));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[7][i++].toFixed(0));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .MAG input').each(function () {
|
||||
$(this).val(PIDs[8][i++].toFixed(1));
|
||||
});
|
||||
|
||||
i = 0;
|
||||
$('.pid_tuning .Vario input').each(function () {
|
||||
switch (i) {
|
||||
case 0:
|
||||
$(this).val(PIDs[9][i++].toFixed(1));
|
||||
break;
|
||||
case 1:
|
||||
$(this).val(PIDs[9][i++].toFixed(3));
|
||||
break;
|
||||
case 2:
|
||||
$(this).val(PIDs[9][i++].toFixed(0));
|
||||
break;
|
||||
}
|
||||
});
|
||||
|
||||
// Fill in data from RC_tuning object
|
||||
$('.rate-tpa input[name="roll-pitch"]').val(RC_tuning.roll_pitch_rate.toFixed(2));
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue