1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-15 20:35:19 +03:00

Cleanup INAV 2.0.0

This commit is contained in:
Pawel Spychalski (DzikuVx) 2019-10-26 22:30:59 +02:00
parent 0016746d93
commit cb1ff69703
19 changed files with 1274 additions and 3246 deletions

View file

@ -62,9 +62,6 @@ var CONFIG,
var FC = {
MAX_SERVO_RATE: 125,
MIN_SERVO_RATE: 0,
isNewMixer: function () {
return !!(typeof CONFIG != "undefined" && semver.gte(CONFIG.flightControllerVersion, "2.0.0"));
},
isRpyFfComponentUsed: function () {
return MIXER_CONFIG.platformType == PLATFORM_AIRPLANE;
},
@ -560,49 +557,17 @@ var FC = {
{bit: 15, group: 'other', name: 'RSSI_ADC', haveTip: true, showNameInTip: true},
{bit: 16, group: 'other', name: 'LED_STRIP', showNameInTip: true},
{bit: 17, group: 'other', name: 'DASHBOARD', showNameInTip: true},
{bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true}
];
if (semver.lt(CONFIG.flightControllerVersion, "2.0.0")) {
features.push(
{bit: 20, group: 'other', name: 'CHANNEL_FORWARDING', showNameInTip: true},
{bit: 5, group: 'other', name: 'SERVO_TILT', showNameInTip: true}
);
}
features.push(
{bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true}
);
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
features.push(
{bit: 26, group: 'other', name: 'SOFTSPI'}
);
}
features.push(
{bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true}
);
features.push(
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false}
);
features.push(
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false}
);
features.push(
{bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true},
{bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true},
{bit: 26, group: 'other', name: 'SOFTSPI'},
{bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true},
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false},
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false},
{bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false},
{bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false}
);
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) {
features.push(
{bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false},
{bit: 0, group: 'other', name: 'THR_VBAT_COMP', haveTip: true, showNameInTip: true},
{bit: 3, group: 'other', name: 'BAT_PROFILE_AUTOSWITCH', haveTip: true, showNameInTip: true}
);
}
];
return features.reverse();
},
@ -802,13 +767,10 @@ var FC = {
'XBUS_MODE_B_RJ01',
'IBUS',
'JETI EXBUS',
'TBS Crossfire'
'TBS Crossfire',
'FPort'
];
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) {
data.push('FPort');
}
return data;
},
getSPIProtocolTypes: function () {
@ -975,13 +937,9 @@ var FC = {
getAccelerometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
}
else if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
} else {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"];
}
else {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "FAKE"];
}
},
getMagnetometerNames: function () {
return ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "FAKE"];
@ -989,21 +947,12 @@ var FC = {
getBarometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.3.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "FAKE"];
} else if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "FAKE"];
} else if (semver.gte(CONFIG.flightControllerVersion, "1.6.2")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "FAKE"];
} else {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "FAKE"];
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "FAKE"];
}
},
getPitotNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) {
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
}
else {
return ["NONE", "AUTO", "MS4525", "FAKE"];
}
},
getRangefinderNames: function () {
let data = [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"];
@ -1084,10 +1033,7 @@ var FC = {
}
},
getRcMapLetters: function () {
if (semver.gte(CONFIG.flightControllerVersion, '1.9.1'))
return ['A', 'E', 'R', 'T'];
else
return ['A', 'E', 'R', 'T', '5', '6', '7', '8'];
},
isRcMapValid: function (val) {
var strBuffer = val.split(''),

View file

@ -231,8 +231,7 @@ var mspHelper = (function (gui) {
ANALOG.amperage = data.getInt16(5, true) / 100; // A
break;
case MSPCodes.MSPV2_INAV_ANALOG:
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
var tmp = data.getUint8(offset++);
let tmp = data.getUint8(offset++);
ANALOG.battery_full_when_plugged_in = (tmp & 1 ? true : false);
ANALOG.use_capacity_thresholds = ((tmp & 2) >> 1 ? true : false);
ANALOG.battery_state = (tmp & 12) >> 2;
@ -252,28 +251,6 @@ var mspHelper = (function (gui) {
ANALOG.battery_percentage = data.getUint8(offset++);
ANALOG.rssi = data.getUint16(offset, true); // 0-1023
offset += 2;
} else {
ANALOG.voltage = data.getUint16(offset, true) / 100.0;
offset += 2;
ANALOG.cell_count = data.getUint8(offset++);
ANALOG.battery_percentage = data.getUint8(offset++);
ANALOG.power = data.getUint16(offset, true);
offset += 2;
ANALOG.mAhdrawn = data.getUint16(offset, true);
offset += 2;
ANALOG.mWhdrawn = data.getUint16(offset, true);
offset += 2;
ANALOG.rssi = data.getUint16(offset, true); // 0-1023
offset += 2;
ANALOG.amperage = data.getInt16(offset, true) / 100; // A
offset += 2;
var battery_flags = data.getUint8(offset++);
ANALOG.battery_full_when_plugged_in = (battery_flags & 1 ? true : false);
ANALOG.use_capacity_thresholds = ((battery_flags & 2) >> 1 ? true : false);
ANALOG.battery_state = (battery_flags & 12) >> 2;
ANALOG.battery_remaining_capacity = data.getUint32(offset, true);
offset += 4;
}
//noinspection JSValidateTypes
dataHandler.analog_last_received_timestamp = Date.now();
break;
@ -385,12 +362,10 @@ var mspHelper = (function (gui) {
offset += 2;
MISC.vbatscale = data.getUint16(offset, true);
offset += 2;
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MISC.voltage_source = data.getUint8(offset++);
MISC.battery_cells = data.getUint8(offset++);
MISC.vbatdetectcellvoltage = data.getUint16(offset, true) / 100;
offset += 2;
}
MISC.vbatmincellvoltage = data.getUint16(offset, true) / 100;
offset += 2;
MISC.vbatmaxcellvoltage = data.getUint16(offset, true) / 100;
@ -411,12 +386,10 @@ var mspHelper = (function (gui) {
case MSPCodes.MSPV2_INAV_BATTERY_CONFIG:
BATTERY_CONFIG.vbatscale = data.getUint16(offset, true);
offset += 2;
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
BATTERY_CONFIG.voltage_source = data.getUint8(offset++);
BATTERY_CONFIG.battery_cells = data.getUint8(offset++);
BATTERY_CONFIG.vbatdetectcellvoltage = data.getUint16(offset, true) / 100;
offset += 2;
}
BATTERY_CONFIG.vbatmincellvoltage = data.getUint16(offset, true) / 100;
offset += 2;
BATTERY_CONFIG.vbatmaxcellvoltage = data.getUint16(offset, true) / 100;
@ -634,9 +607,7 @@ var mspHelper = (function (gui) {
SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_acc = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_mag = data.getUint8(offset++);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
SENSOR_ALIGNMENT.align_opflow = data.getUint8(offset++);
}
break;
case MSPCodes.MSP_SET_RAW_RC:
break;
@ -1224,11 +1195,9 @@ var mspHelper = (function (gui) {
FILTER_CONFIG.gyroNotchHz2 = data.getUint16(13, true);
FILTER_CONFIG.gyroNotchCutoff2 = data.getUint16(15, true);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
FILTER_CONFIG.accNotchHz = data.getUint16(17, true);
FILTER_CONFIG.accNotchCutoff = data.getUint16(19, true);
FILTER_CONFIG.gyroStage2LowpassHz = data.getUint16(21, true);
}
break;
@ -1693,12 +1662,10 @@ var mspHelper = (function (gui) {
buffer.push(highByte(Math.round(MISC.mag_declination * 10)));
buffer.push(lowByte(MISC.vbatscale));
buffer.push(highByte(MISC.vbatscale));
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
buffer.push(MISC.voltage_source);
buffer.push(MISC.battery_cells);
buffer.push(lowByte(Math.round(MISC.vbatdetectcellvoltage * 100)));
buffer.push(highByte(Math.round(MISC.vbatdetectcellvoltage * 100)));
}
buffer.push(lowByte(Math.round(MISC.vbatmincellvoltage * 100)));
buffer.push(highByte(Math.round(MISC.vbatmincellvoltage * 100)));
buffer.push(lowByte(Math.round(MISC.vbatmaxcellvoltage * 100)));
@ -1716,12 +1683,10 @@ var mspHelper = (function (gui) {
case MSPCodes.MSPV2_INAV_SET_BATTERY_CONFIG:
buffer.push(lowByte(BATTERY_CONFIG.vbatscale));
buffer.push(highByte(BATTERY_CONFIG.vbatscale));
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
buffer.push(BATTERY_CONFIG.voltage_source);
buffer.push(BATTERY_CONFIG.battery_cells);
buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
buffer.push(highByte(Math.round(BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
}
buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 100)));
buffer.push(highByte(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 100)));
buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatmaxcellvoltage * 100)));
@ -1874,9 +1839,7 @@ var mspHelper = (function (gui) {
buffer.push(SENSOR_ALIGNMENT.align_gyro);
buffer.push(SENSOR_ALIGNMENT.align_acc);
buffer.push(SENSOR_ALIGNMENT.align_mag);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
buffer.push(SENSOR_ALIGNMENT.align_opflow);
}
break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
@ -2072,7 +2035,6 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(FILTER_CONFIG.gyroNotchCutoff2));
buffer.push(highByte(FILTER_CONFIG.gyroNotchCutoff2));
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
buffer.push(lowByte(FILTER_CONFIG.accNotchHz));
buffer.push(highByte(FILTER_CONFIG.accNotchHz));
@ -2081,7 +2043,6 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(FILTER_CONFIG.gyroStage2LowpassHz));
buffer.push(highByte(FILTER_CONFIG.gyroStage2LowpassHz));
}
break;
@ -2838,10 +2799,7 @@ var mspHelper = (function (gui) {
};
self.queryFcStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0'))
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, callback);
else
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false, callback);
};
self.loadMisc = function (callback) {
@ -2853,12 +2811,7 @@ var mspHelper = (function (gui) {
};
self.loadOutputMapping = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0'))
MSP.send_message(MSPCodes.MSPV2_INAV_OUTPUT_MAPPING, false, false, callback);
else {
OUTPUT_MAPPING.flush();
callback();
}
};
self.loadBatteryConfig = function (callback) {
@ -3042,9 +2995,6 @@ var mspHelper = (function (gui) {
};
self._getSetting = function (name) {
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) {
return self._getLegacySetting(name);
}
if (SETTINGS[name]) {
return Promise.resolve(SETTINGS[name]);
}
@ -3101,31 +3051,6 @@ var mspHelper = (function (gui) {
});
}
self._getLegacySetting = function (name) {
var promise;
if (SETTINGS) {
promise = Promise.resolve(SETTINGS);
} else {
promise = new Promise(function (resolve, reject) {
$.ajax({
url: chrome.runtime.getURL('/resources/settings.json'),
dataType: 'json',
error: function (jqXHR, text, error) {
reject(error);
},
success: function (data) {
SETTINGS = data;
resolve(data);
}
});
});
}
return promise.then(function (data) {
return data[name];
});
};
self._encodeSettingReference = function (name, index, data) {
if (Number.isInteger(index)) {
data.push8(0);
@ -3286,35 +3211,19 @@ var mspHelper = (function (gui) {
};
self.loadMixerConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) {
MSP.send_message(MSPCodes.MSP2_INAV_MIXER, false, false, callback);
} else {
callback();
}
};
self.saveMixerConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_MIXER, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MIXER), false, callback);
} else {
callback();
}
};
self.loadVTXConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
} else {
callback();
}
};
self.saveVTXConfig = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
} else {
callback();
}
};
self.loadBrakingConfig = function(callback) {
@ -3334,7 +3243,6 @@ var mspHelper = (function (gui) {
};
self.loadParameterGroups = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
var groups = [];
while (resp.data.offset < resp.data.byteLength) {
@ -3347,9 +3255,6 @@ var mspHelper = (function (gui) {
callback(groups);
}
});
} else if (callback) {
callback();
}
};
self.loadBrakingConfig = function(callback) {

View file

@ -102,13 +102,7 @@ helper.periodicStatusUpdater = (function () {
}
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS, false, false);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false);
} else {
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
}
MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false);
MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false);

