mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-25 17:25:16 +03:00
chore: add eslint
* add eslint with space rules to cover what sonarcloud doesn't * run lint in travis * add eslint vue config
This commit is contained in:
parent
bc47878b30
commit
d396d97e5e
33 changed files with 884 additions and 188 deletions
|
@ -2,7 +2,7 @@
|
|||
|
||||
/**
|
||||
* Caching of previously downloaded firmwares and release descriptions
|
||||
*
|
||||
*
|
||||
* Depends on LRUMap for which the docs can be found here:
|
||||
* https://github.com/rsms/js-lru
|
||||
*/
|
||||
|
@ -48,7 +48,7 @@ let FirmwareCache = (function () {
|
|||
}
|
||||
|
||||
/**
|
||||
* @param {Function} callback
|
||||
* @param {Function} callback
|
||||
*/
|
||||
function load(callback) {
|
||||
chrome.storage.local.get(CACHEKEY, obj => {
|
||||
|
@ -92,7 +92,7 @@ let FirmwareCache = (function () {
|
|||
};
|
||||
|
||||
/**
|
||||
* @param {Descriptor} release
|
||||
* @param {Descriptor} release
|
||||
* @returns {string} A key used to store a release in the journal
|
||||
*/
|
||||
function keyOf(release) {
|
||||
|
@ -100,7 +100,7 @@ let FirmwareCache = (function () {
|
|||
}
|
||||
|
||||
/**
|
||||
* @param {string} key
|
||||
* @param {string} key
|
||||
* @returns {string} A key for storing cached data for a release
|
||||
*/
|
||||
function withCachePrefix(key) {
|
||||
|
@ -198,11 +198,11 @@ let FirmwareCache = (function () {
|
|||
chrome.storage.local.remove(cacheKeys);
|
||||
});
|
||||
journal.clear();
|
||||
JournalStorage.persist(journal.toJSON());
|
||||
JournalStorage.persist(journal.toJSON());
|
||||
}
|
||||
|
||||
/**
|
||||
* @param {Descriptor} release
|
||||
* @param {Descriptor} release
|
||||
*/
|
||||
function onPutToCache(release) {
|
||||
if (typeof onPutToCacheCallback === "function") {
|
||||
|
@ -212,7 +212,7 @@ let FirmwareCache = (function () {
|
|||
}
|
||||
|
||||
/**
|
||||
* @param {Descriptor} release
|
||||
* @param {Descriptor} release
|
||||
*/
|
||||
function onRemoveFromCache(release) {
|
||||
if (typeof onRemoveFromCacheCallback === "function") {
|
||||
|
@ -222,7 +222,7 @@ let FirmwareCache = (function () {
|
|||
}
|
||||
|
||||
/**
|
||||
* @param {Array} entries
|
||||
* @param {Array} entries
|
||||
*/
|
||||
function onEntriesLoaded(entries) {
|
||||
let pairs = [];
|
||||
|
|
|
@ -106,14 +106,14 @@ TuningSliders.initPidSlidersPosition = function() {
|
|||
};
|
||||
|
||||
TuningSliders.initGyroFilterSliderPosition = function() {
|
||||
this.gyroFilterSliderValue = Math.round((FC.FILTER_CONFIG.gyro_lowpass_dyn_min_hz + FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz + FC.FILTER_CONFIG.gyro_lowpass2_hz) /
|
||||
this.gyroFilterSliderValue = Math.round((FC.FILTER_CONFIG.gyro_lowpass_dyn_min_hz + FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz + FC.FILTER_CONFIG.gyro_lowpass2_hz) /
|
||||
(this.FILTER_DEFAULT.gyro_lowpass_dyn_min_hz + this.FILTER_DEFAULT.gyro_lowpass_dyn_max_hz + this.FILTER_DEFAULT.gyro_lowpass2_hz) * 100) / 100;
|
||||
$('output[name="tuningGyroFilterSlider-number"]').val(this.gyroFilterSliderValue);
|
||||
$('#tuningGyroFilterSlider').val(this.downscaleSliderValue(this.gyroFilterSliderValue));
|
||||
};
|
||||
|
||||
TuningSliders.initDTermFilterSliderPosition = function() {
|
||||
this.dtermFilterSliderValue = Math.round((FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz + FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz + FC.FILTER_CONFIG.dterm_lowpass2_hz) /
|
||||
this.dtermFilterSliderValue = Math.round((FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz + FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz + FC.FILTER_CONFIG.dterm_lowpass2_hz) /
|
||||
(this.FILTER_DEFAULT.dterm_lowpass_dyn_min_hz + this.FILTER_DEFAULT.dterm_lowpass_dyn_max_hz + this.FILTER_DEFAULT.dterm_lowpass2_hz) * 100) / 100;
|
||||
$('output[name="tuningDTermFilterSlider-number"]').val(this.dtermFilterSliderValue);
|
||||
$('#tuningDTermFilterSlider').val(this.downscaleSliderValue(this.dtermFilterSliderValue));
|
||||
|
|
|
@ -57,4 +57,4 @@ function huffmanDecodeBuf(inBuf, inBufCharacterCount, huffmanTree, huffmanLenInd
|
|||
}
|
||||
|
||||
return new Uint8Array(outBuf);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -60,7 +60,7 @@ DataView.prototype.read8 = function() {
|
|||
DataView.prototype.read16 = function() {
|
||||
this.offset += 2;
|
||||
if (this.byteLength >= this.offset) {
|
||||
return this.getInt16(this.offset-2, 1);
|
||||
return this.getInt16(this.offset-2, 1);
|
||||
} else {
|
||||
return null;
|
||||
}
|
||||
|
@ -69,7 +69,7 @@ DataView.prototype.read16 = function() {
|
|||
DataView.prototype.read32 = function() {
|
||||
this.offset += 4;
|
||||
if (this.byteLength >= this.offset) {
|
||||
return this.getInt32(this.offset-4, 1);
|
||||
return this.getInt32(this.offset-4, 1);
|
||||
} else {
|
||||
return null;
|
||||
}
|
||||
|
|
|
@ -54,7 +54,7 @@ const MSP = {
|
|||
listeners: [],
|
||||
|
||||
JUMBO_FRAME_SIZE_LIMIT: 255,
|
||||
|
||||
|
||||
read: function (readInfo) {
|
||||
const data = new Uint8Array(readInfo.data);
|
||||
|
||||
|
@ -231,7 +231,7 @@ const MSP = {
|
|||
}
|
||||
},
|
||||
clearListeners: function() {
|
||||
this.listeners = [];
|
||||
this.listeners = [];
|
||||
},
|
||||
crc8_dvb_s2: function(crc, ch) {
|
||||
crc ^= ch;
|
||||
|
|
|
@ -92,7 +92,7 @@ const MSPCodes = {
|
|||
MSP_ANALOG: 110,
|
||||
MSP_RC_TUNING: 111,
|
||||
MSP_PID: 112,
|
||||
//MSP_BOX: 113, // DEPRECATED
|
||||
//MSP_BOX: 113, // DEPRECATED
|
||||
MSP_MISC: 114, // DEPRECATED
|
||||
MSP_BOXNAMES: 116,
|
||||
MSP_PIDNAMES: 117,
|
||||
|
|
|
@ -22,31 +22,31 @@ MSPConnectorImpl.prototype.connect = function (port, baud, onConnectCallback, on
|
|||
const disconnectAndCleanup = function() {
|
||||
serial.disconnect(function(result) {
|
||||
console.log('Disconnected');
|
||||
|
||||
|
||||
MSP.clearListeners();
|
||||
|
||||
|
||||
self.onTimeoutCallback();
|
||||
});
|
||||
|
||||
|
||||
MSP.disconnect_cleanup();
|
||||
};
|
||||
|
||||
|
||||
FC.resetState();
|
||||
|
||||
|
||||
// disconnect after 10 seconds with error if we don't get IDENT data
|
||||
GUI.timeout_add('msp_connector', function () {
|
||||
if (!CONFIGURATOR.connectionValid) {
|
||||
GUI.log(i18n.getMessage('noConfigurationReceived'));
|
||||
|
||||
|
||||
disconnectAndCleanup();
|
||||
}
|
||||
}, 10000);
|
||||
|
||||
serial.onReceive.addListener(read_serial);
|
||||
|
||||
|
||||
const mspHelper = new MspHelper();
|
||||
MSP.listen(mspHelper.process_data.bind(mspHelper));
|
||||
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
|
||||
CONFIGURATOR.connectionValid = true;
|
||||
|
||||
|
@ -64,13 +64,13 @@ MSPConnectorImpl.prototype.connect = function (port, baud, onConnectCallback, on
|
|||
|
||||
MSPConnectorImpl.prototype.disconnect = function(onDisconnectCallback) {
|
||||
self.onDisconnectCallback = onDisconnectCallback;
|
||||
|
||||
|
||||
serial.disconnect(function (result) {
|
||||
MSP.clearListeners();
|
||||
console.log('Disconnected');
|
||||
|
||||
|
||||
self.onDisconnectCallback(result);
|
||||
});
|
||||
|
||||
|
||||
MSP.disconnect_cleanup();
|
||||
};
|
||||
|
|
|
@ -1008,7 +1008,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
FC.RX_CONFIG.airModeActivateThreshold = 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_FAILSAFE_CONFIG:
|
||||
|
@ -1048,7 +1048,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
let gyroUse32kHz = data.readU8();
|
||||
if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) {
|
||||
FC.PID_ADVANCED_CONFIG.gyroUse32kHz = gyroUse32kHz;
|
||||
}
|
||||
}
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) {
|
||||
FC.PID_ADVANCED_CONFIG.motorPwmInversion = data.readU8();
|
||||
FC.SENSOR_ALIGNMENT.gyro_to_use = data.readU8(); // We don't want to double up on storing this state
|
||||
|
@ -1162,7 +1162,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
FC.ADVANCED_TUNING.feedforwardPitch = data.readU16();
|
||||
FC.ADVANCED_TUNING.feedforwardYaw = data.readU16();
|
||||
FC.ADVANCED_TUNING.antiGravityMode = data.readU8();
|
||||
|
||||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) {
|
||||
FC.ADVANCED_TUNING.dMinRoll = data.readU8();
|
||||
FC.ADVANCED_TUNING.dMinPitch = data.readU8();
|
||||
|
@ -1588,7 +1588,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
dataView : new DataView(data.buffer, data.offset, payloadSize),
|
||||
callbacks : [],
|
||||
};
|
||||
|
||||
|
||||
self.process_data(currentDataHandler);
|
||||
|
||||
data.offset += payloadSize;
|
||||
|
@ -1598,12 +1598,12 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
if (hasReturnedSomeCommand) {
|
||||
// Send again MSP messages missing, the buffer in the FC was too small
|
||||
if (self.mspMultipleCache.length > 0) {
|
||||
|
||||
|
||||
const partialBuffer = [];
|
||||
for (let i = 0; i < self.mspMultipleCache.length; i++) {
|
||||
partialBuffer.push8(self.mspMultipleCache[i]);
|
||||
}
|
||||
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_MULTIPLE_MSP, partialBuffer, false, dataHandler.callbacks);
|
||||
dataHandler.callbacks = [];
|
||||
}
|
||||
|
@ -2110,7 +2110,7 @@ MspHelper.prototype.crunch = function(code) {
|
|||
.push8(FC.ADVANCED_TUNING.dMinAdvance)
|
||||
.push8(FC.ADVANCED_TUNING.useIntegratedYaw)
|
||||
.push8(FC.ADVANCED_TUNING.integratedYawRelax);
|
||||
|
||||
|
||||
if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) {
|
||||
buffer.push8(FC.ADVANCED_TUNING.itermRelaxCutoff);
|
||||
|
||||
|
@ -2512,7 +2512,7 @@ MspHelper.prototype.sendVoltageConfig = function(onCompleteCallback) {
|
|||
let nextFunction = send_next_voltage_config;
|
||||
|
||||
let configIndex = 0;
|
||||
|
||||
|
||||
if (FC.VOLTAGE_METER_CONFIGS.length == 0) {
|
||||
onCompleteCallback();
|
||||
} else {
|
||||
|
@ -2543,7 +2543,7 @@ MspHelper.prototype.sendCurrentConfig = function(onCompleteCallback) {
|
|||
let nextFunction = send_next_current_config;
|
||||
|
||||
let configIndex = 0;
|
||||
|
||||
|
||||
if (FC.CURRENT_METER_CONFIGS.length == 0) {
|
||||
onCompleteCallback();
|
||||
} else {
|
||||
|
|
|
@ -25,8 +25,8 @@ function adjustBoxNameIfPeripheralWithModeID(modeId, defaultName) {
|
|||
default:
|
||||
return defaultName;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return defaultName;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -829,7 +829,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
|
|||
|
||||
if (data[4] == self.state.dfuDNBUSY) {
|
||||
|
||||
//
|
||||
//
|
||||
// H743 Rev.V (probably other H7 Rev.Vs also) remains in dfuDNBUSY state after the specified delay time.
|
||||
// STM32CubeProgrammer deals with behavior with an undocumented procedure as follows.
|
||||
// 1. Issue DFU_CLRSTATUS, which ends up with (14,10) = (errUNKNOWN, dfuERROR)
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
var ReleaseChecker = function (releaseName, releaseUrl) {
|
||||
var self = this;
|
||||
|
||||
|
||||
self._releaseName = releaseName;
|
||||
self._releaseDataTag = `${self._releaseName}ReleaseData`;
|
||||
self._releaseLastUpdateTag = `${self._releaseName}ReleaseLastUpdate`
|
||||
|
@ -23,7 +23,7 @@ ReleaseChecker.prototype.loadReleaseData = function (processFunction) {
|
|||
data[self._releaseDataTag] = releaseData
|
||||
data[self._releaseLastUpdateTag] = releaseDataTimestamp
|
||||
chrome.storage.local.set(data, function () {});
|
||||
|
||||
|
||||
self._processReleaseData(releaseData, processFunction);
|
||||
}).fail(function (data) {
|
||||
var message = '';
|
||||
|
@ -31,7 +31,7 @@ ReleaseChecker.prototype.loadReleaseData = function (processFunction) {
|
|||
message = data['responseJSON'].message;
|
||||
}
|
||||
GUI.log(i18n.getMessage('releaseCheckFailed',[self._releaseName,message]));
|
||||
|
||||
|
||||
self._processReleaseData(cacheReleaseData, processFunction);
|
||||
});
|
||||
} else {
|
||||
|
@ -43,7 +43,7 @@ ReleaseChecker.prototype.loadReleaseData = function (processFunction) {
|
|||
}
|
||||
});
|
||||
}
|
||||
|
||||
|
||||
|
||||
ReleaseChecker.prototype._processReleaseData = function (releaseData, processFunction) {
|
||||
if (releaseData) {
|
||||
|
|
|
@ -702,7 +702,7 @@ function update_live_status() {
|
|||
const max = FC.BATTERY_CONFIG.vbatmaxcellvoltage * nbCells;
|
||||
const warn = FC.BATTERY_CONFIG.vbatwarningcellvoltage * nbCells;
|
||||
|
||||
const NO_BATTERY_VOLTAGE_MAXIMUM = 1.8; // Maybe is better to add a call to MSP_BATTERY_STATE but is not available for all versions
|
||||
const NO_BATTERY_VOLTAGE_MAXIMUM = 1.8; // Maybe is better to add a call to MSP_BATTERY_STATE but is not available for all versions
|
||||
|
||||
if (FC.ANALOG.voltage < min && FC.ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM) {
|
||||
$(".battery-status").addClass('state-empty').removeClass('state-ok').removeClass('state-warning');
|
||||
|
|
|
@ -6,7 +6,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
const self = this;
|
||||
GUI.active_tab_ref = this;
|
||||
GUI.active_tab = 'adjustments';
|
||||
|
||||
|
||||
function get_adjustment_ranges() {
|
||||
MSP.send_message(MSPCodes.MSP_ADJUSTMENT_RANGES, false, false, get_box_ids);
|
||||
}
|
||||
|
@ -29,14 +29,14 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
const template = $('#tab-adjustments-templates .adjustments .adjustment');
|
||||
const newAdjustment = template.clone();
|
||||
|
||||
|
||||
$(newAdjustment).attr('id', 'adjustment-' + adjustmentIndex);
|
||||
$(newAdjustment).data('index', adjustmentIndex);
|
||||
|
||||
//
|
||||
// update selected slot
|
||||
//
|
||||
|
||||
|
||||
if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_42)) {
|
||||
const adjustmentList = $(newAdjustment).find('.adjustmentSlot .slot');
|
||||
adjustmentList.val(adjustmentRange.slotIndex);
|
||||
|
@ -45,7 +45,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
//
|
||||
// populate source channel select box
|
||||
//
|
||||
|
||||
|
||||
const channelList = $(newAdjustment).find('.channelInfo .channel');
|
||||
const channelOptionTemplate = $(channelList).find('option');
|
||||
channelOptionTemplate.remove();
|
||||
|
@ -85,7 +85,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
//
|
||||
// configure range
|
||||
//
|
||||
|
||||
|
||||
const channel_range = {
|
||||
'min': [ 900 ],
|
||||
'max': [ 2100 ]
|
||||
|
@ -119,16 +119,16 @@ TABS.adjustments.initialize = function (callback) {
|
|||
density: 4,
|
||||
stepped: true
|
||||
});
|
||||
|
||||
|
||||
//
|
||||
// add the enable/disable behavior
|
||||
//
|
||||
|
||||
|
||||
const enableElement = $(newAdjustment).find('.enable');
|
||||
$(enableElement).data('adjustmentElement', newAdjustment);
|
||||
$(enableElement).change(function() {
|
||||
const adjustmentElement = $(this).data('adjustmentElement');
|
||||
if ($(this).prop("checked")) {
|
||||
if ($(this).prop("checked")) {
|
||||
$(adjustmentElement).find(':input').prop("disabled", false);
|
||||
$(adjustmentElement).find('.channel-slider').removeAttr("disabled");
|
||||
rangeElement = $(adjustmentElement).find('.range .channel-slider');
|
||||
|
@ -145,10 +145,10 @@ TABS.adjustments.initialize = function (callback) {
|
|||
// keep this element enabled
|
||||
$(this).prop("disabled", false);
|
||||
});
|
||||
|
||||
const isEnabled = (adjustmentRange?.range?.start !== adjustmentRange?.range?.end);
|
||||
|
||||
const isEnabled = (adjustmentRange?.range?.start !== adjustmentRange?.range?.end);
|
||||
$(enableElement).prop("checked", isEnabled).change();
|
||||
|
||||
|
||||
return newAdjustment;
|
||||
}
|
||||
|
||||
|
@ -163,7 +163,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
const newAdjustment = addAdjustment(adjustmentIndex, FC.ADJUSTMENT_RANGES[adjustmentIndex], auxChannelCount);
|
||||
modeTableBodyElement.append(newAdjustment);
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) {
|
||||
$('.tab-adjustments .adjustmentSlotsHelp').hide();
|
||||
|
@ -179,9 +179,9 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
// update internal data structures based on current UI elements
|
||||
const requiredAdjustmentRangeCount = FC.ADJUSTMENT_RANGES.length;
|
||||
|
||||
|
||||
FC.ADJUSTMENT_RANGES = [];
|
||||
|
||||
|
||||
const defaultAdjustmentRange = {
|
||||
slotIndex: 0,
|
||||
auxChannelIndex: 0,
|
||||
|
@ -195,7 +195,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
$('.tab-adjustments .adjustments .adjustment').each(function () {
|
||||
const adjustmentElement = $(this);
|
||||
|
||||
|
||||
if ($(adjustmentElement).find('.enable').prop("checked")) {
|
||||
const rangeValues = $(this).find('.range .channel-slider').val();
|
||||
let slotIndex = 0;
|
||||
|
@ -218,16 +218,16 @@ TABS.adjustments.initialize = function (callback) {
|
|||
FC.ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
|
||||
}
|
||||
});
|
||||
|
||||
|
||||
for (let adjustmentRangeIndex = FC.ADJUSTMENT_RANGES.length; adjustmentRangeIndex < requiredAdjustmentRangeCount; adjustmentRangeIndex++) {
|
||||
FC.ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
|
||||
}
|
||||
|
||||
|
||||
//
|
||||
// send data to FC
|
||||
//
|
||||
mspHelper.sendAdjustmentRanges(save_to_eeprom);
|
||||
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(i18n.getMessage('adjustmentsEepromSaved'));
|
||||
|
@ -243,13 +243,13 @@ TABS.adjustments.initialize = function (callback) {
|
|||
channelPosition = 2100;
|
||||
}
|
||||
const percentage = (channelPosition - 900) / (2100-900) * 100;
|
||||
|
||||
|
||||
$('.adjustments .adjustment').each( function () {
|
||||
const auxChannelCandidateIndex = $(this).find('.channel').val();
|
||||
if (auxChannelCandidateIndex != auxChannelIndex) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
$(this).find('.range .marker').css('left', percentage + '%');
|
||||
});
|
||||
}
|
||||
|
@ -264,7 +264,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
for (let auxChannelIndex = 0; auxChannelIndex < auxChannelCount; auxChannelIndex++) {
|
||||
update_marker(auxChannelIndex, FC.RC.channels[auxChannelIndex + 4]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// update ui instantly on first load
|
||||
|
@ -306,7 +306,7 @@ TABS.adjustments.adjust_template = function () {
|
|||
for (let i = 0; i < elementsNumber; i++) {
|
||||
selectFunction.append(new Option(i18n.getMessage('adjustmentsFunction' + i), i));
|
||||
}
|
||||
|
||||
|
||||
// For 1.40, the D Setpoint has been replaced, so we replace it with the correct values
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) {
|
||||
|
||||
|
|
|
@ -8,7 +8,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
let prevChannelsValues = null;
|
||||
|
||||
function get_mode_ranges() {
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false,
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false,
|
||||
semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41) ? get_mode_ranges_extra : get_box_ids);
|
||||
}
|
||||
|
||||
|
@ -41,17 +41,17 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
function createMode(modeIndex, modeId) {
|
||||
const modeTemplate = $('#tab-auxiliary-templates .mode');
|
||||
const newMode = modeTemplate.clone();
|
||||
|
||||
let modeName = FC.AUX_CONFIG[modeIndex];
|
||||
|
||||
let modeName = FC.AUX_CONFIG[modeIndex];
|
||||
// Adjust the name of the box if a peripheral is selected
|
||||
modeName = adjustBoxNameIfPeripheralWithModeID(modeId, modeName);
|
||||
|
||||
$(newMode).attr('id', 'mode-' + modeIndex);
|
||||
$(newMode).find('.name').text(modeName);
|
||||
|
||||
|
||||
$(newMode).data('index', modeIndex);
|
||||
$(newMode).data('id', modeId);
|
||||
|
||||
|
||||
$(newMode).find('.name').data('modeElement', newMode);
|
||||
$(newMode).find('a.addRange').data('modeElement', newMode);
|
||||
$(newMode).find('a.addLink').data('modeElement', newMode);
|
||||
|
@ -61,7 +61,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
$(newMode).find('.addLink').hide();
|
||||
}
|
||||
|
||||
return newMode;
|
||||
return newMode;
|
||||
}
|
||||
|
||||
function configureLogicList(template) {
|
||||
|
@ -74,7 +74,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
logicOption.text(i18n.getMessage('auxiliaryModeLogicOR'));
|
||||
logicOption.val(0);
|
||||
logicList.append(logicOption);
|
||||
|
||||
|
||||
if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)){
|
||||
logicOption = logicOptionTemplate.clone();
|
||||
logicOption.text(i18n.getMessage('auxiliaryModeLogicAND'));
|
||||
|
@ -83,10 +83,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
logicOptionTemplate.val(0);
|
||||
}
|
||||
|
||||
|
||||
function configureRangeTemplate(auxChannelCount) {
|
||||
const rangeTemplate = $('#tab-auxiliary-templates .range');
|
||||
|
||||
|
||||
const channelList = $(rangeTemplate).find('.channel');
|
||||
const channelOptionTemplate = $(channelList).find('option');
|
||||
channelOptionTemplate.remove();
|
||||
|
@ -105,17 +105,17 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
channelOptionTemplate.val(-1);
|
||||
|
||||
|
||||
configureLogicList(rangeTemplate);
|
||||
}
|
||||
|
||||
|
||||
function configureLinkTemplate() {
|
||||
const linkTemplate = $('#tab-auxiliary-templates .link');
|
||||
|
||||
|
||||
const linkList = $(linkTemplate).find('.linkedTo');
|
||||
const linkOptionTemplate = $(linkList).find('option');
|
||||
linkOptionTemplate.remove();
|
||||
|
||||
|
||||
// set up a blank option in place of ARM
|
||||
let linkOption = linkOptionTemplate.clone();
|
||||
linkOption.text("");
|
||||
|
@ -130,10 +130,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
linkOptionTemplate.val(0);
|
||||
|
||||
|
||||
configureLogicList(linkTemplate);
|
||||
}
|
||||
|
||||
|
||||
function addRangeToMode(modeElement, auxChannelIndex, modeLogic, range) {
|
||||
const modeIndex = $(modeElement).data('index');
|
||||
const modeRanges = $(modeElement).find('.ranges');
|
||||
|
@ -142,14 +142,14 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
'min': [ 900 ],
|
||||
'max': [ 2100 ]
|
||||
};
|
||||
|
||||
|
||||
let rangeValues = [1300, 1700]; // matches MultiWii default values for the old checkbox MID range.
|
||||
if (range !== undefined) {
|
||||
rangeValues = [range.start, range.end];
|
||||
}
|
||||
|
||||
const rangeIndex = modeRanges.children().length;
|
||||
|
||||
|
||||
let rangeElement = $('#tab-auxiliary-templates .range').clone();
|
||||
rangeElement.attr('id', 'mode-' + modeIndex + '-range-' + rangeIndex);
|
||||
modeRanges.append(rangeElement);
|
||||
|
@ -159,7 +159,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
} else if (rangeIndex == 1) {
|
||||
modeRanges.children().eq(0).find('.logic').show();
|
||||
}
|
||||
|
||||
|
||||
$(rangeElement).find('.channel-slider').noUiSlider({
|
||||
start: rangeValues,
|
||||
behaviour: 'snap-drag',
|
||||
|
@ -186,7 +186,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
density: 4,
|
||||
stepped: true
|
||||
});
|
||||
|
||||
|
||||
$(rangeElement).find('.deleteRange').data('rangeElement', rangeElement);
|
||||
$(rangeElement).find('.deleteRange').data('modeElement', modeElement);
|
||||
|
||||
|
@ -195,9 +195,9 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
rangeElement = $(this).data('rangeElement');
|
||||
|
||||
rangeElement.remove();
|
||||
|
||||
|
||||
const siblings = $(modeElement).find('.ranges').children();
|
||||
|
||||
|
||||
if (siblings.length == 1) {
|
||||
siblings.eq(0).find('.logic').hide();
|
||||
}
|
||||
|
@ -236,9 +236,9 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
linkElement = $(this).data('linkElement');
|
||||
|
||||
linkElement.remove();
|
||||
|
||||
|
||||
const siblings = $(modeElement).find('.ranges').children();
|
||||
|
||||
|
||||
if (siblings.length == 1) {
|
||||
siblings.eq(0).find('.logic').hide();
|
||||
}
|
||||
|
@ -256,11 +256,11 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
|
||||
const modeTableBodyElement = $('.tab-auxiliary .modes');
|
||||
for (let modeIndex = 0; modeIndex < FC.AUX_CONFIG.length; modeIndex++) {
|
||||
|
||||
|
||||
const modeId = FC.AUX_CONFIG_IDS[modeIndex];
|
||||
const newMode = createMode(modeIndex, modeId);
|
||||
modeTableBodyElement.append(newMode);
|
||||
|
||||
|
||||
// generate ranges from the supplied AUX names and MODE_RANGES[_EXTRA] data
|
||||
// skip linked modes for now
|
||||
for (let modeRangeIndex = 0; modeRangeIndex < FC.MODE_RANGES.length; modeRangeIndex++) {
|
||||
|
@ -274,7 +274,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) {
|
||||
modeRangeExtra = FC.MODE_RANGES_EXTRA[modeRangeIndex];
|
||||
}
|
||||
|
||||
|
||||
if (modeRange.id != modeId || modeRangeExtra.id != modeId) {
|
||||
continue;
|
||||
}
|
||||
|
@ -292,19 +292,19 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
$('a.addRange').click(function () {
|
||||
const modeElement = $(this).data('modeElement');
|
||||
// auto select AUTO option; default to 'OR' logic
|
||||
addRangeToMode(modeElement, -1, 0);
|
||||
});
|
||||
|
||||
|
||||
$('a.addLink').click(function () {
|
||||
const modeElement = $(this).data('modeElement');
|
||||
// default to 'OR' logic and no link selected
|
||||
addLinkedToMode(modeElement, 0, 0);
|
||||
});
|
||||
|
||||
|
||||
// translate to user-selected language
|
||||
i18n.localizePage();
|
||||
|
||||
|
@ -312,17 +312,17 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
$('a.save').click(function () {
|
||||
|
||||
// update internal data structures based on current UI elements
|
||||
|
||||
|
||||
// we must send this many back to the FC - overwrite all of the old ones to be sure.
|
||||
const requiredModesRangeCount = FC.MODE_RANGES.length;
|
||||
|
||||
|
||||
FC.MODE_RANGES = [];
|
||||
FC.MODE_RANGES_EXTRA = [];
|
||||
|
||||
|
||||
$('.tab-auxiliary .modes .mode').each(function () {
|
||||
const modeElement = $(this);
|
||||
const modeId = modeElement.data('id');
|
||||
|
||||
|
||||
$(modeElement).find('.range').each(function() {
|
||||
const rangeValues = $(this).find('.channel-slider').val();
|
||||
const modeRange = {
|
||||
|
@ -368,7 +368,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
});
|
||||
|
||||
|
||||
for (let modeRangeIndex = FC.MODE_RANGES.length; modeRangeIndex < requiredModesRangeCount; modeRangeIndex++) {
|
||||
const defaultModeRange = {
|
||||
id: 0,
|
||||
|
@ -400,7 +400,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
|
||||
|
||||
|
||||
function limit_channel(channelPosition) {
|
||||
if (channelPosition < 900) {
|
||||
channelPosition = 900;
|
||||
|
@ -409,16 +409,16 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
return channelPosition;
|
||||
}
|
||||
|
||||
|
||||
function update_marker(auxChannelIndex, channelPosition) {
|
||||
const percentage = (channelPosition - 900) / (2100-900) * 100;
|
||||
|
||||
|
||||
$('.modes .ranges .range').each( function () {
|
||||
const auxChannelCandidateIndex = $(this).find('.channel').val();
|
||||
if (auxChannelCandidateIndex !== auxChannelIndex) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
$(this).find('.marker').css('left', percentage + '%');
|
||||
});
|
||||
}
|
||||
|
@ -437,7 +437,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
modeElement.removeClass('off').removeClass('on').removeClass('disabled');
|
||||
continue;
|
||||
}
|
||||
|
||||
|
||||
if (bit_check(FC.CONFIG.mode, i)) {
|
||||
$('.mode .name').eq(i).data('modeElement').addClass('on').removeClass('off').removeClass('disabled');
|
||||
|
||||
|
@ -450,7 +450,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
//ARM mode is a special case
|
||||
if (i == 0) {
|
||||
let armSwitchActive = false;
|
||||
|
||||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) {
|
||||
if (FC.CONFIG.armingDisableCount > 0) {
|
||||
// check the highest bit of the armingDisableFlags. This will be the ARMING_DISABLED_ARMSWITCH flag.
|
||||
|
@ -484,7 +484,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
if (modeElement.find(' .range').length == 0 && modeElement.find(' .link').length == 0) {
|
||||
modeElement.toggle(!hideUnused);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
auto_select_channel(FC.RC.channels, FC.RSSI_CONFIG.channel);
|
||||
|
||||
|
@ -544,8 +544,8 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
})
|
||||
.prop("checked", !!result.hideUnusedModes)
|
||||
.change();
|
||||
});
|
||||
|
||||
});
|
||||
|
||||
// update ui instantly on first load
|
||||
update_ui();
|
||||
|
||||
|
|
|
@ -402,7 +402,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
legacy_accel_alignment_e.hide();
|
||||
|
||||
const GYRO_DETECTION_FLAGS = {
|
||||
DETECTED_GYRO_1: (1 << 0),
|
||||
DETECTED_GYRO_1: (1 << 0),
|
||||
DETECTED_GYRO_2: (1 << 1),
|
||||
DETECTED_DUAL_GYROS: (1 << 7),
|
||||
};
|
||||
|
|
|
@ -16,9 +16,9 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
function load_failssafe_config() {
|
||||
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_rxfail_config);
|
||||
}
|
||||
|
||||
|
||||
function load_rxfail_config() {
|
||||
MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false,
|
||||
MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false,
|
||||
semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41) ? load_gps_rescue : get_box_names);
|
||||
}
|
||||
|
||||
|
@ -57,7 +57,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
function load_motor_config() {
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR_CONFIG, false, false, load_gps_config);
|
||||
}
|
||||
|
||||
|
||||
function load_gps_config() {
|
||||
MSP.send_message(MSPCodes.MSP_GPS_CONFIG, false, false, load_html);
|
||||
}
|
||||
|
@ -78,7 +78,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
$('div.stage2').hide();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// FIXME cleanup oldpane html and css
|
||||
const oldPane = $('div.oldpane');
|
||||
oldPane.prop("disabled", true);
|
||||
|
@ -95,7 +95,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
|
||||
if (typeof FC.RSSI_CONFIG.channel !== 'undefined') {
|
||||
auxAssignment[FC.RSSI_CONFIG.channel - 5] += "<span class=\"modename\">" + "RSSI" + "</span>"; // Aux channels start at 5 in backend so we have to substract 5
|
||||
}
|
||||
}
|
||||
|
||||
for (let modeIndex = 0; modeIndex < FC.AUX_CONFIG.length; modeIndex++) {
|
||||
|
||||
|
@ -113,12 +113,12 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
if (range.start >= range.end) {
|
||||
continue; // invalid!
|
||||
}
|
||||
|
||||
|
||||
// Search for the real name if it belongs to a peripheral
|
||||
let modeName = FC.AUX_CONFIG[modeIndex];
|
||||
let modeName = FC.AUX_CONFIG[modeIndex];
|
||||
modeName = adjustBoxNameIfPeripheralWithModeID(modeId, modeName);
|
||||
|
||||
auxAssignment[modeRange.auxChannelIndex] += "<span class=\"modename\">" + modeName + "</span>";
|
||||
auxAssignment[modeRange.auxChannelIndex] += "<span class=\"modename\">" + modeName + "</span>";
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -386,14 +386,14 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function save_feature_config() {
|
||||
MSP.send_message(MSPCodes.MSP_SET_FEATURE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE_CONFIG), false,
|
||||
MSP.send_message(MSPCodes.MSP_SET_FEATURE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE_CONFIG), false,
|
||||
semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41) ? save_gps_rescue : save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_gps_rescue() {
|
||||
MSP.send_message(MSPCodes.MSP_SET_GPS_RESCUE, mspHelper.crunch(MSPCodes.MSP_SET_GPS_RESCUE), false, save_to_eeprom);
|
||||
}
|
||||
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
}
|
||||
|
|
|
@ -12,19 +12,19 @@ TABS.gps.initialize = function (callback) {
|
|||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_html);
|
||||
|
||||
|
||||
function set_online(){
|
||||
$('#connect').hide();
|
||||
$('#waiting').show();
|
||||
$('#loadmap').hide();
|
||||
}
|
||||
|
||||
|
||||
function set_offline(){
|
||||
$('#connect').show();
|
||||
$('#waiting').hide();
|
||||
$('#loadmap').hide();
|
||||
}
|
||||
|
||||
|
||||
function process_html() {
|
||||
// translate to user-selected languageconsole.log('Online');
|
||||
i18n.localizePage();
|
||||
|
@ -71,7 +71,6 @@ TABS.gps.initialize = function (callback) {
|
|||
$('td', row).eq(1).text(FC.GPS_DATA.quality[i]);
|
||||
$('td', row).eq(2).find('progress').val(FC.GPS_DATA.cno[i]);
|
||||
}
|
||||
|
||||
|
||||
const message = {
|
||||
action: 'center',
|
||||
|
@ -98,7 +97,7 @@ TABS.gps.initialize = function (callback) {
|
|||
}else{
|
||||
gpsWasFixed = false;
|
||||
$('#connect').show();
|
||||
$('#waiting').hide();
|
||||
$('#waiting').hide();
|
||||
$('#loadmap').hide();
|
||||
}
|
||||
}
|
||||
|
@ -109,7 +108,7 @@ TABS.gps.initialize = function (callback) {
|
|||
if (!have_sensor(FC.CONFIG.activeSensors, 'gps')) {
|
||||
//return;
|
||||
}
|
||||
|
||||
|
||||
get_raw_gps_data();
|
||||
}, 75, true);
|
||||
|
||||
|
@ -147,7 +146,7 @@ TABS.gps.initialize = function (callback) {
|
|||
};
|
||||
frame.contentWindow.postMessage(message, '*');
|
||||
});
|
||||
|
||||
|
||||
$('#zoom_out').click(function() {
|
||||
console.log('zoom out');
|
||||
const message = {
|
||||
|
@ -155,14 +154,12 @@ TABS.gps.initialize = function (callback) {
|
|||
};
|
||||
frame.contentWindow.postMessage(message, '*');
|
||||
});
|
||||
|
||||
|
||||
GUI.content_ready(callback);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
TABS.gps.cleanup = function (callback) {
|
||||
if (callback) callback();
|
||||
};
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
TABS.help = {};
|
||||
TABS.help.initialize = function (callback) {
|
||||
|
||||
|
||||
if (GUI.active_tab != 'help') {
|
||||
GUI.active_tab = 'help';
|
||||
}
|
||||
|
|
|
@ -741,7 +741,6 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
case "function-a":
|
||||
case "function-f":
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
@ -754,7 +753,6 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
case "function-f":
|
||||
case "function-g":
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
switch (activeFunction) {
|
||||
|
@ -768,7 +766,6 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
case "function-o":
|
||||
case "function-g":
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
|
@ -781,7 +778,6 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
case "function-a":
|
||||
case "function-f":
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
|
@ -793,7 +789,6 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
case "function-s":
|
||||
case "function-g":
|
||||
return false;
|
||||
break;
|
||||
case "function-r":
|
||||
case "function-b":
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0"))
|
||||
|
@ -801,7 +796,6 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
break;
|
||||
default:
|
||||
return true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -813,10 +807,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
case "function-a":
|
||||
case "function-f":
|
||||
return true;
|
||||
break;
|
||||
default:
|
||||
return false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -48,7 +48,7 @@ function initializeMap() {
|
|||
}));
|
||||
|
||||
iconStyle = new ol.style.Style({
|
||||
image: icon
|
||||
image: icon
|
||||
});
|
||||
|
||||
iconStyleNoFix = new ol.style.Style({
|
||||
|
@ -72,7 +72,7 @@ function initializeMap() {
|
|||
|
||||
map.addLayer(currentPositionLayer);
|
||||
|
||||
window.addEventListener('message', processMapEvents);
|
||||
window.addEventListener('message', processMapEvents);
|
||||
}
|
||||
|
||||
function processMapEvents(e) {
|
||||
|
@ -80,7 +80,7 @@ function processMapEvents(e) {
|
|||
try {
|
||||
switch(e.data.action) {
|
||||
|
||||
case 'zoom_in':
|
||||
case 'zoom_in':
|
||||
mapView.setZoom(mapView.getZoom() + 1);
|
||||
break;
|
||||
|
||||
|
|
|
@ -9,12 +9,12 @@ TABS.motors = {
|
|||
sensorAccelRate: 20,
|
||||
sensorAccelScale: 2,
|
||||
sensorSelectValues: {
|
||||
"gyroScale": {"10" : 10,
|
||||
"25" : 25,
|
||||
"50" : 50,
|
||||
"100" : 100,
|
||||
"200" : 200,
|
||||
"300" : 300,
|
||||
"gyroScale": {"10" : 10,
|
||||
"25" : 25,
|
||||
"50" : 50,
|
||||
"100" : 100,
|
||||
"200" : 200,
|
||||
"300" : 300,
|
||||
"400" : 400,
|
||||
"500" : 500,
|
||||
"1000" : 1000,
|
||||
|
@ -283,7 +283,6 @@ TABS.motors.initialize = function (callback) {
|
|||
const motorVoltage = $('.motors-bat-voltage'),
|
||||
motor_mah_drawing_e = $('.motors-bat-mah-drawing'),
|
||||
motor_mah_drawn_e = $('.motors-bat-mah-drawn');
|
||||
|
||||
|
||||
const rawDataTextElements = {
|
||||
x: [],
|
||||
|
@ -455,7 +454,6 @@ TABS.motors.initialize = function (callback) {
|
|||
motorVoltage.text(i18n.getMessage('motorsVoltageValue', [FC.ANALOG.voltage]));
|
||||
motor_mah_drawing_e.text(i18n.getMessage('motorsADrawingValue', [FC.ANALOG.amperage.toFixed(2)]));
|
||||
motor_mah_drawn_e.text(i18n.getMessage('motorsmAhDrawnValue', [FC.ANALOG.mAhdrawn]));
|
||||
|
||||
}
|
||||
GUI.interval_add('motors_power_data_pull_slow', power_data_pull, 250, true); // 4 fps
|
||||
|
||||
|
@ -684,13 +682,13 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
// Reduce the size of the value if too big
|
||||
if (rpmMotorValue > 999999) {
|
||||
rpmMotorValue = (rpmMotorValue / 1000000).toFixed(5 - (rpmMotorValue / 1000000).toFixed(0).toString().length) + "M";
|
||||
rpmMotorValue = (rpmMotorValue / 1000000).toFixed(5 - (rpmMotorValue / 1000000).toFixed(0).toString().length) + "M";
|
||||
}
|
||||
|
||||
rpmMotorValue = rpmMotorValue.toString().padStart(MAX_VALUE_SIZE);
|
||||
let telemetryText = i18n.getMessage('motorsRPM', {motorsRpmValue: rpmMotorValue});
|
||||
|
||||
|
||||
|
||||
if (FC.MOTOR_CONFIG.use_dshot_telemetry) {
|
||||
|
||||
let invalidPercent = FC.MOTOR_TELEMETRY_DATA.invalidPercent[i];
|
||||
|
@ -714,8 +712,6 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
$('.motor_testing .telemetry .motor-' + i).html(telemetryText);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
// servo indicators are still using old (not flexible block scale), it will be changed in the future accordingly
|
||||
|
|
|
@ -458,7 +458,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
labelsChannelData.ch4.push(element);
|
||||
}
|
||||
});
|
||||
|
||||
|
||||
let plotUpdateRate;
|
||||
const rxRefreshRate = $('select[name="rx_refresh_rate"]');
|
||||
|
||||
|
@ -511,7 +511,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
labelsChannelData.ch2[0].text(FC.RC.channels[1]);
|
||||
labelsChannelData.ch3[0].text(FC.RC.channels[2]);
|
||||
labelsChannelData.ch4[0].text(FC.RC.channels[3]);
|
||||
|
||||
|
||||
// push latest data to the main array
|
||||
for (let i = 0; i < FC.RC.active_channels; i++) {
|
||||
rxPlotData[i].push([samples, FC.RC.channels[i]]);
|
||||
|
|
|
@ -185,8 +185,8 @@ TABS.sensors.initialize = function (callback) {
|
|||
// disable graphs for sensors that are missing
|
||||
let checkboxes = $('.tab-sensors .info .checkboxes input');
|
||||
checkboxes.parent().show();
|
||||
|
||||
if (FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2) {
|
||||
|
||||
if (FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'acc')) {
|
||||
checkboxes.eq(1).prop('disabled', true);
|
||||
}
|
||||
|
|
|
@ -43,14 +43,14 @@ TABS.setup_osd.initialize = function (callback) {
|
|||
});
|
||||
});
|
||||
});
|
||||
|
||||
|
||||
function get_slow_data() {
|
||||
/* FIXME requires MSP update
|
||||
MSP.send_message(MSPCodes.MSP_OSD_VIDEO_STATUS, false, false, function () {
|
||||
let element element = $('.video-mode');
|
||||
const osdVideoMode = osdVideoModes[OSD_VIDEO_STATE.video_mode];
|
||||
element.text(osdVideoMode);
|
||||
|
||||
|
||||
element = $('.camera-connected');
|
||||
element.text(OSD_VIDEO_STATE.camera_connected ? i18n.getMessage('yes') : i18n.getMessage('No'));
|
||||
});
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue