1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-14 20:10:11 +03:00

Cleanup for server

This commit is contained in:
Pawel Spychalski (DzikuVx) 2020-04-28 11:10:51 +02:00
parent 74ee18d8d0
commit 3f95ce9acf
3 changed files with 107 additions and 244 deletions

View file

@ -20,17 +20,6 @@ var mspHelper = (function (gui) {
'921600' '921600'
]; ];
self.BAUD_RATES_pre1_6_3 = [
'AUTO',
'9600',
'19200',
'38400',
'57600',
'115200',
'230400',
'250000'
];
self.SERIAL_PORT_FUNCTIONS = { self.SERIAL_PORT_FUNCTIONS = {
'MSP': 0, 'MSP': 0,
'GPS': 1, 'GPS': 1,
@ -415,10 +404,6 @@ var mspHelper = (function (gui) {
REVERSIBLE_MOTORS.deadband_high = data.getUint16(offset, true); REVERSIBLE_MOTORS.deadband_high = data.getUint16(offset, true);
offset += 2; offset += 2;
REVERSIBLE_MOTORS.neutral = data.getUint16(offset, true); REVERSIBLE_MOTORS.neutral = data.getUint16(offset, true);
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
offset += 2;
REVERSIBLE_MOTORS.deadband_throttle = data.getUint16(offset, true);
}
break; break;
case MSPCodes.MSP_MOTOR_PINS: case MSPCodes.MSP_MOTOR_PINS:
console.log(data); console.log(data);
@ -634,9 +619,7 @@ var mspHelper = (function (gui) {
RC_deadband.deadband = data.getUint8(offset++); RC_deadband.deadband = data.getUint8(offset++);
RC_deadband.yaw_deadband = data.getUint8(offset++); RC_deadband.yaw_deadband = data.getUint8(offset++);
RC_deadband.alt_hold_deadband = data.getUint8(offset++); RC_deadband.alt_hold_deadband = data.getUint8(offset++);
if (semver.gte(CONFIG.apiVersion, "1.24.0")) {
REVERSIBLE_MOTORS.deadband_throttle = data.getUint16(offset, true); REVERSIBLE_MOTORS.deadband_throttle = data.getUint16(offset, true);
}
break; break;
case MSPCodes.MSP_SENSOR_ALIGNMENT: case MSPCodes.MSP_SENSOR_ALIGNMENT:
SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++); SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++);
@ -814,7 +797,7 @@ var mspHelper = (function (gui) {
var serialPortCount = data.byteLength / bytesPerPort; var serialPortCount = data.byteLength / bytesPerPort;
for (i = 0; i < serialPortCount; i++) { for (i = 0; i < serialPortCount; i++) {
var BAUD_RATES = (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) ? mspHelper.BAUD_RATES_post1_6_3 : mspHelper.BAUD_RATES_pre1_6_3; var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
var serialPort = { var serialPort = {
identifier: data.getUint8(offset), identifier: data.getUint8(offset),
@ -836,7 +819,7 @@ var mspHelper = (function (gui) {
var serialPortCount = data.byteLength / bytesPerPort; var serialPortCount = data.byteLength / bytesPerPort;
for (i = 0; i < serialPortCount; i++) { for (i = 0; i < serialPortCount; i++) {
var BAUD_RATES = (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) ? mspHelper.BAUD_RATES_post1_6_3 : mspHelper.BAUD_RATES_pre1_6_3; var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
var serialPort = { var serialPort = {
identifier: data.getUint8(offset), identifier: data.getUint8(offset),
@ -923,7 +906,6 @@ var mspHelper = (function (gui) {
offset += 2; offset += 2;
RX_CONFIG.rx_max_usec = data.getUint16(offset, true); RX_CONFIG.rx_max_usec = data.getUint16(offset, true);
offset += 2; offset += 2;
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
offset += 4; // 4 null bytes for betaflight compatibility offset += 4; // 4 null bytes for betaflight compatibility
RX_CONFIG.spirx_protocol = data.getUint8(offset); RX_CONFIG.spirx_protocol = data.getUint8(offset);
offset++; offset++;
@ -931,7 +913,6 @@ var mspHelper = (function (gui) {
offset += 4; offset += 4;
RX_CONFIG.spirx_channel_count = data.getUint8(offset); RX_CONFIG.spirx_channel_count = data.getUint8(offset);
offset += 1; offset += 1;
}
// unused byte for fpvCamAngleDegrees, for compatiblity with betaflight // unused byte for fpvCamAngleDegrees, for compatiblity with betaflight
offset += 1; offset += 1;
RX_CONFIG.receiver_type = data.getUint8(offset); RX_CONFIG.receiver_type = data.getUint8(offset);
@ -987,11 +968,7 @@ var mspHelper = (function (gui) {
//noinspection JSUndeclaredVariable //noinspection JSUndeclaredVariable
LED_STRIP = []; LED_STRIP = [];
var ledCount = data.byteLength / 7; // v1.4.0 and below incorrectly reported 4 bytes per led. var ledCount = data.byteLength / 4;
if (semver.gte(CONFIG.apiVersion, "1.20.0"))
ledCount = data.byteLength / 4;
var directionMask, var directionMask,
directions, directions,
directionLetterIndex, directionLetterIndex,
@ -1103,8 +1080,6 @@ var mspHelper = (function (gui) {
console.log('Led strip colors saved'); console.log('Led strip colors saved');
break; break;
case MSPCodes.MSP_LED_STRIP_MODECOLOR: case MSPCodes.MSP_LED_STRIP_MODECOLOR:
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
//noinspection JSUndeclaredVariable //noinspection JSUndeclaredVariable
LED_MODE_COLORS = []; LED_MODE_COLORS = [];
@ -1123,7 +1098,6 @@ var mspHelper = (function (gui) {
color: color color: color
}); });
} }
}
break; break;
case MSPCodes.MSP_SET_LED_STRIP_MODECOLOR: case MSPCodes.MSP_SET_LED_STRIP_MODECOLOR:
console.log('Led strip mode colors saved'); console.log('Led strip mode colors saved');
@ -1315,10 +1289,7 @@ var mspHelper = (function (gui) {
CALIBRATION_DATA.magZero.X = data.getInt16(13, true); CALIBRATION_DATA.magZero.X = data.getInt16(13, true);
CALIBRATION_DATA.magZero.Y = data.getInt16(15, true); CALIBRATION_DATA.magZero.Y = data.getInt16(15, true);
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true); CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) {
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0); CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
}
break; break;
@ -1757,7 +1728,6 @@ var mspHelper = (function (gui) {
buffer.push(highByte(RX_CONFIG.rx_min_usec)); buffer.push(highByte(RX_CONFIG.rx_min_usec));
buffer.push(lowByte(RX_CONFIG.rx_max_usec)); buffer.push(lowByte(RX_CONFIG.rx_max_usec));
buffer.push(highByte(RX_CONFIG.rx_max_usec)); buffer.push(highByte(RX_CONFIG.rx_max_usec));
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
buffer.push(0); // 4 null bytes for betaflight compatibility buffer.push(0); // 4 null bytes for betaflight compatibility
buffer.push(0); buffer.push(0);
buffer.push(0); buffer.push(0);
@ -1766,7 +1736,6 @@ var mspHelper = (function (gui) {
// spirx_id - 4 bytes // spirx_id - 4 bytes
buffer.push32(RX_CONFIG.spirx_id); buffer.push32(RX_CONFIG.spirx_id);
buffer.push(RX_CONFIG.spirx_channel_count); buffer.push(RX_CONFIG.spirx_channel_count);
}
// unused byte for fpvCamAngleDegrees, for compatiblity with betaflight // unused byte for fpvCamAngleDegrees, for compatiblity with betaflight
buffer.push(0); buffer.push(0);
// receiver type in RX_CONFIG rather than in BF_CONFIG.features // receiver type in RX_CONFIG rather than in BF_CONFIG.features
@ -1822,7 +1791,7 @@ var mspHelper = (function (gui) {
buffer.push(specificByte(functionMask, 0)); buffer.push(specificByte(functionMask, 0));
buffer.push(specificByte(functionMask, 1)); buffer.push(specificByte(functionMask, 1));
var BAUD_RATES = (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) ? mspHelper.BAUD_RATES_post1_6_3 : mspHelper.BAUD_RATES_pre1_6_3; var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate)); buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate)); buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate)); buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate));
@ -1842,7 +1811,7 @@ var mspHelper = (function (gui) {
buffer.push(specificByte(functionMask, 2)); buffer.push(specificByte(functionMask, 2));
buffer.push(specificByte(functionMask, 3)); buffer.push(specificByte(functionMask, 3));
var BAUD_RATES = (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) ? mspHelper.BAUD_RATES_post1_6_3 : mspHelper.BAUD_RATES_pre1_6_3; var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate)); buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate)); buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate)); buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate));
@ -1857,20 +1826,14 @@ var mspHelper = (function (gui) {
buffer.push(highByte(REVERSIBLE_MOTORS.deadband_high)); buffer.push(highByte(REVERSIBLE_MOTORS.deadband_high));
buffer.push(lowByte(REVERSIBLE_MOTORS.neutral)); buffer.push(lowByte(REVERSIBLE_MOTORS.neutral));
buffer.push(highByte(REVERSIBLE_MOTORS.neutral)); buffer.push(highByte(REVERSIBLE_MOTORS.neutral));
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
buffer.push(lowByte(REVERSIBLE_MOTORS.deadband_throttle));
buffer.push(highByte(REVERSIBLE_MOTORS.deadband_throttle));
}
break; break;
case MSPCodes.MSP_SET_RC_DEADBAND: case MSPCodes.MSP_SET_RC_DEADBAND:
buffer.push(RC_deadband.deadband); buffer.push(RC_deadband.deadband);
buffer.push(RC_deadband.yaw_deadband); buffer.push(RC_deadband.yaw_deadband);
buffer.push(RC_deadband.alt_hold_deadband); buffer.push(RC_deadband.alt_hold_deadband);
if (semver.gte(CONFIG.apiVersion, "1.24.0")) {
buffer.push(lowByte(REVERSIBLE_MOTORS.deadband_throttle)); buffer.push(lowByte(REVERSIBLE_MOTORS.deadband_throttle));
buffer.push(highByte(REVERSIBLE_MOTORS.deadband_throttle)); buffer.push(highByte(REVERSIBLE_MOTORS.deadband_throttle));
}
break; break;
case MSPCodes.MSP_SET_SENSOR_ALIGNMENT: case MSPCodes.MSP_SET_SENSOR_ALIGNMENT:
@ -1970,10 +1933,8 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(CALIBRATION_DATA.magZero.Z)); buffer.push(lowByte(CALIBRATION_DATA.magZero.Z));
buffer.push(highByte(CALIBRATION_DATA.magZero.Z)); buffer.push(highByte(CALIBRATION_DATA.magZero.Z));
if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) {
buffer.push(lowByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256))); buffer.push(lowByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
buffer.push(highByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256))); buffer.push(highByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
}
break; break;
case MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG: case MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG:
@ -2216,16 +2177,11 @@ var mspHelper = (function (gui) {
var buffer = []; var buffer = [];
var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG; var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
buffer.push(BLACKBOX.blackboxDevice & 0xFF); buffer.push(BLACKBOX.blackboxDevice & 0xFF);
if (semver.gte(CONFIG.apiVersion, "2.3.0")) {
messageId = MSPCodes.MSP2_SET_BLACKBOX_CONFIG; messageId = MSPCodes.MSP2_SET_BLACKBOX_CONFIG;
buffer.push(lowByte(BLACKBOX.blackboxRateNum)); buffer.push(lowByte(BLACKBOX.blackboxRateNum));
buffer.push(highByte(BLACKBOX.blackboxRateNum)); buffer.push(highByte(BLACKBOX.blackboxRateNum));
buffer.push(lowByte(BLACKBOX.blackboxRateDenom)); buffer.push(lowByte(BLACKBOX.blackboxRateDenom));
buffer.push(highByte(BLACKBOX.blackboxRateDenom)); buffer.push(highByte(BLACKBOX.blackboxRateDenom));
} else {
buffer.push(BLACKBOX.blackboxRateNum & 0xFF);
buffer.push(BLACKBOX.blackboxRateDenom & 0xFF);
}
//noinspection JSUnusedLocalSymbols //noinspection JSUnusedLocalSymbols
MSP.send_message(messageId, buffer, false, function (response) { MSP.send_message(messageId, buffer, false, function (response) {
onDataCallback(); onDataCallback();
@ -2306,24 +2262,6 @@ var mspHelper = (function (gui) {
var servoRule = SERVO_RULES.get()[servoIndex]; var servoRule = SERVO_RULES.get()[servoIndex];
if (semver.lt(CONFIG.flightControllerVersion, "2.2.0")) {
buffer.push(servoIndex);
buffer.push(servoRule.getTarget());
buffer.push(servoRule.getInput());
buffer.push(lowByte(servoRule.getRate()));
buffer.push(highByte(servoRule.getRate()));
buffer.push(servoRule.getSpeed());
buffer.push(0);
buffer.push(0);
buffer.push(0);
// prepare for next iteration
servoIndex++;
if (servoIndex == SERVO_RULES.getServoRulesCount()) { //This is the last rule. Not pretty, but we have to send all rules
nextFunction = onCompleteCallback;
}
MSP.send_message(MSPCodes.MSP_SET_SERVO_MIX_RULE, buffer, false, nextFunction);
} else {
//INAV 2.2 uses different MSP frame //INAV 2.2 uses different MSP frame
buffer.push(servoIndex); buffer.push(servoIndex);
buffer.push(servoRule.getTarget()); buffer.push(servoRule.getTarget());
@ -2340,7 +2278,6 @@ var mspHelper = (function (gui) {
} }
MSP.send_message(MSPCodes.MSP2_INAV_SET_SERVO_MIXER, buffer, false, nextFunction); MSP.send_message(MSPCodes.MSP2_INAV_SET_SERVO_MIXER, buffer, false, nextFunction);
} }
}
}; };
self.sendMotorMixer = function (onCompleteCallback) { self.sendMotorMixer = function (onCompleteCallback) {
@ -2391,18 +2328,14 @@ var mspHelper = (function (gui) {
}; };
self.loadLogicConditions = function (callback) { self.loadLogicConditions = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS, false, false, callback); MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS, false, false, callback);
} else {
callback();
}
} }
self.sendLogicConditions = function (onCompleteCallback) { self.sendLogicConditions = function (onCompleteCallback) {
let nextFunction = sendCondition, let nextFunction = sendCondition,
conditionIndex = 0; conditionIndex = 0;
if (LOGIC_CONDITIONS.getCount() == 0 || semver.lt(CONFIG.flightControllerVersion, "2.2.0")) { if (LOGIC_CONDITIONS.getCount() == 0) {
onCompleteCallback(); onCompleteCallback();
} else { } else {
nextFunction(); nextFunction();
@ -2444,18 +2377,14 @@ var mspHelper = (function (gui) {
}; };
self.loadGlobalFunctions = function (callback) { self.loadGlobalFunctions = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_GLOBAL_FUNCTIONS, false, false, callback); MSP.send_message(MSPCodes.MSP2_INAV_GLOBAL_FUNCTIONS, false, false, callback);
} else {
callback();
}
} }
self.sendGlobalFunctions = function (onCompleteCallback) { self.sendGlobalFunctions = function (onCompleteCallback) {
let nextFunction = sendGlobalFunction, let nextFunction = sendGlobalFunction,
functionIndex = 0; functionIndex = 0;
if (GLOBAL_FUNCTIONS.getCount() == 0 || semver.lt(CONFIG.flightControllerVersion, "2.4.0")) { if (GLOBAL_FUNCTIONS.getCount() == 0) {
onCompleteCallback(); onCompleteCallback();
} else { } else {
nextFunction(); nextFunction();
@ -2703,36 +2632,6 @@ var mspHelper = (function (gui) {
buffer.push(ledIndex); buffer.push(ledIndex);
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
var directionMask = 0;
for (directionLetterIndex = 0; directionLetterIndex < led.directions.length; directionLetterIndex++) {
bitIndex = MSP.ledDirectionLetters.indexOf(led.directions[directionLetterIndex]);
if (bitIndex >= 0) {
directionMask = bit_set(directionMask, bitIndex);
}
}
buffer.push(specificByte(directionMask, 0));
buffer.push(specificByte(directionMask, 1));
var functionMask = 0;
for (functionLetterIndex = 0; functionLetterIndex < led.functions.length; functionLetterIndex++) {
bitIndex = MSP.ledFunctionLetters.indexOf(led.functions[functionLetterIndex]);
if (bitIndex >= 0) {
functionMask = bit_set(functionMask, bitIndex);
}
}
buffer.push(specificByte(functionMask, 0));
buffer.push(specificByte(functionMask, 1));
buffer.push(led.x);
buffer.push(led.y);
buffer.push(led.color);
} 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
@ -2779,7 +2678,6 @@ var mspHelper = (function (gui) {
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++;
@ -2862,11 +2760,7 @@ var mspHelper = (function (gui) {
}; };
self.loadPidData = function (callback) { self.loadPidData = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, '2.2.0')) {
MSP.send_message(MSPCodes.MSP2_PID, false, false, callback); MSP.send_message(MSPCodes.MSP2_PID, false, false, callback);
} else {
MSP.send_message(MSPCodes.MSP_PID, false, false, callback);
}
}; };
self.loadPidNames = function (callback) { self.loadPidNames = function (callback) {
@ -2906,11 +2800,7 @@ var mspHelper = (function (gui) {
}; };
self.loadRxConfig = function (callback) { self.loadRxConfig = function (callback) {
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, callback); MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, callback);
} else {
callback();
}
}; };
self.load3dConfig = function (callback) { self.load3dConfig = function (callback) {
@ -2970,11 +2860,7 @@ var mspHelper = (function (gui) {
}; };
self.savePidData = function (callback) { self.savePidData = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, '2.2.0')) {
MSP.send_message(MSPCodes.MSP2_SET_PID, mspHelper.crunch(MSPCodes.MSP2_SET_PID), false, callback); MSP.send_message(MSPCodes.MSP2_SET_PID, mspHelper.crunch(MSPCodes.MSP2_SET_PID), false, callback);
} else {
MSP.send_message(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID), false, callback);
}
}; };
self.saveRcTuningData = function (callback) { self.saveRcTuningData = function (callback) {
@ -3022,11 +2908,7 @@ var mspHelper = (function (gui) {
}; };
self.saveRxConfig = function (callback) { self.saveRxConfig = function (callback) {
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, callback); MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, callback);
} else {
callback();
}
}; };
self.saveSensorConfig = function (callback) { self.saveSensorConfig = function (callback) {
@ -3260,11 +3142,7 @@ var mspHelper = (function (gui) {
}; };
self.loadServoMixRules = function (callback) { self.loadServoMixRules = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_SERVO_MIXER, false, false, callback); MSP.send_message(MSPCodes.MSP2_INAV_SERVO_MIXER, false, false, callback);
} else {
MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, callback);
}
}; };
self.loadMotorMixRules = function (callback) { self.loadMotorMixRules = function (callback) {
@ -3337,11 +3215,7 @@ var mspHelper = (function (gui) {
} }
self.loadLogicConditionsStatus = function (callback) { self.loadLogicConditionsStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.3.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS, false, false, callback); MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS, false, false, callback);
} else {
callback();
}
}; };
self.loadGlobalVariablesStatus = function (callback) { self.loadGlobalVariablesStatus = function (callback) {

View file

@ -172,12 +172,6 @@
<span data-i18n="configuration3dNeutral"></span> <span data-i18n="configuration3dNeutral"></span>
</label> </label>
</div> </div>
<div id="deadband-3d-throttle-container" class="number">
<input type="number" id="3ddeadbandthrottle" name="3ddeadbandthrottle" step="1" min="0" max="1000" />
<label for="3ddeadbandthrottle">
<span data-i18n="configuration3dDeadbandThrottle"></span>
</label>
</div>
</div> </div>
</div> </div>

View file

@ -448,11 +448,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#3ddeadbandlow').val(REVERSIBLE_MOTORS.deadband_low); $('#3ddeadbandlow').val(REVERSIBLE_MOTORS.deadband_low);
$('#3ddeadbandhigh').val(REVERSIBLE_MOTORS.deadband_high); $('#3ddeadbandhigh').val(REVERSIBLE_MOTORS.deadband_high);
$('#3dneutral').val(REVERSIBLE_MOTORS.neutral); $('#3dneutral').val(REVERSIBLE_MOTORS.neutral);
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
$('#3ddeadbandthrottle').val(REVERSIBLE_MOTORS.deadband_throttle);
} else {
$('#deadband-3d-throttle-container').remove();
}
// Craft name // Craft name
if (craftName != null) { if (craftName != null) {
@ -484,9 +479,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
REVERSIBLE_MOTORS.deadband_low = parseInt($('#3ddeadbandlow').val()); REVERSIBLE_MOTORS.deadband_low = parseInt($('#3ddeadbandlow').val());
REVERSIBLE_MOTORS.deadband_high = parseInt($('#3ddeadbandhigh').val()); REVERSIBLE_MOTORS.deadband_high = parseInt($('#3ddeadbandhigh').val());
REVERSIBLE_MOTORS.neutral = parseInt($('#3dneutral').val()); REVERSIBLE_MOTORS.neutral = parseInt($('#3dneutral').val());
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
REVERSIBLE_MOTORS.deadband_throttle = ($('#3ddeadbandthrottle').val());
}
SENSOR_ALIGNMENT.align_mag = parseInt(orientation_mag_e.val()); SENSOR_ALIGNMENT.align_mag = parseInt(orientation_mag_e.val());
@ -497,6 +489,9 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]); googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
} }
googleAnalytics.sendEvent('Setting', 'GPSEnabled', FC.isFeatureEnabled('GPS', features) ? "true" : "false");
googleAnalytics.sendEvent("Platform", helper.platform.getById(MIXER_CONFIG.platformType).name, "LPF: " + FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].label + " | Looptime: " + FC_CONFIG.loopTime);
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime); googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
googleAnalytics.sendEvent('Setting', 'GyroLpf', FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].label); googleAnalytics.sendEvent('Setting', 'GyroLpf', FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].label);
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text()); googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());