View file

@ -145,12 +145,6 @@ $(document).ready(function () {
var tab = tabClass.substring(4);
var tabName = $(self).text();
if (CONFIGURATOR.connectionValid && semver.lt(CONFIG.flightControllerVersion, "2.0.0")) {
$('#battery_profile_change').hide();
$('#profile_change').css('width', '125px');
$('#dataflash_wrapper_global').css('width', '125px');
}
if (tabRequiresConnection && !CONFIGURATOR.connectionValid) {
GUI.log(chrome.i18n.getMessage('tabSwitchConnectionRequired'));
return;

View file

@ -1,7 +1,7 @@
{
"manifest_version": 2,
"minimum_chrome_version": "38",
"version": "2.3.0",
"version": "2.3.0-RC3",
"author": "Several",
"name": "INAV - Configurator",
"short_name": "INAV",

2290
package-lock.json generated

File diff suppressed because it is too large Load diff

View file

@ -1,7 +1,7 @@
{
"name": "inav-configurator",
"description": "INAV Configurator",
"version": "2.3.0",
"version": "2.3.0-RC3",
"main": "main.html",
"default_locale": "en",
"scripts": {

File diff suppressed because it is too large Load diff

View file

@ -10,21 +10,6 @@
</div>
</div>
<div class="leftWrapper">
<div class="mixer gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationMixer"></div>
</div>
<div class="spacer_box">
<div class="mixerPreview half">
<img src="./resources/motor_order/custom.svg" />
</div>
<div class="half" style="width: calc(50% - 10px); margin-left: 10px;">
<select class="mixerList">
<!-- list generated here -->
</select>
</div>
</div>
</div>
<div class="config-section sensors gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationSensors"></div>
@ -56,7 +41,7 @@
<label for="sensor-rangefinder"> <span data-i18n="sensorRangefinder"></span></label>
</div>
<div class="select requires-v2_0_0">
<div class="select">
<select id="sensor-opflow"></select>
<label for="sensor-opflow"> <span data-i18n="sensorOpflow"></span></label>
</div>
@ -418,7 +403,7 @@
<div class="features batteryVoltage"></div>
<!--list of generated features goes here-->
<div class="select requires-v2_0_0">
<div class="select">
<select id="voltagesource" class="voltagesource">
<option value="0">Raw</option>
<option value="1">Sag compensated</option>
@ -428,12 +413,12 @@
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationVoltageSourceHelp"></div>
</div>
<div class="number requires-v2_0_0">
<div class="number">
<input type="number" id="cells" name="cells" step="1" min="0" max="8" />
<label for="cells"><span data-i18n="configurationBatteryCells"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellsHelp"></div>
</div>
<div class="number requires-v2_0_0">
<div class="number">
<input type="number" id="celldetectvoltage" name="celldetectvoltage" step="0.01" min="1" max="5" />
<label for="celldetectvoltage"><span data-i18n="configurationBatteryCellDetectVoltage"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellDetectVoltageHelp"></div>

View file

@ -397,13 +397,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// midrc was removed in 2.0, but the firmware still excepts
// the MSP frame with it for backwards compatibility, so we
// just hide it from the UI.
var midThrottleWrapper = $('.midthrottle_wrapper');
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) {
$('#midthrottle').val(MISC.midrc);
midThrottleWrapper.show();
} else {
let midThrottleWrapper = $('.midthrottle_wrapper');
midThrottleWrapper.hide();
}
$('#maxthrottle').val(MISC.maxthrottle);
$('#mincommand').val(MISC.mincommand);
@ -416,19 +411,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#warningcellvoltage').val(MISC.vbatwarningcellvoltage);
$('#voltagescale').val(MISC.vbatscale);
// adjust current offset input attributes
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) {
var current_offset_input = $('#currentoffset');
current_offset_input.attr('step', '1');
current_offset_input.attr('min', '-3300');
current_offset_input.attr('max', '3300');
}
// fill current
$('#currentscale').val(BF_CONFIG.currentscale);
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0'))
$('#currentoffset').val(BF_CONFIG.currentoffset);
else
$('#currentoffset').val(BF_CONFIG.currentoffset / 10);
// fill battery capacity
@ -717,12 +701,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
SENSOR_CONFIG.opflow = $sensorOpflow.val();
});
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
$(".requires-v2_0_0").show();
} else {
$(".requires-v2_0_0").hide();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
$(".removed-v2_1_0").hide();
$(".requires-v2_1_0").show();
@ -816,10 +794,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
MISC.battery_capacity_unit = $('#battery_capacity_unit').val();
BF_CONFIG.currentscale = parseInt($('#currentscale').val());
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0'))
BF_CONFIG.currentoffset = parseInt($('#currentoffset').val());
else
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
_3D.deadband3d_low = parseInt($('#3ddeadbandlow').val());
@ -850,9 +824,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
}
if (!FC.isNewMixer()) {
googleAnalytics.sendEvent('Setting', 'Mixer', helper.mixer.getById(BF_CONFIG.mixerConfiguration).name);
}
googleAnalytics.sendEvent('Setting', 'ReceiverMode', $('#rxType').val());
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
@ -882,13 +854,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#batterycurrent').val([ANALOG.amperage.toFixed(2)]);
}, 100, true); // 10 fps
/*
* Hide mixer section
*/
if (FC.isNewMixer()) {
$('.mixer').addClass("is-hidden");
}
GUI.content_ready(callback);
}
};

