diff --git a/js/msp.js b/js/msp.js old mode 100644 new mode 100755 index 86e0f105..22cea9f1 --- a/js/msp.js +++ b/js/msp.js @@ -378,20 +378,20 @@ var MSP = { 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; + PIDs[i][0] = data.getUint8(needle); + PIDs[i][1] = data.getUint8(needle + 1); + PIDs[i][2] = data.getUint8(needle + 2); 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; + PIDs[i][0] = data.getUint8(needle); + PIDs[i][1] = data.getUint8(needle + 1); + PIDs[i][2] = data.getUint8(needle + 2); break; } } @@ -1157,20 +1157,20 @@ MSP.crunch = function (code) { 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][0])); + buffer.push(parseInt(PIDs[i][1])); 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)); + buffer.push(parseInt(PIDs[i][0])); + buffer.push(parseInt(PIDs[i][1])); + buffer.push(parseInt(PIDs[i][2])); break; } } @@ -1706,4 +1706,3 @@ MSP.SDCARD_STATE_CARD_INIT = 2; MSP.SDCARD_STATE_FS_INIT = 3; MSP.SDCARD_STATE_READY = 4; - diff --git a/tabs/pid_tuning.html b/tabs/pid_tuning.html index a9a716dd..798e87b7 100755 --- a/tabs/pid_tuning.html +++ b/tabs/pid_tuning.html @@ -3,7 +3,7 @@
- +
@@ -44,22 +44,22 @@ - - + + - - + + - - + + @@ -72,15 +72,15 @@ - - + + VEL - - + + @@ -93,7 +93,7 @@ - + @@ -107,23 +107,24 @@ - - + + + - - - + + + - - - + + +
@@ -145,8 +146,8 @@ - - + + @@ -203,4 +204,4 @@
- + \ No newline at end of file diff --git a/tabs/pid_tuning.js b/tabs/pid_tuning.js index 74e14ab7..111cac3e 100755 --- a/tabs/pid_tuning.js +++ b/tabs/pid_tuning.js @@ -6,7 +6,6 @@ TABS.pid_tuning = { TABS.pid_tuning.initialize = function (callback) { var self = this; - if (GUI.active_tab != 'pid_tuning') { GUI.active_tab = 'pid_tuning'; } @@ -44,13 +43,13 @@ TABS.pid_tuning.initialize = function (callback) { $('.pid_tuning .ROLL input').each(function () { switch (i) { case 0: - $(this).val(PIDs[0][i++].toFixed(1)); + $(this).val(PIDs[0][i++]); break; case 1: - $(this).val(PIDs[0][i++].toFixed(3)); + $(this).val(PIDs[0][i++]); break; case 2: - $(this).val(PIDs[0][i++].toFixed(0)); + $(this).val(PIDs[0][i++]); break; } }); @@ -59,13 +58,13 @@ TABS.pid_tuning.initialize = function (callback) { $('.pid_tuning .PITCH input').each(function () { switch (i) { case 0: - $(this).val(PIDs[1][i++].toFixed(1)); + $(this).val(PIDs[1][i++]); break; case 1: - $(this).val(PIDs[1][i++].toFixed(3)); + $(this).val(PIDs[1][i++]); break; case 2: - $(this).val(PIDs[1][i++].toFixed(0)); + $(this).val(PIDs[1][i++]); break; } }); @@ -74,13 +73,13 @@ TABS.pid_tuning.initialize = function (callback) { $('.pid_tuning .YAW input').each(function () { switch (i) { case 0: - $(this).val(PIDs[2][i++].toFixed(1)); + $(this).val(PIDs[2][i++]); break; case 1: - $(this).val(PIDs[2][i++].toFixed(3)); + $(this).val(PIDs[2][i++]); break; case 2: - $(this).val(PIDs[2][i++].toFixed(0)); + $(this).val(PIDs[2][i++]); break; } }); @@ -89,33 +88,33 @@ TABS.pid_tuning.initialize = function (callback) { $('.pid_tuning .ALT input').each(function () { switch (i) { case 0: - $(this).val(PIDs[3][i++].toFixed(1)); + $(this).val(PIDs[3][i++]); break; case 1: - $(this).val(PIDs[3][i++].toFixed(3)); + $(this).val(PIDs[3][i++]); break; case 2: - $(this).val(PIDs[3][i++].toFixed(0)); + $(this).val(PIDs[3][i++]); break; } }); i = 0; $('.pid_tuning .Pos input').each(function () { - $(this).val(PIDs[4][i++].toFixed(2)); + $(this).val(PIDs[4][i++]); }); i = 0; $('.pid_tuning .PosR input').each(function () { switch (i) { case 0: - $(this).val(PIDs[5][i++].toFixed(1)); + $(this).val(PIDs[5][i++]); break; case 1: - $(this).val(PIDs[5][i++].toFixed(2)); + $(this).val(PIDs[5][i++]); break; case 2: - $(this).val(PIDs[5][i++].toFixed(3)); + $(this).val(PIDs[5][i++]); break; } }); @@ -124,13 +123,13 @@ TABS.pid_tuning.initialize = function (callback) { $('.pid_tuning .NavR input').each(function () { switch (i) { case 0: - $(this).val(PIDs[6][i++].toFixed(1)); + $(this).val(PIDs[6][i++]); break; case 1: - $(this).val(PIDs[6][i++].toFixed(2)); + $(this).val(PIDs[6][i++]); break; case 2: - $(this).val(PIDs[6][i++].toFixed(3)); + $(this).val(PIDs[6][i++]); break; } }); @@ -139,33 +138,33 @@ TABS.pid_tuning.initialize = function (callback) { $('.pid_tuning .LEVEL input').each(function () { switch (i) { case 0: - $(this).val(PIDs[7][i++].toFixed(1)); + $(this).val(PIDs[7][i++]); break; case 1: - $(this).val(PIDs[7][i++].toFixed(3)); + $(this).val(PIDs[7][i++]); break; case 2: - $(this).val(PIDs[7][i++].toFixed(0)); + $(this).val(PIDs[7][i++]); break; } }); i = 0; $('.pid_tuning .MAG input').each(function () { - $(this).val(PIDs[8][i++].toFixed(1)); + $(this).val(PIDs[8][i++]); }); i = 0; $('.pid_tuning .Vario input').each(function () { switch (i) { case 0: - $(this).val(PIDs[9][i++].toFixed(1)); + $(this).val(PIDs[9][i++]); break; case 1: - $(this).val(PIDs[9][i++].toFixed(3)); + $(this).val(PIDs[9][i++]); break; case 2: - $(this).val(PIDs[9][i++].toFixed(0)); + $(this).val(PIDs[9][i++]); break; } }); @@ -411,4 +410,4 @@ TABS.pid_tuning.cleanup = function (callback) { if (callback) { callback(); } -}; +}; \ No newline at end of file