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
143
js/msp.js
143
js/msp.js
|
@ -133,8 +133,8 @@ var MSP = {
|
||||||
|
|
||||||
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
|
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
|
||||||
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
|
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
|
||||||
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
|
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
|
||||||
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
|
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
|
||||||
|
|
||||||
last_received_timestamp: null,
|
last_received_timestamp: null,
|
||||||
analog_last_received_timestamp: null,
|
analog_last_received_timestamp: null,
|
||||||
|
@ -283,7 +283,7 @@ var MSP = {
|
||||||
$('span.cycle-time').text(CONFIG.cycleTime);
|
$('span.cycle-time').text(CONFIG.cycleTime);
|
||||||
$('span.cpu-load').text(chrome.i18n.getMessage('statusbar_cpu_load', [CONFIG.cpuload]));
|
$('span.cpu-load').text(chrome.i18n.getMessage('statusbar_cpu_load', [CONFIG.cpuload]));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_RAW_IMU:
|
case MSP_codes.MSP_RAW_IMU:
|
||||||
// 512 for mpu6050, 256 for mma
|
// 512 for mpu6050, 256 for mma
|
||||||
// currently we are unable to differentiate between the sensor types, so we are goign with 512
|
// currently we are unable to differentiate between the sensor types, so we are goign with 512
|
||||||
|
@ -407,31 +407,9 @@ var MSP = {
|
||||||
case MSP_codes.MSP_PID:
|
case MSP_codes.MSP_PID:
|
||||||
// PID data arrived, we need to scale it and save to appropriate bank / array
|
// 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) {
|
for (var i = 0, needle = 0; i < (message_length / 3); i++, needle += 3) {
|
||||||
// main for loop selecting the pid section
|
PIDs[i][0] = data.getUint8(needle);
|
||||||
switch (i) {
|
PIDs[i][1] = data.getUint8(needle + 1);
|
||||||
case 0:
|
PIDs[i][2] = data.getUint8(needle + 2);
|
||||||
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][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;
|
break;
|
||||||
// Disabled, cleanflight does not use MSP_BOX.
|
// Disabled, cleanflight does not use MSP_BOX.
|
||||||
|
@ -939,7 +917,7 @@ var MSP = {
|
||||||
} else {
|
} else {
|
||||||
var mask = data.getUint32(offset, 1);
|
var mask = data.getUint32(offset, 1);
|
||||||
offset +=4;
|
offset +=4;
|
||||||
|
|
||||||
var functionId = (mask >> 8) & 0xF;
|
var functionId = (mask >> 8) & 0xF;
|
||||||
var functions = [];
|
var functions = [];
|
||||||
for (var baseFunctionLetterIndex = 0; baseFunctionLetterIndex < MSP.ledBaseFunctionLetters.length; baseFunctionLetterIndex++) {
|
for (var baseFunctionLetterIndex = 0; baseFunctionLetterIndex < MSP.ledBaseFunctionLetters.length; baseFunctionLetterIndex++) {
|
||||||
|
@ -948,14 +926,14 @@ var MSP = {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
var overlayMask = (mask >> 12) & 0x3F;
|
var overlayMask = (mask >> 12) & 0x3F;
|
||||||
for (var overlayLetterIndex = 0; overlayLetterIndex < MSP.ledOverlayLetters.length; overlayLetterIndex++) {
|
for (var overlayLetterIndex = 0; overlayLetterIndex < MSP.ledOverlayLetters.length; overlayLetterIndex++) {
|
||||||
if (bit_check(overlayMask, overlayLetterIndex)) {
|
if (bit_check(overlayMask, overlayLetterIndex)) {
|
||||||
functions.push(MSP.ledOverlayLetters[overlayLetterIndex]);
|
functions.push(MSP.ledOverlayLetters[overlayLetterIndex]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
var directionMask = (mask >> 22) & 0x3F;
|
var directionMask = (mask >> 22) & 0x3F;
|
||||||
var directions = [];
|
var directions = [];
|
||||||
for (var directionLetterIndex = 0; directionLetterIndex < MSP.ledDirectionLetters.length; directionLetterIndex++) {
|
for (var directionLetterIndex = 0; directionLetterIndex < MSP.ledDirectionLetters.length; directionLetterIndex++) {
|
||||||
|
@ -971,7 +949,7 @@ var MSP = {
|
||||||
directions: directions,
|
directions: directions,
|
||||||
parameters: (mask >> 28) & 0xF
|
parameters: (mask >> 28) & 0xF
|
||||||
};
|
};
|
||||||
|
|
||||||
LED_STRIP.push(led);
|
LED_STRIP.push(led);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -980,11 +958,11 @@ var MSP = {
|
||||||
console.log('Led strip config saved');
|
console.log('Led strip config saved');
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_LED_COLORS:
|
case MSP_codes.MSP_LED_COLORS:
|
||||||
|
|
||||||
LED_COLORS = [];
|
LED_COLORS = [];
|
||||||
|
|
||||||
var colorCount = data.byteLength / 4;
|
var colorCount = data.byteLength / 4;
|
||||||
|
|
||||||
var offset = 0;
|
var offset = 0;
|
||||||
for (var i = 0; offset < data.byteLength && i < colorCount; i++) {
|
for (var i = 0; offset < data.byteLength && i < colorCount; i++) {
|
||||||
|
|
||||||
|
@ -998,10 +976,10 @@ var MSP = {
|
||||||
s: s,
|
s: s,
|
||||||
v: v
|
v: v
|
||||||
};
|
};
|
||||||
|
|
||||||
LED_COLORS.push(color);
|
LED_COLORS.push(color);
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_LED_COLORS:
|
case MSP_codes.MSP_SET_LED_COLORS:
|
||||||
console.log('Led strip colors saved');
|
console.log('Led strip colors saved');
|
||||||
|
@ -1010,9 +988,9 @@ var MSP = {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||||
|
|
||||||
LED_MODE_COLORS = [];
|
LED_MODE_COLORS = [];
|
||||||
|
|
||||||
var colorCount = data.byteLength / 3;
|
var colorCount = data.byteLength / 3;
|
||||||
|
|
||||||
var offset = 0;
|
var offset = 0;
|
||||||
for (var i = 0; offset < data.byteLength && i < colorCount; i++) {
|
for (var i = 0; offset < data.byteLength && i < colorCount; i++) {
|
||||||
|
|
||||||
|
@ -1025,7 +1003,7 @@ var MSP = {
|
||||||
direction: direction,
|
direction: direction,
|
||||||
color: color
|
color: color
|
||||||
};
|
};
|
||||||
|
|
||||||
LED_MODE_COLORS.push(mode_color);
|
LED_MODE_COLORS.push(mode_color);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1033,8 +1011,8 @@ var MSP = {
|
||||||
case MSP_codes.MSP_SET_LED_STRIP_MODECOLOR:
|
case MSP_codes.MSP_SET_LED_STRIP_MODECOLOR:
|
||||||
console.log('Led strip mode colors saved');
|
console.log('Led strip mode colors saved');
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
case MSP_codes.MSP_DATAFLASH_SUMMARY:
|
case MSP_codes.MSP_DATAFLASH_SUMMARY:
|
||||||
if (data.byteLength >= 13) {
|
if (data.byteLength >= 13) {
|
||||||
|
@ -1136,13 +1114,13 @@ var MSP = {
|
||||||
if (this.callbacks[i].code == code) {
|
if (this.callbacks[i].code == code) {
|
||||||
// save callback reference
|
// save callback reference
|
||||||
var callback = this.callbacks[i].callback;
|
var callback = this.callbacks[i].callback;
|
||||||
|
|
||||||
// remove timeout
|
// remove timeout
|
||||||
clearInterval(this.callbacks[i].timer);
|
clearInterval(this.callbacks[i].timer);
|
||||||
|
|
||||||
// remove object from array
|
// remove object from array
|
||||||
this.callbacks.splice(i, 1);
|
this.callbacks.splice(i, 1);
|
||||||
|
|
||||||
// fire callback
|
// fire callback
|
||||||
if (callback) callback({'command': code, 'data': data, 'length': message_length});
|
if (callback) callback({'command': code, 'data': data, 'length': message_length});
|
||||||
}
|
}
|
||||||
|
@ -1268,30 +1246,9 @@ MSP.crunch = function (code) {
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_PID:
|
case MSP_codes.MSP_SET_PID:
|
||||||
for (var i = 0; i < PIDs.length; i++) {
|
for (var i = 0; i < PIDs.length; i++) {
|
||||||
switch (i) {
|
buffer.push(parseInt(PIDs[i][0]));
|
||||||
case 0:
|
buffer.push(parseInt(PIDs[i][1]));
|
||||||
case 1:
|
buffer.push(parseInt(PIDs[i][2]));
|
||||||
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][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;
|
break;
|
||||||
case MSP_codes.MSP_SET_RC_TUNING:
|
case MSP_codes.MSP_SET_RC_TUNING:
|
||||||
|
@ -1730,7 +1687,7 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function send_next_led_strip_config() {
|
function send_next_led_strip_config() {
|
||||||
|
|
||||||
var led = LED_STRIP[ledIndex];
|
var led = LED_STRIP[ledIndex];
|
||||||
/*
|
/*
|
||||||
var led = {
|
var led = {
|
||||||
|
@ -1740,9 +1697,9 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
y: data.getUint8(offset++, 1),
|
y: data.getUint8(offset++, 1),
|
||||||
color: data.getUint8(offset++, 1)
|
color: data.getUint8(offset++, 1)
|
||||||
};
|
};
|
||||||
*/
|
*/
|
||||||
var buffer = [];
|
var buffer = [];
|
||||||
|
|
||||||
buffer.push(ledIndex);
|
buffer.push(ledIndex);
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||||
|
@ -1755,7 +1712,7 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
}
|
}
|
||||||
buffer.push(specificByte(directionMask, 0));
|
buffer.push(specificByte(directionMask, 0));
|
||||||
buffer.push(specificByte(directionMask, 1));
|
buffer.push(specificByte(directionMask, 1));
|
||||||
|
|
||||||
var functionMask = 0;
|
var functionMask = 0;
|
||||||
for (var functionLetterIndex = 0; functionLetterIndex < led.functions.length; functionLetterIndex++) {
|
for (var functionLetterIndex = 0; functionLetterIndex < led.functions.length; functionLetterIndex++) {
|
||||||
var bitIndex = MSP.ledFunctionLetters.indexOf(led.functions[functionLetterIndex]);
|
var bitIndex = MSP.ledFunctionLetters.indexOf(led.functions[functionLetterIndex]);
|
||||||
|
@ -1765,19 +1722,19 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
}
|
}
|
||||||
buffer.push(specificByte(functionMask, 0));
|
buffer.push(specificByte(functionMask, 0));
|
||||||
buffer.push(specificByte(functionMask, 1));
|
buffer.push(specificByte(functionMask, 1));
|
||||||
|
|
||||||
buffer.push(led.x);
|
buffer.push(led.x);
|
||||||
buffer.push(led.y);
|
buffer.push(led.y);
|
||||||
|
|
||||||
buffer.push(led.color);
|
buffer.push(led.color);
|
||||||
} else {
|
} else {
|
||||||
var mask = 0;
|
var mask = 0;
|
||||||
/*
|
/*
|
||||||
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
|
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
|
||||||
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
|
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
|
||||||
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
|
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
|
||||||
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
|
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
|
||||||
|
|
||||||
*/
|
*/
|
||||||
mask |= (led.y << 0);
|
mask |= (led.y << 0);
|
||||||
mask |= (led.x << 4);
|
mask |= (led.x << 4);
|
||||||
|
@ -1789,7 +1746,7 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
for (var overlayLetterIndex = 0; overlayLetterIndex < led.functions.length; overlayLetterIndex++) {
|
for (var overlayLetterIndex = 0; overlayLetterIndex < led.functions.length; overlayLetterIndex++) {
|
||||||
var bitIndex = MSP.ledOverlayLetters.indexOf(led.functions[overlayLetterIndex]);
|
var bitIndex = MSP.ledOverlayLetters.indexOf(led.functions[overlayLetterIndex]);
|
||||||
if (bitIndex >= 0) {
|
if (bitIndex >= 0) {
|
||||||
|
@ -1805,22 +1762,22 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
|
||||||
mask |= bit_set(mask, bitIndex + 22);
|
mask |= bit_set(mask, bitIndex + 22);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
mask |= (0 << 28); // parameters
|
mask |= (0 << 28); // parameters
|
||||||
|
|
||||||
|
|
||||||
buffer.push(specificByte(mask, 0));
|
buffer.push(specificByte(mask, 0));
|
||||||
buffer.push(specificByte(mask, 1));
|
buffer.push(specificByte(mask, 1));
|
||||||
buffer.push(specificByte(mask, 2));
|
buffer.push(specificByte(mask, 2));
|
||||||
buffer.push(specificByte(mask, 3));
|
buffer.push(specificByte(mask, 3));
|
||||||
}
|
}
|
||||||
|
|
||||||
// prepare for next iteration
|
// prepare for next iteration
|
||||||
ledIndex++;
|
ledIndex++;
|
||||||
if (ledIndex == LED_STRIP.length) {
|
if (ledIndex == LED_STRIP.length) {
|
||||||
nextFunction = onCompleteCallback;
|
nextFunction = onCompleteCallback;
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSP_codes.MSP_SET_LED_STRIP_CONFIG, buffer, false, nextFunction);
|
MSP.send_message(MSP_codes.MSP_SET_LED_STRIP_CONFIG, buffer, false, nextFunction);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1830,10 +1787,10 @@ MSP.sendLedStripColors = function(onCompleteCallback) {
|
||||||
onCompleteCallback();
|
onCompleteCallback();
|
||||||
} else {
|
} else {
|
||||||
var buffer = [];
|
var buffer = [];
|
||||||
|
|
||||||
for (var colorIndex = 0; colorIndex < LED_COLORS.length; colorIndex++) {
|
for (var colorIndex = 0; colorIndex < LED_COLORS.length; colorIndex++) {
|
||||||
var color = LED_COLORS[colorIndex];
|
var color = LED_COLORS[colorIndex];
|
||||||
|
|
||||||
buffer.push(specificByte(color.h, 0));
|
buffer.push(specificByte(color.h, 0));
|
||||||
buffer.push(specificByte(color.h, 1));
|
buffer.push(specificByte(color.h, 1));
|
||||||
buffer.push(color.s);
|
buffer.push(color.s);
|
||||||
|
@ -1844,21 +1801,21 @@ MSP.sendLedStripColors = function(onCompleteCallback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.sendLedStripModeColors = function(onCompleteCallback) {
|
MSP.sendLedStripModeColors = function(onCompleteCallback) {
|
||||||
|
|
||||||
var nextFunction = send_next_led_strip_mode_color;
|
var nextFunction = send_next_led_strip_mode_color;
|
||||||
var index = 0;
|
var index = 0;
|
||||||
|
|
||||||
if (LED_MODE_COLORS.length == 0) {
|
if (LED_MODE_COLORS.length == 0) {
|
||||||
onCompleteCallback();
|
onCompleteCallback();
|
||||||
} else {
|
} else {
|
||||||
send_next_led_strip_mode_color();
|
send_next_led_strip_mode_color();
|
||||||
}
|
}
|
||||||
|
|
||||||
function send_next_led_strip_mode_color() {
|
function send_next_led_strip_mode_color() {
|
||||||
var buffer = [];
|
var buffer = [];
|
||||||
|
|
||||||
var mode_color = LED_MODE_COLORS[index];
|
var mode_color = LED_MODE_COLORS[index];
|
||||||
|
|
||||||
buffer.push(mode_color.mode);
|
buffer.push(mode_color.mode);
|
||||||
buffer.push(mode_color.direction);
|
buffer.push(mode_color.direction);
|
||||||
buffer.push(mode_color.color);
|
buffer.push(mode_color.color);
|
||||||
|
@ -1934,4 +1891,4 @@ MSP.SDCARD_STATE_NOT_PRESENT = 0;
|
||||||
MSP.SDCARD_STATE_FATAL = 1;
|
MSP.SDCARD_STATE_FATAL = 1;
|
||||||
MSP.SDCARD_STATE_CARD_INIT = 2;
|
MSP.SDCARD_STATE_CARD_INIT = 2;
|
||||||
MSP.SDCARD_STATE_FS_INIT = 3;
|
MSP.SDCARD_STATE_FS_INIT = 3;
|
||||||
MSP.SDCARD_STATE_READY = 4;
|
MSP.SDCARD_STATE_READY = 4;
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<table class="pid_titlebar">
|
<table class="pid_titlebar">
|
||||||
<tr>
|
<tr>
|
||||||
<th class="name" i18n="pidTuningName""></th>
|
<th class="name" i18n="pidTuningName"></th>
|
||||||
<th class="proportional" i18n="pidTuningProportional"></th>
|
<th class="proportional" i18n="pidTuningProportional"></th>
|
||||||
<th class="integral" i18n="pidTuningIntegral"></th>
|
<th class="integral" i18n="pidTuningIntegral"></th>
|
||||||
<th class="derivative" i18n="pidTuningDerivative"></th>
|
<th class="derivative" i18n="pidTuningDerivative"></th>
|
||||||
|
@ -38,22 +38,22 @@
|
||||||
<tr class="ROLL">
|
<tr class="ROLL">
|
||||||
<!-- 0 -->
|
<!-- 0 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.001" min="0" max="0.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>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="PITCH">
|
<tr class="PITCH">
|
||||||
<!-- 1 -->
|
<!-- 1 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.001" min="0" max="0.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>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="YAW">
|
<tr class="YAW">
|
||||||
<!-- 2 -->
|
<!-- 2 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.001" min="0" max="0.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>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
|
@ -66,15 +66,15 @@
|
||||||
<tr class="ALT">
|
<tr class="ALT">
|
||||||
<!-- 3 -->
|
<!-- 3 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.001" min="0" max="0.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>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="Vario">
|
<tr class="Vario">
|
||||||
<!-- 9 -->
|
<!-- 9 -->
|
||||||
<td>VEL</td>
|
<td>VEL</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><input type="number" name="i" step="0.001" min="0" max="0.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>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
|
@ -87,7 +87,7 @@
|
||||||
<tr class="MAG">
|
<tr class="MAG">
|
||||||
<!-- 8 -->
|
<!-- 8 -->
|
||||||
<td></td>
|
<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>
|
||||||
<td></td>
|
<td></td>
|
||||||
</tr>
|
</tr>
|
||||||
|
@ -101,23 +101,23 @@
|
||||||
<tr class="Pos">
|
<tr class="Pos">
|
||||||
<!-- 4 -->
|
<!-- 4 -->
|
||||||
<td></td>
|
<td></td>
|
||||||
<td><input type="number" name="p" 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="0.01" min="0" max="2.55" /></td>
|
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||||
<td></td>
|
<td></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="PosR">
|
<tr class="PosR">
|
||||||
<!-- 5 -->
|
<!-- 5 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.01" min="0" max="2.55" /></td>
|
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||||
<td><input type="number" name="d" step="0.001" min="0" max="0.255" /></td>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="NavR">
|
<tr class="NavR">
|
||||||
<!-- 6 -->
|
<!-- 6 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.01" min="0" max="2.55" /></td>
|
<td><input type="number" name="i" step="1" min="0" max="255" /></td>
|
||||||
<td><input type="number" name="d" step="0.001" min="0" max="0.255" /></td>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
@ -139,8 +139,8 @@
|
||||||
<tr class="LEVEL">
|
<tr class="LEVEL">
|
||||||
<!-- 7 -->
|
<!-- 7 -->
|
||||||
<td></td>
|
<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><input type="number" name="i" step="0.001" min="0" max="0.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>
|
<td><input type="number" name="d" step="1" min="0" max="255" /></td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
|
|
|
@ -32,136 +32,37 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names);
|
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names);
|
||||||
|
|
||||||
function pid_and_rc_to_form() {
|
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
|
// Fill in the data from PIDs array
|
||||||
var i = 0;
|
var i;
|
||||||
$('.pid_tuning .ROLL input').each(function () {
|
/*
|
||||||
switch (i) {
|
* Iterate over registered sections/PID controllers
|
||||||
case 0:
|
*/
|
||||||
$(this).val(PIDs[0][i++].toFixed(1));
|
for (var sectionId = 0; sectionId < sectionClasses.length; sectionId++) {
|
||||||
break;
|
|
||||||
case 1:
|
|
||||||
$(this).val(PIDs[0][i++].toFixed(3));
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
$(this).val(PIDs[0][i++].toFixed(0));
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
|
|
||||||
i = 0;
|
i = 0;
|
||||||
$('.pid_tuning .PITCH input').each(function () {
|
/*
|
||||||
switch (i) {
|
* Now, iterate over inputs inside PID constroller section
|
||||||
case 0:
|
*/
|
||||||
$(this).val(PIDs[1][i++].toFixed(1));
|
$('.pid_tuning .' + sectionClasses[sectionId] + ' input').each(function () {
|
||||||
break;
|
$(this).val(PIDs[sectionId][i].toFixed(0));
|
||||||
case 1:
|
i++;
|
||||||
$(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
|
// Fill in data from RC_tuning object
|
||||||
$('.rate-tpa input[name="roll-pitch"]').val(RC_tuning.roll_pitch_rate.toFixed(2));
|
$('.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