View file

@ -1,5 +1,4 @@
<div class="tab-configuration tab-mixer toolbar_fixed_bottom">
<div class="content_wrapper is-hidden" id="mixer-hidden-content"><p data-i18n="fcFirmwareUpdateRequired"></p></div>
<div class="content_wrapper" id="mixer-main-content">
<div class="tab_title" data-i18n="tabMixer">Mixer</div>
<!-- Top row -->

View file

@ -216,11 +216,6 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
function processHtml() {
if (!FC.isNewMixer()) {
$('#mixer-hidden-content').removeClass("is-hidden");
$('#mixer-main-content').remove();
}
$servoMixTable = $('#servo-mix-table');
$servoMixTableBody = $servoMixTable.find('tbody');
$motorMixTable = $('#motor-mix-table');

View file

@ -245,11 +245,7 @@ TABS.motors.initialize = function (callback) {
$motorsEnableTestMode.prop('checked', false);
$motorsEnableTestMode.prop('disabled', true);
if (FC.isNewMixer()) {
update_model(MIXER_CONFIG.appliedMixerPreset);
} else {
update_model(BF_CONFIG.mixerConfiguration);
}
// Always start with default/empty sensor data array, clean slate all
initSensorData();

View file

@ -643,7 +643,6 @@ OSD.constants = {
{
name: 'SAG_COMP_MAIN_BATT_VOLTAGE',
id: 53,
min_version: '2.0.0',
preview: osdMainBatteryPreview,
},
{
@ -654,13 +653,11 @@ OSD.constants = {
{
name: 'SAG_COMP_MAIN_BATT_CELL_VOLTAGE',
id: 54,
min_version: '2.0.0',
preview: FONT.symbol(SYM.BATT) + FONT.embed_dot('4.18') + FONT.symbol(SYM.VOLT)
},
{
name: 'POWER_SUPPLY_IMPEDANCE',
id: 55,
min_version: '2.0.0',
preview: ' 23' + FONT.symbol(SYM.MILLIOHM)
},
{
@ -671,13 +668,11 @@ OSD.constants = {
{
name: 'REMAINING_FLIGHT_TIME',
id: 48,
min_version: '2.0.0',
preview: FONT.symbol(SYM.FLY_M) + '10:35'
},
{
name: 'REMAINING_FLIGHT_DISTANCE',
id: 49,
min_version: '2.0.0',
preview: function(osd_data) {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
if (OSD.data.preferences.units === 0) {
@ -1025,7 +1020,6 @@ OSD.constants = {
{
name: 'PITCH_ANGLE',
id: 41,
min_version: '2.0.0',
preview: function () {
return FONT.symbol(SYM.PITCH_UP) + FONT.embed_dot(' 1.5');
},
@ -1033,7 +1027,6 @@ OSD.constants = {
{
name: 'ROLL_ANGLE',
id: 42,
min_version: '2.0.0',
preview: function () {
return FONT.symbol(SYM.ROLL_LEFT) + FONT.embed_dot('31.4');
},
@ -1196,7 +1189,6 @@ OSD.constants = {
{
name: 'HOME_HEADING_ERROR',
id: 50,
min_version: '2.0.0',
preview: FONT.symbol(SYM.HOME) + FONT.symbol(SYM.HEADING) + ' -10' + FONT.symbol(SYM.DEGREES)
},
{
@ -1246,7 +1238,6 @@ OSD.constants = {
{
name: 'WIND_SPEED_HORIZONTAL',
id: 46,
min_version: '2.0.0',
preview: function(osd_data) {
// 6 chars
var p = FONT.symbol(SYM.WIND_SPEED_HORIZONTAL) + FONT.symbol(SYM.DIRECTION + 1);
@ -1262,7 +1253,6 @@ OSD.constants = {
{
name: 'WIND_SPEED_VERTICAL',
id: 47,
min_version: '2.0.0',
preview: function(osd_data) {
// 6 chars
var p = FONT.symbol(SYM.WIND_SPEED_VERTICAL) + FONT.symbol(SYM.AH_DECORATION_UP);
@ -1278,13 +1268,11 @@ OSD.constants = {
{
name: 'CRUISE_HEADING_ERROR',
id: 51,
min_version: '2.0.0',
preview: FONT.symbol(SYM.HEADING) + ' 5' + FONT.symbol(SYM.DEGREES)
},
{
name: 'CRUISE_HEADING_ADJUSTMENT',
id: 52,
min_version: '2.0.0',
preview: FONT.symbol(SYM.HEADING) + ' -90' + FONT.symbol(SYM.DEGREES)
},
]
@ -1295,19 +1283,16 @@ OSD.constants = {
{
name: 'MAP_NORTH',
id: 43,
min_version: '2.0.0',
positionable: false,
},
{
name: 'MAP_TAKEOFF',
id: 44,
min_version: '2.0.0',
positionable: false,
},
{
name: 'RADAR',
id: 45,
min_version: '2.0.0',
positionable: false,
},
{
@ -1340,11 +1325,7 @@ OSD.constants = {
id: 10,
positionable: true,
preview: function(osd_data) {
var preview = 'CH:F7';
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) {
preview += ':1';
}
return preview;
return 'CH:F7:1';
},
},
{
@ -1375,140 +1356,117 @@ OSD.constants = {
{
name: 'LEVEL_PIDS',
id: 56,
min_version: '2.0.0',
preview: 'LEV 20 15 80'
},
{
name: 'POS_XY_PIDS',
id: 57,
min_version: '2.0.0',
preview: 'PXY 20 15 80'
},
{
name: 'POS_Z_PIDS',
id: 58,
min_version: '2.0.0',
preview: 'PZ 20 15 80'
},
{
name: 'VEL_XY_PIDS',
id: 59,
min_version: '2.0.0',
preview: 'VXY 20 15 80'
},
{
name: 'VEL_Z_PIDS',
id: 60,
min_version: '2.0.0',
preview: 'VZ 20 15 80'
},
{
name: 'HEADING_P',
id: 61,
min_version: '2.0.0',
preview: 'HP 20'
},
{
name: 'BOARD_ALIGNMENT_ROLL',
id: 62,
min_version: '2.0.0',
preview: 'AR 0'
},
{
name: 'BOARD_ALIGNMENT_PITCH',
id: 63,
min_version: '2.0.0',
preview: 'AP ' + FONT.embed_dot('1.0')
},
{
name: 'THROTTLE_EXPO',
id: 66,
min_version: '2.0.0',
preview: 'TEX 0'
},
{
name: 'STABILIZED_RC_EXPO',
id: 64,
min_version: '2.0.0',
preview: 'EXP 20'
},
{
name: 'STABILIZED_RC_YAW_EXPO',
id: 65,
min_version: '2.0.0',
preview: 'YEX 20'
},
{
name: 'STABILIZED_PITCH_RATE',
id: 67,
min_version: '2.0.0',
preview: 'SPR 20'
},
{
name: 'STABILIZED_ROLL_RATE',
id: 68,
min_version: '2.0.0',
preview: 'SRR 20'
},
{
name: 'STABILIZED_YAW_RATE',
id: 69,
min_version: '2.0.0',
preview: 'SYR 20'
},
{
name: 'MANUAL_RC_EXPO',
id: 70,
min_version: '2.0.0',
preview: 'MEX 20'
},
{
name: 'MANUAL_RC_YAW_EXPO',
id: 71,
min_version: '2.0.0',
preview: 'MYX 20'
},
{
name: 'MANUAL_PITCH_RATE',
id: 72,
min_version: '2.0.0',
preview: 'MPR 20'
},
{
name: 'MANUAL_ROLL_RATE',
id: 73,
min_version: '2.0.0',
preview: 'MRR 20'
},
{
name: 'MANUAL_YAW_RATE',
id: 74,
min_version: '2.0.0',
preview: 'MYR 20'
},
{
name: 'NAV_FW_CRUISE_THROTTLE',
id: 75,
min_version: '2.0.0',
preview: 'CRS 1500'
},
{
name: 'NAV_FW_PITCH_TO_THROTTLE',
id: 76,
min_version: '2.0.0',
preview: 'P2T 10'
},
{
name: 'FW_MIN_THROTTLE_DOWN_PITCH_ANGLE',
id: 77,
min_version: '2.0.0',
preview: '0TP ' + FONT.embed_dot('4.5')
},
]
},
{
name: 'osdGroupPIDOutputs',
min_version: '2.0.0',
items: [
{
name: 'FW_ALT_PID_OUTPUTS',
@ -1589,10 +1547,6 @@ OSD.get_item_preview = function(item) {
return preview;
}
OSD.use_layouts_api = function() {
return semver.gte(CONFIG.flightControllerVersion, '2.0.0');
};
OSD.reload = function(callback) {
OSD.initData();
var done = function() {
@ -1601,7 +1555,6 @@ OSD.reload = function(callback) {
callback();
}
};
if (OSD.use_layouts_api()) {
MSP.promise(MSPCodes.MSP2_INAV_OSD_LAYOUTS).then(function (resp) {
OSD.msp.decodeLayoutCounts(resp);
@ -1628,12 +1581,6 @@ OSD.reload = function(callback) {
});
});
});
} else {
MSP.promise(MSPCodes.MSP_OSD_CONFIG).then(function (data) {
OSD.msp.decode(data);
done();
});
}
};
OSD.updateSelectedLayout = function(new_layout) {
@ -1655,33 +1602,21 @@ OSD.updateDisplaySize = function () {
};
OSD.saveAlarms = function(callback) {
// Before the layouts API was introduced, config and alarms were saved
// with the same MSP cmd.
if (!OSD.use_layouts_api()) {
return OSD.saveConfig(callback);
}
var data = OSD.msp.encodeAlarms();
let data = OSD.msp.encodeAlarms();
return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_ALARMS, data).then(callback);
}
OSD.saveConfig = function(callback) {
if (OSD.use_layouts_api()) {
return OSD.saveAlarms(function () {
var data = OSD.msp.encodePreferences();
return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_PREFERENCES, data).then(callback);
});
}
return MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, OSD.msp.encodeOther()).then(callback);
};
OSD.saveItem = function(item, callback) {
var pos = OSD.data.items[item.id];
if (OSD.use_layouts_api()) {
var data = OSD.msp.encodeLayoutItem(OSD.data.selected_layout, item, pos);
let pos = OSD.data.items[item.id];
let data = OSD.msp.encodeLayoutItem(OSD.data.selected_layout, item, pos);
return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_LAYOUT_ITEM, data).then(callback);
}
var data = OSD.msp.encodeItem(item.id, pos);
return MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, data).then(callback);
};
//noinspection JSUnusedLocalSymbols

View file

@ -492,20 +492,6 @@
<div class="helpicon cf_tip" data-i18n_title="yawPLimitHelp"></div>
</td>
</tr>
<tr class="deprecated-v2_0">
<th data-i18n="rollPitchItermIgnoreRate"></th>
<td >
<input type="number" id="rollPitchItermIgnoreRate" class="rate-tpa_input" step="5" min="15" max="1000" />
<div class="helpicon cf_tip" data-i18n_title="rollPitchItermIgnoreRateHelp"></div>
</td>
</tr>
<tr class="deprecated-v2_0">
<th data-i18n="yawItermIgnoreRate"></th>
<td >
<input type="number" id="yawItermIgnoreRate" class="rate-tpa_input" step="5" min="15" max="1000" />
<div class="helpicon cf_tip" data-i18n_title="yawItermIgnoreRateHelp"></div>
</td>
</tr>
</table>
</div>
<div class="cf_column half">

View file

@ -135,8 +135,6 @@ TABS.pid_tuning.initialize = function (callback) {
$accSoftLpfHz = $('#accSoftLpfHz'),
$dtermLpfHz = $('#dtermLpfHz'),
$yawLpfHz = $('#yawLpfHz'),
$rollPitchItermIgnoreRate = $('#rollPitchItermIgnoreRate'),
$yawItermIgnoreRate = $('#yawItermIgnoreRate'),
$axisAccelerationLimitRollPitch = $('#axisAccelerationLimitRollPitch'),
$axisAccelerationLimitYaw = $('#axisAccelerationLimitYaw');
@ -147,8 +145,6 @@ TABS.pid_tuning.initialize = function (callback) {
$accSoftLpfHz.val(INAV_PID_CONFIG.accSoftLpfHz);
$dtermLpfHz.val(FILTER_CONFIG.dtermLpfHz);
$yawLpfHz.val(FILTER_CONFIG.yawLpfHz);
$rollPitchItermIgnoreRate.val(PID_ADVANCED.rollPitchItermIgnoreRate);
$yawItermIgnoreRate.val(PID_ADVANCED.yawItermIgnoreRate);
$axisAccelerationLimitRollPitch.val(PID_ADVANCED.axisAccelerationLimitRollPitch * 10);
$axisAccelerationLimitYaw.val(PID_ADVANCED.axisAccelerationLimitYaw * 10);
@ -180,14 +176,6 @@ TABS.pid_tuning.initialize = function (callback) {
FILTER_CONFIG.yawLpfHz = parseInt($yawLpfHz.val(), 10);
});
$rollPitchItermIgnoreRate.change(function () {
PID_ADVANCED.rollPitchItermIgnoreRate = parseInt($rollPitchItermIgnoreRate.val(), 10);
});
$yawItermIgnoreRate.change(function () {
PID_ADVANCED.yawItermIgnoreRate = parseInt($yawItermIgnoreRate.val(), 10);
});
$axisAccelerationLimitRollPitch.change(function () {
PID_ADVANCED.axisAccelerationLimitRollPitch = Math.round(parseInt($axisAccelerationLimitRollPitch.val(), 10) / 10);
});
@ -196,12 +184,6 @@ TABS.pid_tuning.initialize = function (callback) {
PID_ADVANCED.axisAccelerationLimitYaw = Math.round(parseInt($axisAccelerationLimitYaw.val(), 10) / 10);
});
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
$('.deprecated-v2_0').hide();
} else {
$('.deprecated-v2_0').show();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
$('.requires-v2_1').show();
} else {

View file

@ -72,14 +72,6 @@ TABS.receiver.initialize = function (callback) {
// translate to user-selected language
localize();
if (semver.lt(CONFIG.flightControllerVersion, '1.9.1')) {
rcmap_options = $('select[name="rcmap_helper"] option');
for (i = 0; i < rcmap_options.length; ++i) {
option = rcmap_options[i];
option.setAttribute("value", option.getAttribute("value") + "5678");
}
}
// fill in data from RC_tuning
$('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2));
$('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2));

View file

@ -211,7 +211,7 @@ TABS.sensors.initialize = function (callback) {
checkboxes.eq(4).prop('disabled', true);
}
if (semver.lt(CONFIG.flightControllerVersion, "1.9.1") || (!bit_check(CONFIG.activeSensors, 6))) { // airspeed
if (!bit_check(CONFIG.activeSensors, 6)) { // airspeed
checkboxes.eq(5).prop('disabled', true);
}

View file

@ -235,16 +235,12 @@ TABS.setup.initialize3D = function () {
// load the model including materials
if (useWebGlRenderer) {
if (FC.isNewMixer()) {
if (MIXER_CONFIG.appliedMixerPreset === -1) {
model_file = 'custom';
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("mixerNotConfigured") + "</strong></span>");
} else {
model_file = helper.mixer.getById(MIXER_CONFIG.appliedMixerPreset).model;
}
} else {
model_file = helper.mixer.getById(BF_CONFIG.mixerConfiguration).model;
}
} else {
model_file = 'fallback'
}