From 97c622fbb1c7bcddc61b50393aa8d1109d9dab9f Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 26 Feb 2019 09:12:04 +0100 Subject: [PATCH 1/3] 1.7 family removed --- js/fc.js | 59 ++++------------ js/msp/MSPHelper.js | 144 ++++++++++++++------------------------ tabs/advanced_tuning.html | 4 +- tabs/advanced_tuning.js | 87 +++++++++++------------ tabs/configuration.html | 2 +- tabs/configuration.js | 6 -- tabs/failsafe.html | 36 +++++----- tabs/failsafe.js | 59 +++++++--------- tabs/osd.js | 22 ++---- tabs/ports.js | 34 ++++----- tabs/profiles.js | 18 ++--- 11 files changed, 175 insertions(+), 296 deletions(-) diff --git a/js/fc.js b/js/fc.js index 13e7d256..1e99310c 100644 --- a/js/fc.js +++ b/js/fc.js @@ -576,11 +576,9 @@ var FC = { {bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false} ); - if (semver.gte(CONFIG.flightControllerVersion, '1.7.3')) { - features.push( - {bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false} - ); - } + features.push( + {bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false} + ); if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { features.push( @@ -697,22 +695,14 @@ var FC = { ]; }, getGpsProtocols: function () { - var data = [ + return [ 'NMEA', 'UBLOX', 'I2C-NAV', - 'DJI NAZA' + 'DJI NAZA', + 'UBLOX7', + 'MTK' ]; - - if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) { - data.push('UBLOX7') - } - - if (semver.gte(CONFIG.flightControllerVersion, "1.7.2")) { - data.push('MTK') - } - - return data; }, getGpsBaudRates: function () { return [ @@ -769,12 +759,10 @@ var FC = { // Versions using feature bits don't allow not having an // RX and fallback to RX_PPM. - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - rxTypes.push({ - name: 'RX_NONE', - value: 0, - }); - } + rxTypes.push({ + name: 'RX_NONE', + value: 0, + }); return rxTypes; }, @@ -788,25 +776,10 @@ var FC = { } } } - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - return RX_CONFIG.receiver_type == rxType.value; - } - return bit_check(BF_CONFIG.features, rxType.bit); + return RX_CONFIG.receiver_type == rxType.value; }, setRxTypeEnabled: function(rxType) { - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - RX_CONFIG.receiver_type = rxType.value; - } else { - // Clear other rx features before - var rxTypes = this.getRxTypes(); - for (var ii = 0; ii < rxTypes.length; ii++) { - BF_CONFIG.features = bit_clear(BF_CONFIG.features, rxTypes[ii].bit); - } - // Set the feature for this rx type (if any, RX_NONE is set by clearing all) - if (rxType.bit !== undefined) { - BF_CONFIG.features = bit_set(BF_CONFIG.features, rxType.bit); - } - } + RX_CONFIG.receiver_type = rxType.value; }, getSerialRxTypes: function () { var data = [ @@ -1070,11 +1043,7 @@ var FC = { return ["Current", "Extra", "Fixed", "Max", "At Least"]; }, getRthAllowLanding: function() { - var values = ["Never", "Always"]; - if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) { - values.push("Only on failsafe"); - } - return values; + return ["Never", "Always", "Only on failsafe"]; }, getFailsafeProcedure: function () { return { diff --git a/js/msp/MSPHelper.js b/js/msp/MSPHelper.js index 20d8f3b0..d743adff 100644 --- a/js/msp/MSPHelper.js +++ b/js/msp/MSPHelper.js @@ -93,12 +93,6 @@ var mspHelper = (function (gui) { CONFIG.cycleTime = data.getUint16(0, true); CONFIG.i2cError = data.getUint16(2, true); CONFIG.activeSensors = data.getUint16(4, true); - - /* For 1.7.4+ MSP_ACTIVEBOXES should be used to determine active modes */ - if (semver.lt(CONFIG.flightControllerVersion, "1.7.4")) { - CONFIG.mode = data.getUint32(6, true); - } - CONFIG.profile = data.getUint8(10); CONFIG.cpuload = data.getUint16(11, true); CONFIG.armingFlags = data.getUint16(13, true); @@ -867,12 +861,10 @@ var mspHelper = (function (gui) { RX_CONFIG.spirx_channel_count = data.getUint8(offset); offset += 1; } - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - // unused byte for fpvCamAngleDegrees, for compatiblity with betaflight - offset += 1; - RX_CONFIG.receiver_type = data.getUint8(offset); - offset += 1; - } + // unused byte for fpvCamAngleDegrees, for compatiblity with betaflight + offset += 1; + RX_CONFIG.receiver_type = data.getUint8(offset); + offset += 1; break; case MSPCodes.MSP_FAILSAFE_CONFIG: @@ -888,24 +880,20 @@ var mspHelper = (function (gui) { offset += 2; FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset); offset++; - if (semver.gte(CONFIG.flightControllerVersion, "1.7.3")) { - FAILSAFE_CONFIG.failsafe_recovery_delay = data.getUint8(offset); - offset++; - FAILSAFE_CONFIG.failsafe_fw_roll_angle = data.getUint16(offset, true); - offset += 2; - FAILSAFE_CONFIG.failsafe_fw_pitch_angle = data.getUint16(offset, true); - offset += 2; - FAILSAFE_CONFIG.failsafe_fw_yaw_rate = data.getUint16(offset, true); - offset += 2; - FAILSAFE_CONFIG.failsafe_stick_motion_threshold = data.getUint16(offset, true); - offset += 2; - } - if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) { - FAILSAFE_CONFIG.failsafe_min_distance = data.getUint16(offset, true); - offset += 2; - FAILSAFE_CONFIG.failsafe_min_distance_procedure = data.getUint8(offset); - offset++; - } + FAILSAFE_CONFIG.failsafe_recovery_delay = data.getUint8(offset); + offset++; + FAILSAFE_CONFIG.failsafe_fw_roll_angle = data.getUint16(offset, true); + offset += 2; + FAILSAFE_CONFIG.failsafe_fw_pitch_angle = data.getUint16(offset, true); + offset += 2; + FAILSAFE_CONFIG.failsafe_fw_yaw_rate = data.getUint16(offset, true); + offset += 2; + FAILSAFE_CONFIG.failsafe_stick_motion_threshold = data.getUint16(offset, true); + offset += 2; + FAILSAFE_CONFIG.failsafe_min_distance = data.getUint16(offset, true); + offset += 2; + FAILSAFE_CONFIG.failsafe_min_distance_procedure = data.getUint8(offset); + offset++; break; case MSPCodes.MSP_RXFAIL_CONFIG: @@ -1702,12 +1690,10 @@ var mspHelper = (function (gui) { buffer.push32(RX_CONFIG.spirx_id); buffer.push(RX_CONFIG.spirx_channel_count); } - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - // unused byte for fpvCamAngleDegrees, for compatiblity with betaflight - buffer.push(0); - // receiver type in RX_CONFIG rather than in BF_CONFIG.features - buffer.push(RX_CONFIG.receiver_type); - } + // unused byte for fpvCamAngleDegrees, for compatiblity with betaflight + buffer.push(0); + // receiver type in RX_CONFIG rather than in BF_CONFIG.features + buffer.push(RX_CONFIG.receiver_type); break; case MSPCodes.MSP_SET_FAILSAFE_CONFIG: @@ -1719,22 +1705,18 @@ var mspHelper = (function (gui) { buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay)); buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay)); buffer.push(FAILSAFE_CONFIG.failsafe_procedure); - if (semver.gte(CONFIG.flightControllerVersion, "1.7.3")) { - buffer.push(FAILSAFE_CONFIG.failsafe_recovery_delay); - buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle)); - buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle)); - buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_pitch_angle)); - buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_pitch_angle)); - buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate)); - buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate)); - buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold)); - buffer.push(highByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold)); - } - if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) { - buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_min_distance)); - buffer.push(highByte(FAILSAFE_CONFIG.failsafe_min_distance)); - buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure); - } + buffer.push(FAILSAFE_CONFIG.failsafe_recovery_delay); + buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle)); + buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle)); + buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_pitch_angle)); + buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_pitch_angle)); + buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate)); + buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate)); + buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold)); + buffer.push(highByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold)); + buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_min_distance)); + buffer.push(highByte(FAILSAFE_CONFIG.failsafe_min_distance)); + buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure); break; case MSPCodes.MSP_SET_TRANSPONDER_CONFIG: @@ -2897,35 +2879,19 @@ var mspHelper = (function (gui) { }; self.loadRthAndLandConfig = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) { - MSP.send_message(MSPCodes.MSP_RTH_AND_LAND_CONFIG, false, false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP_RTH_AND_LAND_CONFIG, false, false, callback); }; self.saveRthAndLandConfig = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) { - MSP.send_message(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG), false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG), false, callback); }; self.loadFwConfig = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) { - MSP.send_message(MSPCodes.MSP_FW_CONFIG, false, false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP_FW_CONFIG, false, false, callback); }; self.saveFwConfig = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) { MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback); - } else { - callback(); - } }; self.getMissionInfo = function (callback) { @@ -3117,31 +3083,23 @@ var mspHelper = (function (gui) { }; self.getRTC = function (callback) { - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - MSP.send_message(MSPCodes.MSP_RTC, false, false, function (resp) { - var seconds = resp.data.read32(); - var millis = resp.data.readU16(); - if (callback) { - callback(seconds, millis); - } - }); - } else if (callback) { - callback(0, 0); - } + MSP.send_message(MSPCodes.MSP_RTC, false, false, function (resp) { + var seconds = resp.data.read32(); + var millis = resp.data.readU16(); + if (callback) { + callback(seconds, millis); + } + }); }; self.setRTC = function (callback) { - if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) { - var now = Date.now(); - var secs = now / 1000; - var millis = now % 1000; - var data = []; - data.push32(secs); - data.push16(millis); - MSP.send_message(MSPCodes.MSP_SET_RTC, data, false, callback); - } else if (callback) { - callback(); - } + var now = Date.now(); + var secs = now / 1000; + var millis = now % 1000; + var data = []; + data.push32(secs); + data.push16(millis); + MSP.send_message(MSPCodes.MSP_SET_RTC, data, false, callback); }; self.loadServoConfiguration = function (callback) { diff --git a/tabs/advanced_tuning.html b/tabs/advanced_tuning.html index 0fd2addc..f6097c7e 100644 --- a/tabs/advanced_tuning.html +++ b/tabs/advanced_tuning.html @@ -58,7 +58,7 @@ -
+
@@ -214,7 +214,7 @@
-
+
diff --git a/tabs/advanced_tuning.js b/tabs/advanced_tuning.js index 20bb666d..54305fef 100644 --- a/tabs/advanced_tuning.js +++ b/tabs/advanced_tuning.js @@ -68,53 +68,46 @@ TABS.advanced_tuning.initialize = function (callback) { $('.requires-v2_1').hide(); } - if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) { - - $rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst); - $rthClimbFirst.change(function () { - if ($(this).is(":checked")) { - RTH_AND_LAND_CONFIG.rthClimbFirst = 1; - } else { - RTH_AND_LAND_CONFIG.rthClimbFirst = 0; - } - }); - $rthClimbFirst.change(); - - $rthClimbIgnoreEmergency.prop("checked", RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency); - $rthClimbIgnoreEmergency.change(function () { - if ($(this).is(":checked")) { - RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency = 1; - } else { - RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency = 0; - } - }); - $rthClimbIgnoreEmergency.change(); - - $rthTailFirst.prop("checked", RTH_AND_LAND_CONFIG.rthTailFirst); - $rthTailFirst.change(function () { - if ($(this).is(":checked")) { - RTH_AND_LAND_CONFIG.rthTailFirst = 1; - } else { - RTH_AND_LAND_CONFIG.rthTailFirst = 0; - } - }); - $rthTailFirst.change(); - - GUI.fillSelect($rthAltControlMode, FC.getRthAltControlMode(), RTH_AND_LAND_CONFIG.rthAltControlMode); - $rthAltControlMode.val(RTH_AND_LAND_CONFIG.rthAltControlMode); - $rthAltControlMode.change(function () { - RTH_AND_LAND_CONFIG.rthAltControlMode = $rthAltControlMode.val(); - }); - GUI.fillSelect($rthAllowLanding, FC.getRthAllowLanding(), RTH_AND_LAND_CONFIG.rthAllowLanding); - $rthAllowLanding.val(RTH_AND_LAND_CONFIG.rthAllowLanding); - $rthAllowLanding.change(function () { - RTH_AND_LAND_CONFIG.rthAllowLanding = $rthAllowLanding.val(); - }); - - $('.requires-v1_7_1').show(); - } else { - $('.requires-v1_7_1').hide(); - } + $rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst); + $rthClimbFirst.change(function () { + if ($(this).is(":checked")) { + RTH_AND_LAND_CONFIG.rthClimbFirst = 1; + } else { + RTH_AND_LAND_CONFIG.rthClimbFirst = 0; + } + }); + $rthClimbFirst.change(); + + $rthClimbIgnoreEmergency.prop("checked", RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency); + $rthClimbIgnoreEmergency.change(function () { + if ($(this).is(":checked")) { + RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency = 1; + } else { + RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency = 0; + } + }); + $rthClimbIgnoreEmergency.change(); + + $rthTailFirst.prop("checked", RTH_AND_LAND_CONFIG.rthTailFirst); + $rthTailFirst.change(function () { + if ($(this).is(":checked")) { + RTH_AND_LAND_CONFIG.rthTailFirst = 1; + } else { + RTH_AND_LAND_CONFIG.rthTailFirst = 0; + } + }); + $rthTailFirst.change(); + + GUI.fillSelect($rthAltControlMode, FC.getRthAltControlMode(), RTH_AND_LAND_CONFIG.rthAltControlMode); + $rthAltControlMode.val(RTH_AND_LAND_CONFIG.rthAltControlMode); + $rthAltControlMode.change(function () { + RTH_AND_LAND_CONFIG.rthAltControlMode = $rthAltControlMode.val(); + }); + GUI.fillSelect($rthAllowLanding, FC.getRthAllowLanding(), RTH_AND_LAND_CONFIG.rthAllowLanding); + $rthAllowLanding.val(RTH_AND_LAND_CONFIG.rthAllowLanding); + $rthAllowLanding.change(function () { + RTH_AND_LAND_CONFIG.rthAllowLanding = $rthAllowLanding.val(); + }); GUI.fillSelect($userControlMode, FC.getUserControlMode(), NAV_POSHOLD.userControlMode); $userControlMode.val(NAV_POSHOLD.userControlMode); diff --git a/tabs/configuration.html b/tabs/configuration.html index 6fb625ea..34c6a7ee 100644 --- a/tabs/configuration.html +++ b/tabs/configuration.html @@ -51,7 +51,7 @@
-
+
diff --git a/tabs/configuration.js b/tabs/configuration.js index 6036673f..da0a4032 100644 --- a/tabs/configuration.js +++ b/tabs/configuration.js @@ -736,12 +736,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) { SENSOR_CONFIG.opflow = $sensorOpflow.val(); }); - if (semver.gte(CONFIG.flightControllerVersion, "1.7.0")) { - $(".requires-v1_7").show(); - } else { - $(".requires-v1_7").hide(); - } - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { $(".requires-v1_8_1").show(); } else { diff --git a/tabs/failsafe.html b/tabs/failsafe.html index e86e2c85..6e4f2412 100644 --- a/tabs/failsafe.html +++ b/tabs/failsafe.html @@ -80,28 +80,26 @@
-
-
-
- -
- -
+
+
+
+ +
+
-
- -
-
+
+ +
+
-
- - -
-
+
+ + +
diff --git a/tabs/failsafe.js b/tabs/failsafe.js index a4b5ce60..ccc02c35 100644 --- a/tabs/failsafe.js +++ b/tabs/failsafe.js @@ -196,9 +196,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { $('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay); $('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay); $('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay); - if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) { - $('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance); - } + $('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance); // set stage 2 failsafe procedure $('input[type="radio"].procedure').change(function () { @@ -249,44 +247,39 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { // set stage 2 kill switch option $('input[name="failsafe_kill_switch"]').prop('checked', FAILSAFE_CONFIG.failsafe_kill_switch); - if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) { - // Adjust Minimum Distance values when checkbox is checked/unchecked - $failsafeUseMinimumDistanceCheckbox.change(function() { - if ($(this).is(':checked')) { - // 20 meters seems like a reasonable default for a minimum distance - $failsafeMinDistance.val(2000); - $failsafeMinDistanceElements.show(); - $failsafeMinDistanceProcedureElements.show(); - } else { - // If they uncheck it, clear the distance to 0, which disables this feature - $failsafeMinDistance.val(0); - $failsafeMinDistanceElements.hide(); - $failsafeMinDistanceProcedureElements.hide(); - } - }); - - // Set initial state of controls according to data - if (FAILSAFE_CONFIG.failsafe_min_distance > 0) { - $failsafeUseMinimumDistanceCheckbox.prop('checked', true); + // Adjust Minimum Distance values when checkbox is checked/unchecked + $failsafeUseMinimumDistanceCheckbox.change(function() { + if ($(this).is(':checked')) { + // 20 meters seems like a reasonable default for a minimum distance + $failsafeMinDistance.val(2000); $failsafeMinDistanceElements.show(); $failsafeMinDistanceProcedureElements.show(); } else { - $failsafeUseMinimumDistanceCheckbox.prop('checked', false); + // If they uncheck it, clear the distance to 0, which disables this feature + $failsafeMinDistance.val(0); $failsafeMinDistanceElements.hide(); $failsafeMinDistanceProcedureElements.hide(); } + }); - // Alternate, minimum distance failsafe procedure - GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure); - $failsafeMinDistanceProcedure.val(FAILSAFE_CONFIG.failsafe_min_distance_procedure); - $failsafeMinDistanceProcedure.change(function () { - FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val(); - }); - $('.requires-v1_7_4').show(); + // Set initial state of controls according to data + if (FAILSAFE_CONFIG.failsafe_min_distance > 0) { + $failsafeUseMinimumDistanceCheckbox.prop('checked', true); + $failsafeMinDistanceElements.show(); + $failsafeMinDistanceProcedureElements.show(); } else { - $('.requires-v1_7_4').hide(); + $failsafeUseMinimumDistanceCheckbox.prop('checked', false); + $failsafeMinDistanceElements.hide(); + $failsafeMinDistanceProcedureElements.hide(); } + // Alternate, minimum distance failsafe procedure + GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure); + $failsafeMinDistanceProcedure.val(FAILSAFE_CONFIG.failsafe_min_distance_procedure); + $failsafeMinDistanceProcedure.change(function () { + FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val(); + }); + $('a.save').click(function () { // gather data that doesn't have automatic change event bound RX_CONFIG.rx_min_usec = parseInt($('input[name="rx_min_usec"]').val()); @@ -296,9 +289,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val()); FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val()); FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val()); - if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) { - FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val()); - } + FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val()); if ($('input[id="land"]').is(':checked')) { FAILSAFE_CONFIG.failsafe_procedure = 0; diff --git a/tabs/osd.js b/tabs/osd.js index 79a5721a..94369e92 100644 --- a/tabs/osd.js +++ b/tabs/osd.js @@ -349,10 +349,7 @@ function altitude_alarm_from_display(osd_data, value) { // depending on the OSD display unit used (hence, no conversion) function altitude_alarm_display_function(fn) { return function(osd_data, value) { - if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) { - return fn(osd_data, value) - } - return value; + return fn(osd_data, value) } } @@ -433,7 +430,7 @@ OSD.constants = { UNIT_TYPES: [ {name: 'osdUnitImperial', value: 0}, {name: 'osdUnitMetric', value: 1}, - {name: 'osdUnitUK', tip: 'osdUnitUKTip', value: 2, min_version: "1.7.3"}, + {name: 'osdUnitUK', tip: 'osdUnitUKTip', value: 2}, ], AHISIDEBARWIDTHPOSITION: 7, AHISIDEBARHEIGHTPOSITION: 3, @@ -560,7 +557,6 @@ OSD.constants = { { name: 'MAIN_BATT_CELL_VOLTAGE', id: 32, - min_version: '1.7.4', preview: FONT.symbol(SYM.VOLT) + FONT.embed_dot('3.90V') }, { @@ -607,7 +603,6 @@ OSD.constants = { { name: 'THROTTLE_POSITION_AUTO_THR', id: 33, - min_version: '1.7.4', preview: FONT.symbol(SYM.THR) + FONT.symbol(SYM.THR1) + ' 51' }, { @@ -623,7 +618,6 @@ OSD.constants = { { name: 'MESSAGES', id: 30, - min_version: '1.7.4', preview: ' SYSTEM MESSAGE ', // 28 chars, like OSD_MESSAGE_LENGTH on osd.c }, { @@ -634,7 +628,6 @@ OSD.constants = { { name: 'HEADING_GRAPH', id: 34, - min_version: '1.7.4', preview: FONT.symbol(SYM.HEADING_W) + FONT.symbol(SYM.HEADING_LINE) + FONT.symbol(SYM.HEADING_DIVIDED_LINE) + @@ -648,7 +641,6 @@ OSD.constants = { { name: 'AIR_SPEED', id: 27, - min_version: '1.7.3', enabled: function() { return SENSOR_CONFIG.pitot != 0; }, @@ -666,7 +658,6 @@ OSD.constants = { { name: 'RTC_TIME', id: 29, - min_version: '1.7.4', preview: FONT.symbol(SYM.CLOCK) + '13:37' }, ] @@ -852,7 +843,6 @@ OSD.constants = { { name: 'ONTIME_FLYTIME', id: 28, - min_version: '1.7.4', preview: FONT.symbol(SYM.FLY_M) + '04:11' }, { @@ -939,7 +929,6 @@ OSD.constants = { { name: 'EFFICIENCY_MAH', id: 35, - min_version: '1.7.4', preview: "123" + FONT.symbol(SYM.MAH_KM_0) + FONT.symbol(SYM.MAH_KM_1) }, { @@ -1054,7 +1043,6 @@ OSD.constants = { { name: 'GPS_HDOP', id: 31, - min_version: '1.7.4', preview: FONT.symbol(SYM.GPS_HDP1) + FONT.symbol(SYM.GPS_HDP2) + FONT.embed_dot('1.8') }, { @@ -1631,10 +1619,8 @@ OSD.msp = { d.alarms.fly_minutes = view.readU16(); d.alarms.max_altitude = view.readU16(); - if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) { - d.alarms.dist = view.readU16(); - d.alarms.max_neg_altitude = view.readU16(); - } + d.alarms.dist = view.readU16(); + d.alarms.max_neg_altitude = view.readU16(); d.items = []; // start at the offset from the other fields diff --git a/tabs/ports.js b/tabs/ports.js index facee252..355e9da4 100644 --- a/tabs/ports.js +++ b/tabs/ports.js @@ -43,26 +43,22 @@ TABS.ports.initialize = function (callback) { } // support configure RunCam Device - if (semver.gte(CONFIG.flightControllerVersion, "1.7.3")) { - functionRules.push({ - name: 'RUNCAM_DEVICE_CONTROL', - groups: ['peripherals'], - maxPorts: 1 } - ); - } + functionRules.push({ + name: 'RUNCAM_DEVICE_CONTROL', + groups: ['peripherals'], + maxPorts: 1 } + ); - if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) { - functionRules.push({ - name: 'TBS_SMARTAUDIO', - groups: ['peripherals'], - maxPorts: 1 } - ); - functionRules.push({ - name: 'IRC_TRAMP', - groups: ['peripherals'], - maxPorts: 1 } - ); - } + functionRules.push({ + name: 'TBS_SMARTAUDIO', + groups: ['peripherals'], + maxPorts: 1 } + ); + functionRules.push({ + name: 'IRC_TRAMP', + groups: ['peripherals'], + maxPorts: 1 } + ); for (var i = 0; i < functionRules.length; i++) { functionRules[i].displayName = chrome.i18n.getMessage('portsFunction_' + functionRules[i].name); diff --git a/tabs/profiles.js b/tabs/profiles.js index 9a54cb4c..0e9158cd 100644 --- a/tabs/profiles.js +++ b/tabs/profiles.js @@ -546,11 +546,7 @@ presets.model = (function () { if (mixerType == 'airplane' || mixerType == 'flyingwing') { // Always set MOTOR_STOP and feature AIRMODE for fixed wing window.BF_CONFIG.features |= 1 << 4; // MOTOR_STOP - if (semver.gt(CONFIG.flightControllerVersion, '1.7.2')) { - // Note that feature_AIRMODE is only supported on - // INAV > 1.7.2. - window.BF_CONFIG.features |= 1 << 22; // AIRMODE - } + window.BF_CONFIG.features |= 1 << 22; // AIRMODE } }; @@ -643,13 +639,11 @@ TABS.profiles.initialize = function (callback, scrollPosition) { } } var promises = {}; - if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) { - var settings = presets.settings.get(currentPreset.type); - Object.keys(settings).forEach(function(key, ii) { - var value = settings[key]; - promises[key] = mspHelper.setSetting(name, value); - }); - } + var settings = presets.settings.get(currentPreset.type); + Object.keys(settings).forEach(function(key, ii) { + var value = settings[key]; + promises[key] = mspHelper.setSetting(name, value); + }); Promise.props(promises).then(function () { saveChainer.execute(); }); From 521915b5a9ec4c75255bfe1adce1b5adc610b342 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 26 Feb 2019 15:23:04 +0100 Subject: [PATCH 2/3] 1.8 removed --- _locales/en/messages.json | 2 +- js/fc.js | 10 ++--- js/msp/MSPHelper.js | 62 +++++++------------------- js/periodicStatusUpdater.js | 35 ++++----------- main.js | 1 - tabs/adjustments.js | 6 +-- tabs/calibration.js | 88 ++++++++----------------------------- tabs/configuration.html | 2 +- tabs/configuration.js | 34 ++------------ tabs/osd.js | 4 -- tabs/pid_tuning.js | 13 +----- tabs/receiver.js | 13 +----- tabs/setup.html | 12 ++--- tabs/setup.js | 41 +++++++---------- 14 files changed, 77 insertions(+), 246 deletions(-) diff --git a/_locales/en/messages.json b/_locales/en/messages.json index b8fe5757..f26f6a98 100755 --- a/_locales/en/messages.json +++ b/_locales/en/messages.json @@ -847,7 +847,7 @@ "message": "Note: Do NOT disable MSP on the first serial port unless you know what you are doing. You may have to reflash and erase your configuration if you do." }, "portsFirmwareUpgradeRequired": { - "message": "Firmware upgrade required. Serial port configurations of firmware < 1.8.0 is not supported." + "message": "Firmware upgrade required." }, "portsButtonSave": { "message": "Save and Reboot" diff --git a/js/fc.js b/js/fc.js index 1e99310c..70393751 100644 --- a/js/fc.js +++ b/js/fc.js @@ -580,12 +580,10 @@ var FC = { {bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false} ); - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - features.push( - {bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false}, - {bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false} - ); - } + features.push( + {bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false}, + {bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false} + ); if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) { features.push( diff --git a/js/msp/MSPHelper.js b/js/msp/MSPHelper.js index d743adff..b0556947 100644 --- a/js/msp/MSPHelper.js +++ b/js/msp/MSPHelper.js @@ -1229,10 +1229,6 @@ var mspHelper = (function (gui) { break; case MSPCodes.MSP_CALIBRATION_DATA: - if (semver.lte(CONFIG.flightControllerVersion, "1.8.0")) { - break; - } - var callibrations = data.getUint8(0); CALIBRATION_DATA.acc.Pos0 = (1 & (callibrations >> 0)); CALIBRATION_DATA.acc.Pos1 = (1 & (callibrations >> 1)); @@ -2253,10 +2249,6 @@ var mspHelper = (function (gui) { self.sendMotorMixer = function (onCompleteCallback) { - if (semver.lt(CONFIG.flightControllerVersion, "1.8.1")) { - onCompleteCallback(); - } - var nextFunction = sendMixer, servoIndex = 0; @@ -2863,19 +2855,11 @@ var mspHelper = (function (gui) { }; self.loadCalibrationData = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - MSP.send_message(MSPCodes.MSP_CALIBRATION_DATA, false, false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP_CALIBRATION_DATA, false, false, callback); }; self.saveCalibrationData = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - MSP.send_message(MSPCodes.MSP_SET_CALIBRATION_DATA, mspHelper.crunch(MSPCodes.MSP_SET_CALIBRATION_DATA), false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP_SET_CALIBRATION_DATA, mspHelper.crunch(MSPCodes.MSP_SET_CALIBRATION_DATA), false, callback); }; self.loadRthAndLandConfig = function (callback) { @@ -2895,11 +2879,7 @@ var mspHelper = (function (gui) { }; self.getMissionInfo = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback); }; self._getSetting = function (name) { @@ -3111,11 +3091,7 @@ var mspHelper = (function (gui) { }; self.loadMotorMixRules = function (callback) { - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - MSP.send_message(MSPCodes.MSP2_COMMON_MOTOR_MIXER, false, false, callback); - } else { - callback(); - } + MSP.send_message(MSPCodes.MSP2_COMMON_MOTOR_MIXER, false, false, callback); }; self.loadMotors = function (callback) { @@ -3123,29 +3099,21 @@ var mspHelper = (function (gui) { }; self.getCraftName = function(callback) { - if (semver.gt(CONFIG.flightControllerVersion, "1.8.0")) { - MSP.send_message(MSPCodes.MSP_NAME, false, false, function(resp) { - var name = resp.data.readString(); - if (callback) { - callback(name); - } - }); - } else if (callback) { - callback(null); - } + MSP.send_message(MSPCodes.MSP_NAME, false, false, function(resp) { + var name = resp.data.readString(); + if (callback) { + callback(name); + } + }); }; self.setCraftName = function(name, callback) { - if (semver.gt(CONFIG.flightControllerVersion, "1.8.0")) { - var data = []; - name = name || ""; - for (var ii = 0; ii < name.length; ii++) { - data.push(name.charCodeAt(ii)); - } - MSP.send_message(MSPCodes.MSP_SET_NAME, data, false, callback); - } else if (callback) { - callback(); + var data = []; + name = name || ""; + for (var ii = 0; ii < name.length; ii++) { + data.push(name.charCodeAt(ii)); } + MSP.send_message(MSPCodes.MSP_SET_NAME, data, false, callback); }; self.loadMixerConfig = function (callback) { diff --git a/js/periodicStatusUpdater.js b/js/periodicStatusUpdater.js index 7768a0fc..924bef30 100644 --- a/js/periodicStatusUpdater.js +++ b/js/periodicStatusUpdater.js @@ -53,30 +53,16 @@ helper.periodicStatusUpdater = (function () { if (ANALOG != undefined) { var nbCells; - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - nbCells = ANALOG.cell_count; - } else { - nbCells = Math.floor(ANALOG.voltage / MISC.vbatmaxcellvoltage) + 1; - if (ANALOG.voltage == 0) - nbCells = 1; - } - + nbCells = ANALOG.cell_count; var min = MISC.vbatmincellvoltage * nbCells; var max = MISC.vbatmaxcellvoltage * nbCells; var warn = MISC.vbatwarningcellvoltage * nbCells; - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - $(".battery-status").css({ - width: ANALOG.battery_percentage + "%", - display: 'inline-block' - }); - } else { - $(".battery-status").css({ - width: ((ANALOG.voltage - min) / (max - min) * 100) + "%", - display: 'inline-block' - }); - } - + $(".battery-status").css({ + width: ANALOG.battery_percentage + "%", + display: 'inline-block' + }); + if (active) { $(".linkicon").css({ 'background-image': 'url("../images/icons/cf_icon_link_active.svg")' @@ -87,7 +73,7 @@ helper.periodicStatusUpdater = (function () { }); } - if (((semver.gte(CONFIG.flightControllerVersion, '1.8.1')) && (((ANALOG.use_capacity_thresholds) && (ANALOG.battery_remaining_capacity <= (MISC.battery_capacity_warning - MISC.battery_capacity_critical))) || ((!ANALOG.use_capacity_thresholds) && (ANALOG.voltage < warn))) || (ANALOG.voltage < min)) || ((semver.lt(CONFIG.flightControllerVersion, '1.8.1')) && (ANALOG.voltage < warn))) { + if (((ANALOG.use_capacity_thresholds && ANALOG.battery_remaining_capacity <= MISC.battery_capacity_warning - MISC.battery_capacity_critical) || (!ANALOG.use_capacity_thresholds && ANALOG.voltage < warn)) || ANALOG.voltage < min) { $(".battery-status").css('background-color', '#D42133'); } else { $(".battery-status").css('background-color', '#59AA29'); @@ -124,12 +110,7 @@ helper.periodicStatusUpdater = (function () { } MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false); - - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false); - } else { - MSP.send_message(MSPCodes.MSP_ANALOG, false, false); - } + MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false); privateScope.updateView(); } diff --git a/main.js b/main.js index befd88ee..08e91438 100644 --- a/main.js +++ b/main.js @@ -123,7 +123,6 @@ $(document).ready(function () { } }); - //set '1.8.0' for test appUpdater.checkRelease(chrome.runtime.getManifest().version); // log library versions in console to make version tracking easier diff --git a/tabs/adjustments.js b/tabs/adjustments.js index a36a2e6e..3821ecc7 100644 --- a/tabs/adjustments.js +++ b/tabs/adjustments.js @@ -64,11 +64,7 @@ TABS.adjustments.initialize = function (callback) { // update list of selected functions var functionListOptions = $(functionList).find('option'); - var availableFunctionCount = 21; - - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - availableFunctionCount = 32; - } + var availableFunctionCount = 32; var functionListOptions = $(functionListOptions).slice(0,availableFunctionCount); functionList.empty().append(functionListOptions); diff --git a/tabs/calibration.js b/tabs/calibration.js index d3b73631..fa0b830a 100755 --- a/tabs/calibration.js +++ b/tabs/calibration.js @@ -52,30 +52,20 @@ TABS.calibration.initialize = function (callback) { GUI.active_tab = 'calibration'; googleAnalytics.sendAppView('Calibration'); } - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - loadChainer.setChain([ - mspHelper.loadStatus, - mspHelper.loadSensorConfig, - mspHelper.loadCalibrationData - ]); - loadChainer.setExitPoint(loadHtml); - loadChainer.execute(); - - saveChainer.setChain([ - mspHelper.saveCalibrationData - ]); - saveChainer.setExitPoint(reboot); - - MSP.send_message(MSPCodes.MSP_IDENT, false, false, loadHtml); - } else { - loadChainer.setChain([ - mspHelper.loadStatus - ]); - loadChainer.setExitPoint(loadHtml); - loadChainer.execute(); - - saveChainer.setExitPoint(reboot); - } + loadChainer.setChain([ + mspHelper.loadStatus, + mspHelper.loadSensorConfig, + mspHelper.loadCalibrationData + ]); + loadChainer.setExitPoint(loadHtml); + loadChainer.execute(); + + saveChainer.setChain([ + mspHelper.saveCalibrationData + ]); + saveChainer.setExitPoint(reboot); + + MSP.send_message(MSPCodes.MSP_IDENT, false, false, loadHtml); function reboot() { //noinspection JSUnresolvedVariable @@ -132,32 +122,6 @@ TABS.calibration.initialize = function (callback) { updateSensorData(); } - //For 1.8.0 - function calibrate() { - var self = $(this); - - if (!self.hasClass('disabled')) { - self.addClass('disabled'); - MSP.send_message(MSPCodes.MSP_ACC_CALIBRATION, false, false, function () { - GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibStarted')); - }); - - helper.timeout.add('button_reset', function () { - GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibEnded')); - - self.removeClass('disabled'); - - if (!bit_check(CONFIG.armingFlags & 0xff00, 13)) { - for (var i = 0; i < 6; i++) { - CALIBRATION_DATA.acc['Pos' + i] = 1; - } - updateCalibrationSteps(); - } - - }, 2000); - } - } - function calibrateNew() { var newStep = null, $button = $(this); @@ -215,17 +179,6 @@ TABS.calibration.initialize = function (callback) { saveChainer.execute(); }); - if (semver.lte(CONFIG.flightControllerVersion, "1.8.0")) { - $('#accPosAll, #mag-calibrated-data').hide(); - - var accIsCalibrate = +(!bit_check(CONFIG.armingFlags & 0xff00, 13)); - for (var i = 0; i < 6; i++) { - CALIBRATION_DATA.acc['Pos' + i] = accIsCalibrate; - } - - updateCalibrationSteps(); - } - if (SENSOR_CONFIG.magnetometer === 0) { //Comment for test $('#mag_btn, #mag-calibrated-data').css('pointer-events', 'none').css('opacity', '0.4'); @@ -258,9 +211,7 @@ TABS.calibration.initialize = function (callback) { modalProcessing.close(); GUI.log(chrome.i18n.getMessage('initialSetupMagCalibEnded')); - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - MSP.send_message(MSPCodes.MSP_CALIBRATION_DATA, false, false, updateSensorData); - } + MSP.send_message(MSPCodes.MSP_CALIBRATION_DATA, false, false, updateSensorData); helper.interval.remove('compass_calibration_interval'); } }, 1000); @@ -277,13 +228,10 @@ TABS.calibration.initialize = function (callback) { // translate to user-selected language localize(); - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - $('#calibrate-start-button').on('click', calibrateNew); - MSP.send_message(MSPCodes.MSP_CALIBRATION_DATA, false, false, updateSensorData); - } else { - $('#calibrate-start-button').on('click', calibrate); - } + $('#calibrate-start-button').on('click', calibrateNew); + MSP.send_message(MSPCodes.MSP_CALIBRATION_DATA, false, false, updateSensorData); + GUI.content_ready(callback); } }; diff --git a/tabs/configuration.html b/tabs/configuration.html index 34c6a7ee..aec756b8 100644 --- a/tabs/configuration.html +++ b/tabs/configuration.html @@ -495,7 +495,7 @@ -
+
diff --git a/tabs/configuration.js b/tabs/configuration.js index da0a4032..c27ca591 100644 --- a/tabs/configuration.js +++ b/tabs/configuration.js @@ -44,12 +44,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { loadCraftName ]; - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - loadChain.push(mspHelper.loadMiscV2); - } else { - loadChain.push(mspHelper.loadMisc); - } - + loadChain.push(mspHelper.loadMiscV2); loadChainer.setChain(loadChain); loadChainer.setExitPoint(load_html); loadChainer.execute(); @@ -71,12 +66,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { saveCraftName, ]; - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - saveChain.push(mspHelper.saveMiscV2); - } else { - saveChain.push(mspHelper.saveMisc); - } - + saveChain.push(mspHelper.saveMiscV2); saveChain.push(mspHelper.saveToEeprom); saveChainer.setChain(saveChain); @@ -417,14 +407,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('#maxthrottle').val(MISC.maxthrottle); $('#mincommand').val(MISC.mincommand); - // Battery thresholds resolution is 100mV and voltage scale max is 255 before 1.8.1 - if (semver.lt(CONFIG.flightControllerVersion, '1.8.1')) { - $('#mincellvoltage').attr('step', '0.1'); - $('#maxcellvoltage').attr('step', '0.1'); - $('#warningcellvoltage').attr('step', '0.1'); - $('#voltagescale').attr('max', '255'); - } - // fill battery voltage $('#voltagesource').val(MISC.voltage_source); $('#cells').val(MISC.battery_cells); @@ -736,12 +718,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) { SENSOR_CONFIG.opflow = $sensorOpflow.val(); }); - if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) { - $(".requires-v1_8_1").show(); - } else { - $(".requires-v1_8_1").hide(); - } - if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { $(".requires-v2_0_0").show(); } else { @@ -903,11 +879,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { }); helper.interval.add('config_load_analog', function () { - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - $('#batteryvoltage').val([ANALOG.voltage.toFixed(2)]); - } else { - $('#batteryvoltage').val([ANALOG.voltage.toFixed(1)]); - } + $('#batteryvoltage').val([ANALOG.voltage.toFixed(2)]); $('#batterycurrent').val([ANALOG.amperage.toFixed(2)]); }, 100, true); // 10 fps diff --git a/tabs/osd.js b/tabs/osd.js index 94369e92..6ffd9496 100644 --- a/tabs/osd.js +++ b/tabs/osd.js @@ -574,7 +574,6 @@ OSD.constants = { { name: 'MAIN_BATT_REMAINING_PERCENTAGE', id: 38, - min_version: '1.8.1', preview: '100%' }, { @@ -912,7 +911,6 @@ OSD.constants = { { name: 'WH_DRAWN', id: 36, - min_version: '1.8.1', preview: FONT.symbol(SYM.WH) + FONT.embed_dot('1.25') }, { @@ -923,7 +921,6 @@ OSD.constants = { { name: 'MAIN_BATT_REMAINING_CAPACITY', id: 37, - min_version: '1.8.1', preview: FONT.symbol(SYM.MAH) + '690 ' // 4 chars }, { @@ -934,7 +931,6 @@ OSD.constants = { { name: 'EFFICIENCY_WH', id: 39, - min_version: '1.8.1', preview: FONT.embed_dot('1.23') + FONT.symbol(SYM.WH_KM_0) + FONT.symbol(SYM.WH_KM_1) } ] diff --git a/tabs/pid_tuning.js b/tabs/pid_tuning.js index 6b101060..9aa67682 100755 --- a/tabs/pid_tuning.js +++ b/tabs/pid_tuning.js @@ -16,12 +16,7 @@ TABS.pid_tuning.initialize = function (callback) { mspHelper.loadPidAdvanced, mspHelper.loadFilterConfig ]; - - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - loadChain.push(mspHelper.loadRateProfileData); - } else { - loadChain.push(mspHelper.loadRcTuningData); - } + loadChain.push(mspHelper.loadRateProfileData); loadChainer.setChain(loadChain); loadChainer.setExitPoint(load_html); @@ -233,11 +228,7 @@ TABS.pid_tuning.initialize = function (callback) { } function send_rc_tuning_changes() { - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - MSP.send_message(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE, mspHelper.crunch(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE), false, saveINAVPidConfig); - } else { - MSP.send_message(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING), false, saveINAVPidConfig); - } + MSP.send_message(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE, mspHelper.crunch(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE), false, saveINAVPidConfig); } function saveINAVPidConfig() { diff --git a/tabs/receiver.js b/tabs/receiver.js index 62dce43a..48f8e4dc 100644 --- a/tabs/receiver.js +++ b/tabs/receiver.js @@ -24,12 +24,7 @@ TABS.receiver.initialize = function (callback) { mspHelper.loadRcDeadband ]; - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - loadChain.push(mspHelper.loadRateProfileData); - } else { - loadChain.push(mspHelper.loadRcTuningData); - } - + loadChain.push(mspHelper.loadRateProfileData); loadChainer.setChain(loadChain); loadChainer.setExitPoint(load_html); loadChainer.execute(); @@ -328,11 +323,7 @@ TABS.receiver.initialize = function (callback) { }); } - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - MSP.send_message(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE, mspHelper.crunch(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE), false, save_rc_map); - } else { - MSP.send_message(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING), false, save_rc_map); - } + MSP.send_message(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE, mspHelper.crunch(MSPCodes.MSPV2_INAV_SET_RATE_PROFILE), false, save_rc_map); }); $("a.sticks").click(function () { diff --git a/tabs/setup.html b/tabs/setup.html index ce9942dd..0e5974c2 100644 --- a/tabs/setup.html +++ b/tabs/setup.html @@ -92,7 +92,7 @@
- + @@ -100,19 +100,19 @@ - + - + - + - + @@ -128,7 +128,7 @@ - + diff --git a/tabs/setup.js b/tabs/setup.js index a8c7ea26..da829d81 100755 --- a/tabs/setup.js +++ b/tabs/setup.js @@ -21,12 +21,7 @@ TABS.setup.initialize = function (callback) { mspHelper.loadMixerConfig ]; - if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { - loadChain.push(mspHelper.loadMiscV2); - } else { - loadChain.push(mspHelper.loadMisc); - } - + loadChain.push(mspHelper.loadMiscV2); loadChainer.setChain(loadChain); loadChainer.setExitPoint(load_html); loadChainer.execute(); @@ -150,26 +145,22 @@ TABS.setup.initialize = function (callback) { helper.mspBalancedInterval.add('setup_data_pull_fast', 40, 1, get_fast_data); helper.mspBalancedInterval.add('setup_data_pull_slow', 250, 1, get_slow_data); - if (semver.lt(CONFIG.flightControllerVersion, '1.8.1')) { - $('.requires-v1_8_1').hide(); - } - helper.interval.add('gui_analog_update', function () { - bat_cells_e.text(chrome.i18n.getMessage('initialSetupBatteryDetectedCellsValue', [ANALOG.cell_count])); - bat_voltage_e.text(chrome.i18n.getMessage('initialSetupBatteryVoltageValue', [ANALOG.voltage])); - remaining_capacity_wh_decimals = ANALOG.battery_remaining_capacity.toString().length < 5 ? 3 : (7 - ANALOG.battery_remaining_capacity.toString().length); - remaining_capacity_value = MISC.battery_capacity_unit == 'mAh' ? ANALOG.battery_remaining_capacity : (ANALOG.battery_remaining_capacity / 1000).toFixed(remaining_capacity_wh_decimals < 0 ? 0 : remaining_capacity_wh_decimals); - remaining_capacity_unit = MISC.battery_capacity_unit == 'mAh' ? 'mAh' : 'Wh'; - bat_remaining_e.text(chrome.i18n.getMessage('initialSetupBatteryRemainingCapacityValue', ((MISC.battery_capacity > 0) && ANALOG.battery_full_when_plugged_in) ? [remaining_capacity_value, remaining_capacity_unit] : ['NA', ''])); - bat_percent_e.text(chrome.i18n.getMessage('initialSetupBatteryPercentageValue', [ANALOG.battery_percentage])); - bat_full_e.text(chrome.i18n.getMessage('initialSetupBatteryFullValue', [ANALOG.battery_full_when_plugged_in])); - bat_thresh_e.text(chrome.i18n.getMessage('initialSetupBatteryThresholdsValue', [ANALOG.use_capacity_thresholds])); - bat_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn])); - capacity_drawn_decimals = ANALOG.mWhdrawn.toString().length < 5 ? 3 : (7 - ANALOG.mWhdrawn.toString().length); - bat_wh_drawn_e.text(chrome.i18n.getMessage('initialSetup_Wh_drawnValue', [(ANALOG.mWhdrawn / 1000).toFixed(capacity_drawn_decimals < 0 ? 0 : capacity_drawn_decimals)])); - bat_current_draw_e.text(chrome.i18n.getMessage('initialSetupCurrentDrawValue', [ANALOG.amperage.toFixed(2)])); - bat_power_draw_e.text(chrome.i18n.getMessage('initialSetupPowerDrawValue', [ANALOG.power.toFixed(2)])); - rssi_e.text(chrome.i18n.getMessage('initialSetupRSSIValue', [((ANALOG.rssi / 1023) * 100).toFixed(0)])); + bat_cells_e.text(chrome.i18n.getMessage('initialSetupBatteryDetectedCellsValue', [ANALOG.cell_count])); + bat_voltage_e.text(chrome.i18n.getMessage('initialSetupBatteryVoltageValue', [ANALOG.voltage])); + remaining_capacity_wh_decimals = ANALOG.battery_remaining_capacity.toString().length < 5 ? 3 : (7 - ANALOG.battery_remaining_capacity.toString().length); + remaining_capacity_value = MISC.battery_capacity_unit == 'mAh' ? ANALOG.battery_remaining_capacity : (ANALOG.battery_remaining_capacity / 1000).toFixed(remaining_capacity_wh_decimals < 0 ? 0 : remaining_capacity_wh_decimals); + remaining_capacity_unit = MISC.battery_capacity_unit == 'mAh' ? 'mAh' : 'Wh'; + bat_remaining_e.text(chrome.i18n.getMessage('initialSetupBatteryRemainingCapacityValue', ((MISC.battery_capacity > 0) && ANALOG.battery_full_when_plugged_in) ? [remaining_capacity_value, remaining_capacity_unit] : ['NA', ''])); + bat_percent_e.text(chrome.i18n.getMessage('initialSetupBatteryPercentageValue', [ANALOG.battery_percentage])); + bat_full_e.text(chrome.i18n.getMessage('initialSetupBatteryFullValue', [ANALOG.battery_full_when_plugged_in])); + bat_thresh_e.text(chrome.i18n.getMessage('initialSetupBatteryThresholdsValue', [ANALOG.use_capacity_thresholds])); + bat_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn])); + capacity_drawn_decimals = ANALOG.mWhdrawn.toString().length < 5 ? 3 : (7 - ANALOG.mWhdrawn.toString().length); + bat_wh_drawn_e.text(chrome.i18n.getMessage('initialSetup_Wh_drawnValue', [(ANALOG.mWhdrawn / 1000).toFixed(capacity_drawn_decimals < 0 ? 0 : capacity_drawn_decimals)])); + bat_current_draw_e.text(chrome.i18n.getMessage('initialSetupCurrentDrawValue', [ANALOG.amperage.toFixed(2)])); + bat_power_draw_e.text(chrome.i18n.getMessage('initialSetupPowerDrawValue', [ANALOG.power.toFixed(2)])); + rssi_e.text(chrome.i18n.getMessage('initialSetupRSSIValue', [((ANALOG.rssi / 1023) * 100).toFixed(0)])); }, 100, true); function updateArminFailure() { From 369162e1fdf5729b71656010a0799e1623838199 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 27 Feb 2019 20:11:44 +0100 Subject: [PATCH 3/3] remove not needed debug message --- package-lock.json | 8 ++++---- tabs/configuration.js | 1 - 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/package-lock.json b/package-lock.json index ac6aaf57..d4a9a462 100644 --- a/package-lock.json +++ b/package-lock.json @@ -1,6 +1,6 @@ { "name": "inav-configurator", - "version": "2.1.3", + "version": "2.1.4", "lockfileVersion": 1, "requires": true, "dependencies": { @@ -4845,9 +4845,9 @@ "integrity": "sha1-CXtgK1NCKlIsGvuHkDGDNpQaAR0=" }, "nw": { - "version": "0.36.1", - "resolved": "https://registry.npmjs.org/nw/-/nw-0.36.1.tgz", - "integrity": "sha512-U7sJiy5RdPCjM9SV2n54Ve0kzLWEI3ccSTRLwkHuzlZNA7+bQYwNW4Yq/X9a6PXGuYYfTjOt2mxWj1AYKLl5hA==", + "version": "0.36.1-sdk", + "resolved": "https://registry.npmjs.org/nw/-/nw-0.36.1-sdk.tgz", + "integrity": "sha512-dYrwqv9rUFxAdHIj3dWEp1Z1JgvIKfEP8Uogo+zJJ6CzvYdvY2xIL+E2BObhrCwggGYGWvl1UBlAssJanr2d0Q==", "requires": { "chalk": "1.1.3", "decompress": "3.0.0", diff --git a/tabs/configuration.js b/tabs/configuration.js index c27ca591..9ae50103 100644 --- a/tabs/configuration.js +++ b/tabs/configuration.js @@ -565,7 +565,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $gyroLpfMessage.removeClass('warning-box'); if (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) { - console.log($gyroLpfMessage); switch (parseInt(INAV_PID_CONFIG.gyroscopeLpf, 10)) { case 0: $gyroLpfMessage.html(chrome.i18n.getMessage('gyroLpfSuggestedMessage'));
0
0 V
0 %
NA
0
0
0 mAh
0 Wh