diff --git a/src/js/Beepers.js b/src/js/Beepers.js index a69e3e61..acf1aaf8 100644 --- a/src/js/Beepers.js +++ b/src/js/Beepers.js @@ -26,7 +26,7 @@ class Beepers { { bit: 18, name: 'BLACKBOX_ERASE', visible: true }, ]; - if (semver.gte(config.apiVersion, "1.37.0")) { + if (semver.gte(config.apiVersion, API_VERSION_1_37)) { beepers.push( { bit: 19, name: 'CRASH_FLIP', visible: true }, { bit: 20, name: 'CAM_CONNECTION_OPEN', visible: true }, @@ -34,7 +34,7 @@ class Beepers { ); } - if (semver.gte(config.apiVersion, "1.39.0")) { + if (semver.gte(config.apiVersion, API_VERSION_1_39)) { beepers.push( { bit: 22, name: 'RC_SMOOTHING_INIT_FAIL', visible: true } ); diff --git a/src/js/Features.js b/src/js/Features.js index 4976ec0e..c2065311 100644 --- a/src/js/Features.js +++ b/src/js/Features.js @@ -21,7 +21,7 @@ var Features = function (config) { {bit: 17, group: 'other', name: 'DISPLAY', haveTip: true} ]; - if (!semver.gte(config.apiVersion, "1.33.0")) { + if (!semver.gte(config.apiVersion, API_VERSION_1_33)) { features.push( {bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true} ); @@ -33,7 +33,7 @@ var Features = function (config) { ); } - if (semver.gte(FC.CONFIG.apiVersion, "1.15.0") && !semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, "1.15.0") && !semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { features.push( {bit: 8, group: 'rxFailsafe', name: 'FAILSAFE', haveTip: true} ); @@ -57,7 +57,7 @@ var Features = function (config) { features.push( {bit: 23, group: 'superexpoRates', name: 'SUPEREXPO_RATES'} ); - } else if (!semver.gte(config.apiVersion, "1.33.0")) { + } else if (!semver.gte(config.apiVersion, API_VERSION_1_33)) { features.push( {bit: 23, group: 'other', name: 'SDCARD'} ); @@ -68,28 +68,28 @@ var Features = function (config) { features.push( {bit: 18, group: 'other', name: 'OSD'} ); - if (!semver.gte(FC.CONFIG.apiVersion, "1.35.0")) { + if (!semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_35)) { features.push( {bit: 24, group: 'other', name: 'VTX'} ) } } - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { features.push( {bit: 25, group: 'rxMode', mode: 'select', name: 'RX_SPI'}, {bit: 27, group: 'escSensor', name: 'ESC_SENSOR'} ); } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { features.push( {bit: 28, group: 'antiGravity', name: 'ANTI_GRAVITY', haveTip: true, hideName: true}, {bit: 29, group: 'other', name: 'DYNAMIC_FILTER'} ); } - if (!semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (!semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { features.push( {bit: 1, group: 'batteryVoltage', name: 'VBAT'}, {bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'} diff --git a/src/js/backup_restore.js b/src/js/backup_restore.js index 345170a7..b3e4e9cf 100644 --- a/src/js/backup_restore.js +++ b/src/js/backup_restore.js @@ -116,13 +116,13 @@ function configuration_backup(callback) { if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) { uniqueData.push(MSPCodes.MSP_LED_STRIP_MODECOLOR); } - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { uniqueData.push(MSPCodes.MSP_MOTOR_CONFIG); uniqueData.push(MSPCodes.MSP_RSSI_CONFIG); uniqueData.push(MSPCodes.MSP_GPS_CONFIG); uniqueData.push(MSPCodes.MSP_FEATURE_CONFIG); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { uniqueData.push(MSPCodes.MSP_MODE_RANGES_EXTRA); } } @@ -166,16 +166,16 @@ function configuration_backup(callback) { configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FC.FAILSAFE_CONFIG); configuration.RXFAIL_CONFIG = jQuery.extend(true, [], FC.RXFAIL_CONFIG); } - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { configuration.RSSI_CONFIG = jQuery.extend(true, {}, FC.RSSI_CONFIG); configuration.FEATURE_CONFIG = jQuery.extend(true, {}, FC.FEATURE_CONFIG); configuration.MOTOR_CONFIG = jQuery.extend(true, {}, FC.MOTOR_CONFIG); configuration.GPS_CONFIG = jQuery.extend(true, {}, FC.GPS_CONFIG); } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { configuration.BEEPER_CONFIG = jQuery.extend(true, {}, FC.BEEPER_CONFIG); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { configuration.MODE_RANGES_EXTRA = jQuery.extend(true, [], FC.MODE_RANGES_EXTRA); } @@ -768,7 +768,7 @@ function configuration_restore(callback) { } function upload_mode_ranges() { - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { if (configuration.MODE_RANGES_EXTRA == undefined) { FC.MODE_RANGES_EXTRA = []; @@ -824,7 +824,7 @@ function configuration_restore(callback) { uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG); uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG); } - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { uniqueData.push(MSPCodes.MSP_SET_FEATURE_CONFIG); uniqueData.push(MSPCodes.MSP_SET_MOTOR_CONFIG); uniqueData.push(MSPCodes.MSP_SET_GPS_CONFIG); diff --git a/src/js/data_storage.js b/src/js/data_storage.js index 8dbaffa0..54131d14 100644 --- a/src/js/data_storage.js +++ b/src/js/data_storage.js @@ -1,5 +1,17 @@ 'use strict'; +const API_VERSION_1_31 = '1.31.0'; +const API_VERSION_1_32 = '1.32.0'; +const API_VERSION_1_33 = '1.33.0'; +const API_VERSION_1_34 = '1.34.0'; +const API_VERSION_1_35 = '1.35.0'; +const API_VERSION_1_36 = '1.36.0'; +const API_VERSION_1_37 = '1.37.0'; +const API_VERSION_1_38 = '1.38.0'; +const API_VERSION_1_39 = '1.39.0'; +const API_VERSION_1_40 = '1.40.0'; +const API_VERSION_1_41 = '1.41.0'; +const API_VERSION_1_42 = '1.42.0'; const API_VERSION_1_43 = '1.43.0'; const API_VERSION_1_44 = '1.44.0'; diff --git a/src/js/fc.js b/src/js/fc.js index 2cfb1deb..2457e92b 100644 --- a/src/js/fc.js +++ b/src/js/fc.js @@ -564,11 +564,11 @@ const FC = { } if ((flightControllerIdentifier === 'BTFL' && semver.gte(flightControllerVersion, "2.6.0")) || - (flightControllerIdentifier === 'CLFL' && semver.gte(apiVersion, "1.31.0"))) { + (flightControllerIdentifier === 'CLFL' && semver.gte(apiVersion, API_VERSION_1_31))) { result.push('JETIEXBUS'); } - if (semver.gte(apiVersion, "1.31.0")) { + if (semver.gte(apiVersion, API_VERSION_1_31)) { result.push('CRSF'); } @@ -576,15 +576,15 @@ const FC = { result.push('SPEKTRUM2048/SRXL'); } - if (semver.gte(apiVersion, "1.35.0")) { + if (semver.gte(apiVersion, API_VERSION_1_35)) { result.push('TARGET_CUSTOM'); } - if (semver.gte(apiVersion, "1.37.0")) { + if (semver.gte(apiVersion, API_VERSION_1_37)) { result.push('FrSky FPort'); } - if (semver.gte(apiVersion, "1.42.0")) { + if (semver.gte(apiVersion, API_VERSION_1_42)) { result.push('SPEKTRUM SRXL2'); } @@ -756,7 +756,7 @@ const FC = { boardHasVcp() { let hasVcp = false; - if (semver.gte(this.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(this.CONFIG.apiVersion, API_VERSION_1_37)) { hasVcp = bit_check(this.CONFIG.targetCapabilities, this.TARGET_CAPABILITIES_FLAGS.HAS_VCP); } else { hasVcp = BOARD.find_board_definition(this.CONFIG.boardIdentifier).vcp; @@ -773,9 +773,9 @@ const FC = { getFilterDefaults() { const versionFilterDefaults = this.DEFAULT; - if (semver.eq(this.CONFIG.apiVersion, "1.40.0")) { + if (semver.eq(this.CONFIG.apiVersion, API_VERSION_1_40)) { versionFilterDefaults.dterm_lowpass2_hz = 200; - } else if (semver.gte(this.CONFIG.apiVersion, "1.41.0")) { + } else if (semver.gte(this.CONFIG.apiVersion, API_VERSION_1_41)) { versionFilterDefaults.gyro_lowpass_hz = 150; versionFilterDefaults.gyro_lowpass_type = this.FILTER_TYPE_FLAGS.BIQUAD; versionFilterDefaults.gyro_lowpass2_hz = 0; @@ -784,7 +784,7 @@ const FC = { versionFilterDefaults.dterm_lowpass_type = this.FILTER_TYPE_FLAGS.BIQUAD; versionFilterDefaults.dterm_lowpass2_hz = 150; versionFilterDefaults.dterm_lowpass2_type = this.FILTER_TYPE_FLAGS.BIQUAD; - if (semver.gte(this.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(this.CONFIG.apiVersion, API_VERSION_1_42)) { versionFilterDefaults.gyro_lowpass_hz = 200; versionFilterDefaults.gyro_lowpass_dyn_min_hz = 200; versionFilterDefaults.gyro_lowpass_dyn_max_hz = 500; diff --git a/src/js/main.js b/src/js/main.js index dc870734..8e041c8e 100644 --- a/src/js/main.js +++ b/src/js/main.js @@ -655,13 +655,13 @@ function updateTabList(features) { $('#tabs ul.mode-connected li.tab_osd').hide(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { $('#tabs ul.mode-connected li.tab_power').show(); } else { $('#tabs ul.mode-connected li.tab_power').hide(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { $('#tabs ul.mode-connected li.tab_vtx').show(); } else { $('#tabs ul.mode-connected li.tab_vtx').hide(); diff --git a/src/js/msp/MSPHelper.js b/src/js/msp/MSPHelper.js index efddac28..b464fa7e 100644 --- a/src/js/msp/MSPHelper.js +++ b/src/js/msp/MSPHelper.js @@ -95,7 +95,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.CONFIG.numProfiles = data.readU8(); FC.CONFIG.rateProfile = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { // Read flight mode flags var byteCount = data.readU8(); for (let i = 0; i < byteCount; i++) { @@ -197,7 +197,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.ANALOG.rssi = data.readU16(); // 0-1023 FC.ANALOG.amperage = data.read16() / 100; // A FC.ANALOG.last_received_timestamp = Date.now(); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.ANALOG.voltage = data.readU16() / 100; } break; @@ -232,14 +232,14 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.BATTERY_STATE.voltage = data.readU8() / 10.0; // V FC.BATTERY_STATE.mAhDrawn = data.readU16(); // mAh FC.BATTERY_STATE.amperage = data.readU16() / 100; // A - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.BATTERY_STATE.batteryState = data.readU8(); FC.BATTERY_STATE.voltage = data.readU16() / 100; } break; case MSPCodes.MSP_VOLTAGE_METER_CONFIG: - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.MISC.vbatscale = data.readU8(); // 10-200 FC.MISC.vbatmincellvoltage = data.readU8() / 10; // 10-50 FC.MISC.vbatmaxcellvoltage = data.readU8() / 10; // 10-50 @@ -271,7 +271,7 @@ MspHelper.prototype.process_data = function(dataHandler) { } break; case MSPCodes.MSP_CURRENT_METER_CONFIG: - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.BF_CONFIG.currentscale = data.read16(); FC.BF_CONFIG.currentoffset = data.read16(); FC.BF_CONFIG.currentmetertype = data.readU8(); @@ -307,7 +307,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.BATTERY_CONFIG.capacity = data.readU16(); FC.BATTERY_CONFIG.voltageMeterSource = data.readU8(); FC.BATTERY_CONFIG.currentMeterSource = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.BATTERY_CONFIG.vbatmincellvoltage = data.readU16() / 100; FC.BATTERY_CONFIG.vbatmaxcellvoltage = data.readU16() / 100; FC.BATTERY_CONFIG.vbatwarningcellvoltage = data.readU16() / 100; @@ -344,18 +344,18 @@ MspHelper.prototype.process_data = function(dataHandler) { } else { FC.RC_TUNING.RC_YAW_EXPO = 0; } - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { FC.RC_TUNING.rcPitchRate = parseFloat((data.readU8() / 100).toFixed(2)); FC.RC_TUNING.RC_PITCH_EXPO = parseFloat((data.readU8() / 100).toFixed(2)); } else { FC.RC_TUNING.rcPitchRate = 0; FC.RC_TUNING.RC_PITCH_EXPO = 0; } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.RC_TUNING.throttleLimitType = data.readU8(); FC.RC_TUNING.throttleLimitPercent = data.readU8(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.RC_TUNING.roll_rate_limit = data.readU16(); FC.RC_TUNING.pitch_rate_limit = data.readU16(); FC.RC_TUNING.yaw_rate_limit = data.readU16(); @@ -380,7 +380,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.ARMING_CONFIG.auto_disarm_delay = data.readU8(); FC.ARMING_CONFIG.disarm_kill_switch = data.readU8(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { FC.ARMING_CONFIG.small_angle = data.readU8(); } break; @@ -411,7 +411,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.MOTOR_CONFIG.minthrottle = data.readU16(); // 0-2000 FC.MOTOR_CONFIG.maxthrottle = data.readU16(); // 0-2000 FC.MOTOR_CONFIG.mincommand = data.readU16(); // 0-2000 - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.MOTOR_CONFIG.motor_count = data.readU8(); FC.MOTOR_CONFIG.motor_poles = data.readU8(); FC.MOTOR_CONFIG.use_dshot_telemetry = data.readU8() != 0; @@ -421,7 +421,7 @@ MspHelper.prototype.process_data = function(dataHandler) { case MSPCodes.MSP_GPS_CONFIG: FC.GPS_CONFIG.provider = data.readU8(); FC.GPS_CONFIG.ublox_sbas = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.34.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_34)) { FC.GPS_CONFIG.auto_config = data.readU8(); FC.GPS_CONFIG.auto_baud = data.readU8(); @@ -503,7 +503,7 @@ MspHelper.prototype.process_data = function(dataHandler) { case MSPCodes.MSP_SERVO_CONFIGURATIONS: FC.SERVO_CONFIG = []; // empty the array as new data is coming in - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { if (data.byteLength % 12 == 0) { for (let i = 0; i < data.byteLength; i += 12) { var arr = { @@ -676,7 +676,7 @@ MspHelper.prototype.process_data = function(dataHandler) { case MSPCodes.MSP_MIXER_CONFIG: FC.MIXER_CONFIG.mixer = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.MIXER_CONFIG.reverseMotorDir = data.readU8(); } break; @@ -689,10 +689,10 @@ MspHelper.prototype.process_data = function(dataHandler) { case MSPCodes.MSP_BEEPER_CONFIG: FC.BEEPER_CONFIG.beepers.setDisabledMask(data.readU32()); - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { FC.BEEPER_CONFIG.dshotBeaconTone = data.readU8(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { FC.BEEPER_CONFIG.dshotBeaconConditions.setDisabledMask(data.readU32()); } break; @@ -704,7 +704,7 @@ MspHelper.prototype.process_data = function(dataHandler) { break; case MSPCodes.MSP_SET_REBOOT: - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { var rebootType = data.read8(); if ((rebootType === self.REBOOT_TYPES.MSC) || (rebootType === self.REBOOT_TYPES.MSC_UTC)) { if (data.read8() === 0) { @@ -758,13 +758,13 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.CONFIG.boardIdentifier = identifier; FC.CONFIG.boardVersion = data.readU16(); - if (semver.gte(FC.CONFIG.apiVersion, "1.35.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_35)) { FC.CONFIG.boardType = data.readU8(); } else { FC.CONFIG.boardType = 0; } - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { FC.CONFIG.targetCapabilities = data.readU8(); let length = data.readU8(); @@ -776,7 +776,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.CONFIG.targetName = ""; } - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { let length = data.readU8(); for (let i = 0; i < length; i++) { FC.CONFIG.boardName += String.fromCharCode(data.readU8()); @@ -796,13 +796,13 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.CONFIG.signature = []; } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.CONFIG.mcuTypeId = data.readU8(); } else { FC.CONFIG.mcuTypeId = 255; } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.CONFIG.configurationState = data.readU8(); } @@ -955,19 +955,19 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.RX_CONFIG.rcInterpolation = data.readU8(); FC.RX_CONFIG.rcInterpolationInterval = data.readU8(); FC.RX_CONFIG.airModeActivateThreshold = data.readU16(); - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { FC.RX_CONFIG.rxSpiProtocol = data.readU8(); FC.RX_CONFIG.rxSpiId = data.readU32(); FC.RX_CONFIG.rxSpiRfChannelCount = data.readU8(); FC.RX_CONFIG.fpvCamAngleDegrees = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { FC.RX_CONFIG.rcInterpolationChannels = data.readU8(); FC.RX_CONFIG.rcSmoothingType = data.readU8(); FC.RX_CONFIG.rcSmoothingInputCutoff = data.readU8(); FC.RX_CONFIG.rcSmoothingDerivativeCutoff = data.readU8(); FC.RX_CONFIG.rcSmoothingInputType = data.readU8(); FC.RX_CONFIG.rcSmoothingDerivativeType = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.RX_CONFIG.usbCdcHidType = data.readU8(); FC.RX_CONFIG.rcSmoothingAutoSmoothness = data.readU8(); } @@ -1022,10 +1022,10 @@ MspHelper.prototype.process_data = function(dataHandler) { if (semver.gte(FC.CONFIG.apiVersion, "1.25.0")) { let gyroUse32kHz = data.readU8(); - if (semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.PID_ADVANCED_CONFIG.gyroUse32kHz = gyroUse32kHz; } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + 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 FC.PID_ADVANCED_CONFIG.gyroHighFsr = data.readU8(); @@ -1052,10 +1052,10 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.FILTER_CONFIG.gyro_notch2_hz = data.readU16(); FC.FILTER_CONFIG.gyro_notch2_cutoff = data.readU16(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.FILTER_CONFIG.dterm_lowpass_type = data.readU8(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { FC.FILTER_CONFIG.gyro_hardware_lpf = data.readU8(); let gyro_32khz_hardware_lpf = data.readU8(); FC.FILTER_CONFIG.gyro_lowpass_hz = data.readU16(); @@ -1063,7 +1063,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.FILTER_CONFIG.gyro_lowpass_type = data.readU8(); FC.FILTER_CONFIG.gyro_lowpass2_type = data.readU8(); FC.FILTER_CONFIG.dterm_lowpass2_hz = data.readU16(); - if (semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.FILTER_CONFIG.gyro_32khz_hardware_lpf = gyro_32khz_hardware_lpf; } else { FC.FILTER_CONFIG.gyro_32khz_hardware_lpf = 0; @@ -1073,7 +1073,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz = data.readU16(); FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz = data.readU16(); FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz = data.readU16(); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.FILTER_CONFIG.dyn_notch_range = data.readU8(); FC.FILTER_CONFIG.dyn_notch_width_percent = data.readU8(); FC.FILTER_CONFIG.dyn_notch_q = data.readU16(); @@ -1104,7 +1104,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.ADVANCED_TUNING.deltaMethod = data.readU8(); FC.ADVANCED_TUNING.vbatPidCompensation = data.readU8(); if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) { - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { FC.ADVANCED_TUNING.feedforwardTransition = data.readU8(); } else { FC.ADVANCED_TUNING.dtermSetpointTransition = data.readU8(); @@ -1119,14 +1119,14 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.ADVANCED_TUNING.levelAngleLimit = data.readU8(); FC.ADVANCED_TUNING.levelSensitivity = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.ADVANCED_TUNING.itermThrottleThreshold = data.readU16(); FC.ADVANCED_TUNING.itermAcceleratorGain = data.readU16(); - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { FC.ADVANCED_TUNING.dtermSetpointWeight = data.readU16(); - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { FC.ADVANCED_TUNING.itermRotation = data.readU8(); FC.ADVANCED_TUNING.smartFeedforward = data.readU8(); FC.ADVANCED_TUNING.itermRelax = data.readU8(); @@ -1139,7 +1139,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.ADVANCED_TUNING.feedforwardYaw = data.readU16(); FC.ADVANCED_TUNING.antiGravityMode = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.ADVANCED_TUNING.dMinRoll = data.readU8(); FC.ADVANCED_TUNING.dMinPitch = data.readU8(); FC.ADVANCED_TUNING.dMinYaw = data.readU8(); @@ -1148,7 +1148,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.ADVANCED_TUNING.useIntegratedYaw = data.readU8(); FC.ADVANCED_TUNING.integratedYawRelax = data.readU8(); - if(semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.ADVANCED_TUNING.itermRelaxCutoff = data.readU8(); if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) { @@ -1186,7 +1186,7 @@ MspHelper.prototype.process_data = function(dataHandler) { var ledDirectionLetters = ['n', 'e', 's', 'w', 'u', 'd']; // in LSB bit order var ledFunctionLetters = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l']; // in LSB bit order var ledBaseFunctionLetters = ['c', 'f', 'a', 'l', 's', 'g', 'r']; // in LSB bit - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { var ledOverlayLetters = ['t', 'o', 'b', 'n', 'i', 'w']; // in LSB bit } else { var ledOverlayLetters = ['t', 'o', 'b', 'v', 'i', 'w']; // in LSB bit @@ -1197,7 +1197,7 @@ MspHelper.prototype.process_data = function(dataHandler) { if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) { ledCount = data.byteLength / 4; } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { // According to betaflight/src/main/msp/msp.c // API 1.41 - add indicator for advanced profile support and the current profile selection // 0 = basic ledstrip available @@ -1357,7 +1357,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.BLACKBOX.blackboxDevice = data.readU8(); FC.BLACKBOX.blackboxRateNum = data.readU8(); FC.BLACKBOX.blackboxRateDenom = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.BLACKBOX.blackboxPDenom = data.readU16(); } if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_44)) { @@ -1369,7 +1369,7 @@ MspHelper.prototype.process_data = function(dataHandler) { break; case MSPCodes.MSP_TRANSPONDER_CONFIG: var bytesRemaining = data.byteLength; - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { var providerCount = data.readU8(); bytesRemaining--; @@ -1420,7 +1420,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FC.VTX_CONFIG.vtx_device_ready = data.readU8() != 0; FC.VTX_CONFIG.vtx_low_power_disarm = data.readU8(); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.VTX_CONFIG.vtx_pit_mode_frequency = data.readU16(); FC.VTX_CONFIG.vtx_table_available = data.readU8() != 0; FC.VTX_CONFIG.vtx_table_bands = data.readU8(); @@ -1648,16 +1648,16 @@ MspHelper.prototype.crunch = function(code) { case MSPCodes.MSP_SET_BEEPER_CONFIG: var beeperDisabledMask = FC.BEEPER_CONFIG.beepers.getDisabledMask(); buffer.push32(beeperDisabledMask); - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { buffer.push8(FC.BEEPER_CONFIG.dshotBeaconTone); } - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { buffer.push32(FC.BEEPER_CONFIG.dshotBeaconConditions.getDisabledMask()); } break; case MSPCodes.MSP_SET_MIXER_CONFIG: buffer.push8(FC.MIXER_CONFIG.mixer) - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { buffer.push8(FC.MIXER_CONFIG.reverseMotorDir); } break; @@ -1698,15 +1698,15 @@ MspHelper.prototype.crunch = function(code) { buffer.push8(Math.round(FC.RC_TUNING.rcYawRate * 100)); } } - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { buffer.push8(Math.round(FC.RC_TUNING.rcPitchRate * 100)); buffer.push8(Math.round(FC.RC_TUNING.RC_PITCH_EXPO * 100)); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { buffer.push8(FC.RC_TUNING.throttleLimitType); buffer.push8(FC.RC_TUNING.throttleLimitPercent); } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push16(FC.RC_TUNING.roll_rate_limit); buffer.push16(FC.RC_TUNING.pitch_rate_limit); buffer.push16(FC.RC_TUNING.yaw_rate_limit); @@ -1727,7 +1727,7 @@ MspHelper.prototype.crunch = function(code) { case MSPCodes.MSP_SET_ARMING_CONFIG: buffer.push8(FC.ARMING_CONFIG.auto_disarm_delay) .push8(FC.ARMING_CONFIG.disarm_kill_switch); - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { buffer.push8(FC.ARMING_CONFIG.small_angle); } break; @@ -1756,7 +1756,7 @@ MspHelper.prototype.crunch = function(code) { buffer.push16(FC.MOTOR_CONFIG.minthrottle) .push16(FC.MOTOR_CONFIG.maxthrottle) .push16(FC.MOTOR_CONFIG.mincommand); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push8(FC.MOTOR_CONFIG.motor_poles); buffer.push8(FC.MOTOR_CONFIG.use_dshot_telemetry ? 1 : 0); } @@ -1764,7 +1764,7 @@ MspHelper.prototype.crunch = function(code) { case MSPCodes.MSP_SET_GPS_CONFIG: buffer.push8(FC.GPS_CONFIG.provider) .push8(FC.GPS_CONFIG.ublox_sbas); - if (semver.gte(FC.CONFIG.apiVersion, "1.34.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_34)) { buffer.push8(FC.GPS_CONFIG.auto_config) .push8(FC.GPS_CONFIG.auto_baud); @@ -1802,14 +1802,14 @@ MspHelper.prototype.crunch = function(code) { .push16(FC.BATTERY_CONFIG.capacity) .push8(FC.BATTERY_CONFIG.voltageMeterSource) .push8(FC.BATTERY_CONFIG.currentMeterSource); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { buffer.push16(Math.round(FC.BATTERY_CONFIG.vbatmincellvoltage * 100)) .push16(Math.round(FC.BATTERY_CONFIG.vbatmaxcellvoltage * 100)) .push16(Math.round(FC.BATTERY_CONFIG.vbatwarningcellvoltage * 100)); } break; case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG: - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { buffer.push8(FC.MISC.vbatscale) .push8(Math.round(FC.MISC.vbatmincellvoltage * 10)) .push8(Math.round(FC.MISC.vbatmaxcellvoltage * 10)) @@ -1820,7 +1820,7 @@ MspHelper.prototype.crunch = function(code) { } break; case MSPCodes.MSP_SET_CURRENT_METER_CONFIG: - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { buffer.push16(FC.BF_CONFIG.currentscale) .push16(FC.BF_CONFIG.currentoffset) .push8(FC.BF_CONFIG.currentmetertype) @@ -1840,19 +1840,19 @@ MspHelper.prototype.crunch = function(code) { buffer.push8(FC.RX_CONFIG.rcInterpolation) .push8(FC.RX_CONFIG.rcInterpolationInterval) .push16(FC.RX_CONFIG.airModeActivateThreshold); - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { buffer.push8(FC.RX_CONFIG.rxSpiProtocol) .push32(FC.RX_CONFIG.rxSpiId) .push8(FC.RX_CONFIG.rxSpiRfChannelCount) .push8(FC.RX_CONFIG.fpvCamAngleDegrees); - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { buffer.push8(FC.RX_CONFIG.rcInterpolationChannels) .push8(FC.RX_CONFIG.rcSmoothingType) .push8(FC.RX_CONFIG.rcSmoothingInputCutoff) .push8(FC.RX_CONFIG.rcSmoothingDerivativeCutoff) .push8(FC.RX_CONFIG.rcSmoothingInputType) .push8(FC.RX_CONFIG.rcSmoothingDerivativeType); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push8(FC.RX_CONFIG.usbCdcHidType) .push8(FC.RX_CONFIG.rcSmoothingAutoSmoothness); } @@ -1874,7 +1874,7 @@ MspHelper.prototype.crunch = function(code) { break; case MSPCodes.MSP_SET_TRANSPONDER_CONFIG: - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { buffer.push8(FC.TRANSPONDER.provider); // } for (let i = 0; i < FC.TRANSPONDER.data.length; i++) { @@ -1956,7 +1956,7 @@ MspHelper.prototype.crunch = function(code) { buffer.push8(FC.SENSOR_ALIGNMENT.align_gyro) .push8(FC.SENSOR_ALIGNMENT.align_acc) .push8(FC.SENSOR_ALIGNMENT.align_mag); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { buffer.push8(FC.SENSOR_ALIGNMENT.gyro_to_use) .push8(FC.SENSOR_ALIGNMENT.gyro_1_align) .push8(FC.SENSOR_ALIGNMENT.gyro_2_align); @@ -1973,11 +1973,11 @@ MspHelper.prototype.crunch = function(code) { if (semver.gte(FC.CONFIG.apiVersion, "1.25.0")) { let gyroUse32kHz = 0; - if (semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { gyroUse32kHz = FC.PID_ADVANCED_CONFIG.gyroUse32kHz; } buffer.push8(gyroUse32kHz); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push8(FC.PID_ADVANCED_CONFIG.motorPwmInversion) .push8(FC.SENSOR_ALIGNMENT.gyro_to_use) // We don't want to double up on storing this state .push8(FC.PID_ADVANCED_CONFIG.gyroHighFsr) @@ -2003,12 +2003,12 @@ MspHelper.prototype.crunch = function(code) { buffer.push16(FC.FILTER_CONFIG.gyro_notch2_hz) .push16(FC.FILTER_CONFIG.gyro_notch2_cutoff) } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { buffer.push8(FC.FILTER_CONFIG.dterm_lowpass_type); } - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { let gyro_32khz_hardware_lpf = 0; - if (semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { gyro_32khz_hardware_lpf = FC.FILTER_CONFIG.gyro_32khz_hardware_lpf; } buffer.push8(FC.FILTER_CONFIG.gyro_hardware_lpf) @@ -2019,14 +2019,14 @@ MspHelper.prototype.crunch = function(code) { .push8(FC.FILTER_CONFIG.gyro_lowpass2_type) .push16(FC.FILTER_CONFIG.dterm_lowpass2_hz); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { buffer.push8(FC.FILTER_CONFIG.dterm_lowpass2_type) .push16(FC.FILTER_CONFIG.gyro_lowpass_dyn_min_hz) .push16(FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz) .push16(FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz) .push16(FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz); } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push8(FC.FILTER_CONFIG.dyn_notch_range) .push8(FC.FILTER_CONFIG.dyn_notch_width_percent) .push16(FC.FILTER_CONFIG.dyn_notch_q) @@ -2051,7 +2051,7 @@ MspHelper.prototype.crunch = function(code) { .push8(FC.ADVANCED_TUNING.vbatPidCompensation); if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) { - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { buffer.push8(FC.ADVANCED_TUNING.feedforwardTransition); } else { buffer.push8(FC.ADVANCED_TUNING.dtermSetpointTransition); @@ -2067,14 +2067,14 @@ MspHelper.prototype.crunch = function(code) { buffer.push8(FC.ADVANCED_TUNING.levelAngleLimit) .push8(FC.ADVANCED_TUNING.levelSensitivity); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { buffer.push16(FC.ADVANCED_TUNING.itermThrottleThreshold) .push16(FC.ADVANCED_TUNING.itermAcceleratorGain); - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { buffer.push16(FC.ADVANCED_TUNING.dtermSetpointWeight); - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { buffer.push8(FC.ADVANCED_TUNING.itermRotation) .push8(FC.ADVANCED_TUNING.smartFeedforward) .push8(FC.ADVANCED_TUNING.itermRelax) @@ -2087,7 +2087,7 @@ MspHelper.prototype.crunch = function(code) { .push16(FC.ADVANCED_TUNING.feedforwardYaw) .push8(FC.ADVANCED_TUNING.antiGravityMode); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { buffer.push8(FC.ADVANCED_TUNING.dMinRoll) .push8(FC.ADVANCED_TUNING.dMinPitch) .push8(FC.ADVANCED_TUNING.dMinYaw) @@ -2096,7 +2096,7 @@ MspHelper.prototype.crunch = function(code) { .push8(FC.ADVANCED_TUNING.useIntegratedYaw) .push8(FC.ADVANCED_TUNING.integratedYawRelax); - if(semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push8(FC.ADVANCED_TUNING.itermRelaxCutoff); if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) { @@ -2138,7 +2138,7 @@ MspHelper.prototype.crunch = function(code) { buffer.push8(FC.BLACKBOX.blackboxDevice) .push8(FC.BLACKBOX.blackboxRateNum) .push8(FC.BLACKBOX.blackboxRateDenom); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { buffer.push16(FC.BLACKBOX.blackboxPDenom); } if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_44)) { @@ -2172,7 +2172,7 @@ MspHelper.prototype.crunch = function(code) { case MSPCodes.MSP_SET_RTC: var now = new Date(); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { var timestamp = now.getTime(); var secs = timestamp / 1000; var millis = timestamp % 1000; @@ -2196,7 +2196,7 @@ MspHelper.prototype.crunch = function(code) { .push8(FC.VTX_CONFIG.vtx_pit_mode ? 1 : 0) .push8(FC.VTX_CONFIG.vtx_low_power_disarm); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { buffer.push16(FC.VTX_CONFIG.vtx_pit_mode_frequency) .push8(FC.VTX_CONFIG.vtx_band) .push8(FC.VTX_CONFIG.vtx_channel) @@ -2294,11 +2294,11 @@ MspHelper.prototype.setRawRx = function(channels) { MspHelper.prototype.dataflashRead = function(address, blockSize, onDataCallback) { var outData = [address & 0xFF, (address >> 8) & 0xFF, (address >> 16) & 0xFF, (address >> 24) & 0xFF]; - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { outData = outData.concat([blockSize & 0xFF, (blockSize >> 8) & 0xFF]); } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { // Allow compression outData = outData.concat([1]); } @@ -2310,7 +2310,7 @@ MspHelper.prototype.dataflashRead = function(address, blockSize, onDataCallback) var headerSize = 4; var dataSize = response.data.buffer.byteLength - headerSize; var dataCompressionType = 0; - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { headerSize = headerSize + 3; dataSize = response.data.readU16(); dataCompressionType = response.data.readU8(); @@ -2383,7 +2383,7 @@ MspHelper.prototype.sendServoConfigurations = function(onCompleteCallback) { .push16(servoConfiguration.middle) .push8(servoConfiguration.rate); - if (semver.lt(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_33)) { buffer.push8(servoConfiguration.angleAtMin) .push8(servoConfiguration.angleAtMax); } @@ -2443,7 +2443,7 @@ MspHelper.prototype.sendModeRanges = function(onCompleteCallback) { .push8((modeRange.range.start - 900) / 25) .push8((modeRange.range.end - 900) / 25); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { var modeRangeExtra = FC.MODE_RANGES_EXTRA[modeRangeIndex]; buffer.push8(modeRangeExtra.modeLogic) @@ -2573,7 +2573,7 @@ MspHelper.prototype.sendLedStripConfig = function(onCompleteCallback) { var ledDirectionLetters = ['n', 'e', 's', 'w', 'u', 'd']; // in LSB bit order var ledFunctionLetters = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l']; // in LSB bit order var ledBaseFunctionLetters = ['c', 'f', 'a', 'l', 's', 'g', 'r']; // in LSB bit - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { var ledOverlayLetters = ['t', 'o', 'b', 'w', 'i', 'w']; // in LSB bit } else { var ledOverlayLetters = ['t', 'o', 'b', 'v', 'i', 'w']; // in LSB bit @@ -2761,7 +2761,9 @@ MspHelper.prototype.sendRxFailConfig = function(onCompleteCallback) { } MspHelper.prototype.setArmingEnabled = function(doEnable, disableRunawayTakeoffPrevention, onCompleteCallback) { - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0") && (FC.CONFIG.armingDisabled === doEnable || FC.CONFIG.runawayTakeoffPreventionDisabled !== disableRunawayTakeoffPrevention)) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37) + && (FC.CONFIG.armingDisabled === doEnable || FC.CONFIG.runawayTakeoffPreventionDisabled !== disableRunawayTakeoffPrevention)) { + FC.CONFIG.armingDisabled = !doEnable; FC.CONFIG.runawayTakeoffPreventionDisabled = disableRunawayTakeoffPrevention; diff --git a/src/js/protocols/stm32.js b/src/js/protocols/stm32.js index 917e7c01..6edb7b27 100644 --- a/src/js/protocols/stm32.js +++ b/src/js/protocols/stm32.js @@ -141,7 +141,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback) GUI.log(i18n.getMessage('apiVersionReceived', [FC.CONFIG.apiVersion])); - if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_42)) { self.msp_connector.disconnect(function (disconnectionResult) { diff --git a/src/js/serial_backend.js b/src/js/serial_backend.js index 3a3a9914..2fc657cc 100644 --- a/src/js/serial_backend.js +++ b/src/js/serial_backend.js @@ -425,7 +425,7 @@ function processName() { } function setRtc() { - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { MSP.send_message(MSPCodes.MSP_SET_RTC, mspHelper.crunch(MSPCodes.MSP_SET_RTC), false, finishOpen); } else { finishOpen(); @@ -497,7 +497,7 @@ function onConnect() { $('#tabs ul.mode-connected').show(); MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false); - if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_BATTERY_CONFIG, false, false); } MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false); @@ -635,7 +635,7 @@ function have_sensor(sensors_detected, sensor_code) { case 'sonar': return bit_check(sensors_detected, 4); case 'gyro': - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { return bit_check(sensors_detected, 5); } else { return true; @@ -659,7 +659,7 @@ function update_live_status() { if (GUI.active_tab != 'cli') { MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false); - if (semver.gte(FC.CONFIG.apiVersion, "1.32.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_32)) { MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false); } else { MSP.send_message(MSPCodes.MSP_STATUS, false, false); diff --git a/src/js/tabs/adjustments.js b/src/js/tabs/adjustments.js index 36ccf522..537f506a 100644 --- a/src/js/tabs/adjustments.js +++ b/src/js/tabs/adjustments.js @@ -37,7 +37,7 @@ TABS.adjustments.initialize = function (callback) { // update selected slot // - if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_42)) { var adjustmentList = $(newAdjustment).find('.adjustmentSlot .slot'); adjustmentList.val(adjustmentRange.slotIndex); } @@ -165,7 +165,7 @@ TABS.adjustments.initialize = function (callback) { } - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { $('.tab-adjustments .adjustmentSlotsHelp').hide(); $('.tab-adjustments .adjustmentSlotHeader').hide(); $('.tab-adjustments .adjustmentSlot').hide(); @@ -199,7 +199,7 @@ TABS.adjustments.initialize = function (callback) { if ($(adjustmentElement).find('.enable').prop("checked")) { var rangeValues = $(this).find('.range .channel-slider').val(); var slotIndex = 0; - if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_42)) { slotIndex = parseInt($(this).find('.adjustmentSlot .slot').val()); } @@ -291,13 +291,13 @@ TABS.adjustments.adjust_template = function () { var selectFunction = $('#functionSelectionSelect'); var elementsNumber; - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { elementsNumber = 31; // OSD Profile Select & LED Profile Select - } else if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + } else if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { elementsNumber = 29; // PID Audio - } else if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + } else if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { elementsNumber = 26; // PID Audio - } else if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + } else if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { elementsNumber = 25; // Horizon Strength } else { elementsNumber = 24; // Setpoint transition @@ -308,7 +308,7 @@ TABS.adjustments.adjust_template = function () { } // For 1.40, the D Setpoint has been replaced, so we replace it with the correct values - if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_40)) { var element22 = selectFunction.find("option[value='22']"); var element23 = selectFunction.find("option[value='23']"); diff --git a/src/js/tabs/auxiliary.js b/src/js/tabs/auxiliary.js index fb3bfbb4..3ae1ca28 100644 --- a/src/js/tabs/auxiliary.js +++ b/src/js/tabs/auxiliary.js @@ -9,7 +9,7 @@ TABS.auxiliary.initialize = function (callback) { function get_mode_ranges() { MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, - semver.gte(FC.CONFIG.apiVersion, "1.41.0") ? get_mode_ranges_extra : get_box_ids); + semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41) ? get_mode_ranges_extra : get_box_ids); } function get_mode_ranges_extra() { @@ -57,7 +57,7 @@ TABS.auxiliary.initialize = function (callback) { $(newMode).find('a.addLink').data('modeElement', newMode); // hide link button for ARM - if (modeId == 0 || semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (modeId == 0 || semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { $(newMode).find('.addLink').hide(); } @@ -75,7 +75,7 @@ TABS.auxiliary.initialize = function (callback) { logicOption.val(0); logicList.append(logicOption); - if(semver.gte(FC.CONFIG.apiVersion, "1.41.0")){ + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)){ var logicOption = logicOptionTemplate.clone(); logicOption.text(i18n.getMessage('auxiliaryModeLogicAND')); logicOption.val(1); @@ -271,7 +271,7 @@ TABS.auxiliary.initialize = function (callback) { modeLogic: 0, linkedTo: 0 }; - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { modeRangeExtra = FC.MODE_RANGES_EXTRA[modeRangeIndex]; } @@ -451,7 +451,7 @@ TABS.auxiliary.initialize = function (callback) { if (i == 0) { var armSwitchActive = false; - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + 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. var armSwitchMask = 1 << (FC.CONFIG.armingDisableCount - 1); diff --git a/src/js/tabs/configuration.js b/src/js/tabs/configuration.js index de12d734..d2009cdd 100644 --- a/src/js/tabs/configuration.js +++ b/src/js/tabs/configuration.js @@ -19,7 +19,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { GUI.configuration_loaded = true; } - if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_36)) { //Show old battery configuration for pre-BF-3.2 self.SHOW_OLD_BATTERY_CONFIG = true; } else { @@ -32,7 +32,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_beeper_config() { var next_callback = load_serial_config; - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { MSP.send_message(MSPCodes.MSP_BEEPER_CONFIG, false, false, next_callback); } else { next_callback(); @@ -61,7 +61,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_motor_config() { var next_callback = load_gps_config; - if(semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_MOTOR_CONFIG, false, false, next_callback); } else { next_callback(); @@ -70,7 +70,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_gps_config() { var next_callback = load_acc_trim; - if(semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_GPS_CONFIG, false, false, load_acc_trim); } else { next_callback(); @@ -83,7 +83,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_misc() { var next_callback = load_arming_config; - if (semver.lt(FC.CONFIG.apiVersion, "1.33.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_MISC, false, false, next_callback); } else { next_callback(); @@ -178,7 +178,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_rx_config() { const next_callback = load_filter_config; - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, next_callback); } else { next_callback(); @@ -187,7 +187,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_filter_config() { const next_callback = load_html; - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { MSP.send_message(MSPCodes.MSP_FILTER_CONFIG, false, false, next_callback); } else { next_callback(); @@ -216,7 +216,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { var mixer = FC.MIXER_CONFIG.mixer var reverse = ""; - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { reverse = FC.MIXER_CONFIG.reverseMotorDir ? "_reversed" : ""; } @@ -260,7 +260,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { var dshotBeaconCondition_e = $('tbody.dshotBeaconConditions'); var dshotBeaconSwitch_e = $('tr.dshotBeaconSwitch'); - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { for (var i = 1; i <= 5; i++) { dshotBeeperBeaconTone.append(''); } @@ -276,7 +276,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { dshotBeeperBeaconTone.val(FC.BEEPER_CONFIG.dshotBeaconTone); var template = $('.beepers .beeper-template'); - if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_39)) { dshotBeaconSwitch_e.hide(); FC.BEEPER_CONFIG.dshotBeaconConditions.generateElements(template, dshotBeaconCondition_e); @@ -306,7 +306,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { var destination = $('.beepers .beeper-configuration'); var beeper_e = $('.tab-configuration .beepers'); - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { FC.BEEPER_CONFIG.beepers.generateElements(template, destination); } else { beeper_e.hide(); @@ -327,7 +327,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { 'CW 270° flip' ]; - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { alignments.push('Custom'); } @@ -395,7 +395,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { }); // Multi gyro config - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { gyro_align_content_e.show(); legacy_gyro_alignment_e.hide(); @@ -473,17 +473,17 @@ TABS.configuration.initialize = function (callback, scrollPosition) { escProtocols.push('BRUSHED'); } - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { escProtocols.push('DSHOT150'); escProtocols.push('DSHOT300'); escProtocols.push('DSHOT600'); - if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_42)) { escProtocols.push('DSHOT1200'); } } - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { escProtocols.push('PROSHOT1000'); } @@ -508,7 +508,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('input[id="unsyncedPWMSwitch"]').prop('checked', FC.PID_ADVANCED_CONFIG.use_unsyncedPwm !== 0).change(); $('input[name="unsyncedpwmfreq"]').val(FC.PID_ADVANCED_CONFIG.motor_pwm_rate); $('input[name="digitalIdlePercent"]').val(FC.PID_ADVANCED_CONFIG.digitalIdlePercent); - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { let dshotBidirectional_e = $('input[id="dshotBidir"]'); dshotBidirectional_e.prop('checked', FC.MOTOR_CONFIG.use_dshot_telemetry).change(); @@ -548,8 +548,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('input[name="motorPoles"]').val(FC.MOTOR_CONFIG.motor_poles); } - $('#escProtocolTooltip').toggle(semver.lt(FC.CONFIG.apiVersion, "1.42.0")); - $('#escProtocolTooltipNoDSHOT1200').toggle(semver.gte(FC.CONFIG.apiVersion, "1.42.0")); + $('#escProtocolTooltip').toggle(semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_42)); + $('#escProtocolTooltipNoDSHOT1200').toggle(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)); function updateVisibility() { // Hide unused settings @@ -581,8 +581,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('div.digitalIdlePercent').toggle(protocolConfigured && digitalProtocol); $('.escSensor').toggle(protocolConfigured && digitalProtocol); - $('div.checkboxDshotBidir').toggle(protocolConfigured && semver.gte(FC.CONFIG.apiVersion, "1.42.0") && digitalProtocol); - $('div.motorPoles').toggle(protocolConfigured && rpmFeaturesVisible && semver.gte(FC.CONFIG.apiVersion, "1.42.0")); + $('div.checkboxDshotBidir').toggle(protocolConfigured && semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42) && digitalProtocol); + $('div.motorPoles').toggle(protocolConfigured && rpmFeaturesVisible && semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)); $('.escMotorStop').toggle(protocolConfigured); @@ -655,7 +655,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { gyroTextElement.val(gyroContent); }; - if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { gyroUse32kHzElement.prop('checked', FC.PID_ADVANCED_CONFIG.gyroUse32kHz !== 0); gyroUse32kHzElement.change(function () { @@ -687,7 +687,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { pidBaseFreq = FC.CONFIG.sampleRateHz / 1000; } else { pidBaseFreq = 8; - if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, "1.41.0") && gyroUse32kHzElement.is(':checked')) { + if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41) && gyroUse32kHzElement.is(':checked')) { pidBaseFreq = 32; } pidBaseFreq = pidBaseFreq / parseInt($(this).val()); @@ -723,9 +723,9 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('input[name="craftName"]').val(FC.CONFIG.name); - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { $('input[name="fpvCamAngleDegrees"]').val(FC.RX_CONFIG.fpvCamAngleDegrees); - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { $('input[name="fpvCamAngleDegrees"]').attr("max", 90); } } else { @@ -741,7 +741,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { 'NMEA', 'UBLOX' ]; - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { gpsProtocols.push('MSP'); } @@ -804,7 +804,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { }).prop('checked', FC.GPS_CONFIG.auto_config === 1).change(); - if (semver.gte(FC.CONFIG.apiVersion, "1.34.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_34)) { gpsAutoBaudGroup.show(); gpsAutoConfigGroup.show(); } else { @@ -863,7 +863,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { // select current serial RX type serialRXSelectEl.val(FC.RX_CONFIG.serialrx_provider); - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { var spiRxTypes = [ 'NRF24_V202_250K', 'NRF24_V202_1M', @@ -876,7 +876,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { 'FRSKY_D' ]; - if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { spiRxTypes.push( 'FRSKY_X', 'A7105_FLYSKY', @@ -885,7 +885,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { ); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { spiRxTypes.push( 'SFHSS', 'SPEKTRUM', @@ -950,13 +950,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('div.cycles').show(); } - if(semver.gte(FC.CONFIG.apiVersion, "1.37.0") || !isExpertModeEnabled()) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37) || !isExpertModeEnabled()) { $('input[id="disarmkillswitch"]').prop('checked', true); $('div.disarm').hide(); } - $('._smallAngle').toggle(semver.gte(FC.CONFIG.apiVersion, "1.37.0")); - if(semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + $('._smallAngle').toggle(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)); + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { $('input[id="configurationSmallAngle"]').val(FC.ARMING_CONFIG.small_angle); } @@ -987,7 +987,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('div.batterymetertype').hide(); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { $('input[name="mincellvoltage"]').prop('step','0.01'); $('input[name="maxcellvoltage"]').prop('step','0.01'); $('input[name="warningcellvoltage"]').prop('step','0.01'); @@ -1153,7 +1153,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { }); $('input[id="accHardwareSwitch"]').change(function() { - if(semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { var checked = $(this).is(':checked'); $('.accelNeeded').toggle(checked); } @@ -1206,14 +1206,14 @@ TABS.configuration.initialize = function (callback, scrollPosition) { FC.ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val()); FC.ARMING_CONFIG.disarm_kill_switch = $('input[id="disarmkillswitch"]').is(':checked') ? 1 : 0; } - if(semver.gte(FC.CONFIG.apiVersion, "1.37.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_37)) { FC.ARMING_CONFIG.small_angle = parseInt($('input[id="configurationSmallAngle"]').val()); } FC.MOTOR_CONFIG.minthrottle = parseInt($('input[name="minthrottle"]').val()); FC.MOTOR_CONFIG.maxthrottle = parseInt($('input[name="maxthrottle"]').val()); FC.MOTOR_CONFIG.mincommand = parseInt($('input[name="mincommand"]').val()); - if(semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { FC.MOTOR_CONFIG.motor_poles = parseInt($('input[name="motorPoles"]').val()); } @@ -1234,7 +1234,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { FC.MOTOR_3D_CONFIG.neutral = parseInt($('input[name="3dneutral"]').val()); } - if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.SENSOR_ALIGNMENT.gyro_to_use = parseInt(orientation_gyro_to_use_e.val()); } @@ -1255,11 +1255,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) { FC.PID_ADVANCED_CONFIG.pid_process_denom = value; FC.PID_ADVANCED_CONFIG.digitalIdlePercent = parseFloat($('input[name="digitalIdlePercent"]').val()); - if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { FC.PID_ADVANCED_CONFIG.gyroUse32kHz = $('input[id="gyroUse32kHz"]').is(':checked') ? 1 : 0; } - if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_31)) { FC.RX_CONFIG.fpvCamAngleDegrees = parseInt($('input[name="fpvCamAngleDegrees"]').val()); } @@ -1278,7 +1278,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function save_beeper_config() { var next_callback = save_misc; - if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_36)) { MSP.send_message(MSPCodes.MSP_SET_BEEPER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BEEPER_CONFIG), false, next_callback); } else { next_callback(); @@ -1287,7 +1287,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function save_misc() { var next_callback = save_mixer_config; - if(semver.lt(FC.CONFIG.apiVersion, "1.33.0")) { + if(semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, next_callback); } else { next_callback(); @@ -1306,7 +1306,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function save_motor_config() { var next_callback = save_gps_config; - if(semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_SET_MOTOR_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_MOTOR_CONFIG), false, next_callback); } else { next_callback(); @@ -1314,13 +1314,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) { } function save_gps_config() { - if (semver.gte(FC.CONFIG.apiVersion, "1.34.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_34)) { FC.GPS_CONFIG.auto_baud = $('input[name="gps_auto_baud"]').is(':checked') ? 1 : 0; FC.GPS_CONFIG.auto_config = $('input[name="gps_auto_config"]').is(':checked') ? 1 : 0; } var next_callback = save_motor_3d_config; - if(semver.gte(FC.CONFIG.apiVersion, "1.33.0")) { + if(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) { MSP.send_message(MSPCodes.MSP_SET_GPS_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_GPS_CONFIG), false, next_callback); } else { next_callback(); @@ -1404,7 +1404,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function save_filter_config() { const next_callback = save_to_eeprom; - if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) { + if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_42)) { MSP.send_message(MSPCodes.MSP_SET_FILTER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FILTER_CONFIG), false, next_callback); } else { next_callback(); diff --git a/src/js/tabs/failsafe.js b/src/js/tabs/failsafe.js index df526e4b..3719a133 100644 --- a/src/js/tabs/failsafe.js +++ b/src/js/tabs/failsafe.js @@ -19,7 +19,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { function load_rxfail_config() { MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false, - semver.gte(FC.CONFIG.apiVersion, "1.41.0") ? load_gps_rescue : get_box_names); + semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41) ? load_gps_rescue : get_box_names); } function load_gps_rescue() { @@ -135,7 +135,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { for (i = 0; i < FC.RXFAIL_CONFIG.length; i++) { if (i < channelNames.length) { - if (semver.lt(FC.CONFIG.apiVersion, "1.41.0")) { + if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_41)) { fullChannels_e.append('\