From eb6e269467ab10ee257756766bdfa3722eadcf8b Mon Sep 17 00:00:00 2001 From: mikeller Date: Sat, 28 Mar 2020 16:20:26 +1300 Subject: [PATCH] Added warning when connecting to firmware newer than configurator. --- locales/en/messages.json | 50 +++++++++++++++++++--------------- src/css/dark-theme.css | 5 +--- src/css/main.css | 3 +- src/js/RateCurve.js | 2 +- src/js/backup_restore.js | 2 +- src/js/data_storage.js | 26 +++++++++++------- src/js/main.js | 14 +++++++--- src/js/msp/MSPHelper.js | 26 +++++++++--------- src/js/serial_backend.js | 20 ++++++++++---- src/js/tabs/configuration.js | 12 ++++---- src/js/tabs/failsafe.js | 4 +-- src/js/tabs/onboard_logging.js | 2 +- src/js/tabs/osd.js | 10 +++---- src/js/tabs/pid_tuning.js | 28 +++++++++---------- src/js/tabs/receiver.js | 4 +-- src/js/tabs/setup.js | 6 ++-- 16 files changed, 120 insertions(+), 94 deletions(-) diff --git a/locales/en/messages.json b/locales/en/messages.json index 8299f199..7c730c8a 100644 --- a/locales/en/messages.json +++ b/locales/en/messages.json @@ -236,7 +236,10 @@ "message": "Show update notifications for unstable versions of the configurator" }, "configuratorUpdateNotice": { - "message": "You are using an outdated version of the Betaflight Configurator.
Version $1 is available online, please visit the release page to download and install the latest version with fixes and improvements.
Please close the configurator window before updating." + "message": "You are using an outdated version of the Betaflight Configurator.
$t(configuratorUpdateHelp.message)" + }, + "configuratorUpdateHelp": { + "message": "Using a newer version of the firmware with an outdated version of Configurator means that changing some settings will result in a corrupted firmware configuration and a non-working craft. Furthermore, some features of the firmware will only be configurable in CLI.
Betaflight Configurator version $1 is available for download online, please visit this page to download and install the latest version with fixes and improvements.
Please close the configurator window before updating." }, "configuratorUpdateWebsite": { "message": "Go to Release Website" @@ -506,11 +509,14 @@ "reportProblemsDialogFooter": { "message": "Please fix these problems before attempting to fly your craft." }, - "reportProblemsDialogACC_NEEDS_CALIBRATION": { - "message": "the accelerometer is enabled but it is not calibrated. If you plan to use the accelerometer, please follow the instructions for '$t(initialSetupButtonCalibrateAccel.message)' on the '$t(tabSetup.message)' tab. If any function that requires the accelerometer (auto level modes, GPS rescue, ...) is enabled, arming of the craft will be disabled until the accelerometer has been calibrated. If you are not planning on using the accelerometer it is recommended that you disable it in '$t(configurationSystem.message)' on the '$t(tabConfiguration.message)' tab." + "reportProblemsDialogAPI_VERSION_MAX_SUPPORTED": { + "message": "the version of configurator that you are using ($3) is older than the firmware you are using ($4).
$t(configuratorUpdateHelp.message)" }, "reportProblemsDialogMOTOR_PROTOCOL_DISABLED": { - "message": "there is no motor output protocol selected. Please select a motor output protocol appropriate for your ESCs in '$t(configurationEscFeatures.message)' on the '$t(tabConfiguration.message)' tab. $t(escProtocolDisabledMessage.message)" + "message": "there is no motor output protocol selected.
Please select a motor output protocol appropriate for your ESCs in '$t(configurationEscFeatures.message)' on the '$t(tabConfiguration.message)' tab.
$t(escProtocolDisabledMessage.message)" + }, + "reportProblemsDialogACC_NEEDS_CALIBRATION": { + "message": "the accelerometer is enabled but it is not calibrated.
If you plan to use the accelerometer, please follow the instructions for '$t(initialSetupButtonCalibrateAccel.message)' on the '$t(tabSetup.message)' tab. If any function that requires the accelerometer (auto level modes, GPS rescue, ...) is enabled, arming of the craft will be disabled until the accelerometer has been calibrated.
If you are not planning on using the accelerometer it is recommended that you disable it in '$t(configurationSystem.message)' on the '$t(tabConfiguration.message)' tab." }, "infoVersions": { @@ -645,16 +651,16 @@ "message": "Hardware" }, "defaultWelcomeText": { - "message": "The application supports all hardware that can run Betaflight. Check flash tab for full list of hardware.

Download Betaflight Blackbox Log Viewer

The firmware source code can be downloaded from here

The latest STM USB VCP Drivers can be downloaded from here
For legacy hardware using a CP210x USB to serial chip:
The latest CP210x Drivers can be downloaded from here
The latest Zadig for Windows USB driver installation can be downloaded from here
" + "message": "The application supports all hardware that can run Betaflight. Check flash tab for full list of hardware.

Download Betaflight Blackbox Log Viewer

The firmware source code can be downloaded from here

The latest STM USB VCP Drivers can be downloaded from here
For legacy hardware using a CP210x USB to serial chip:
The latest CP210x Drivers can be downloaded from here
The latest Zadig for Windows USB driver installation can be downloaded from here
" }, "defaultContributingHead": { "message": "Contributing" }, "defaultContributingText": { - "message": "If you would like to help make Betaflight even better you can help in many ways, including:
" + "message": "If you would like to help make Betaflight even better you can help in many ways, including:
" }, "defaultFacebookText": { - "message": "We also have a Facebook Group.
Join us to get a place to talk about Betaflight, ask configuration questions, or just hang out with fellow pilots." + "message": "We also have a Facebook Group.
Join us to get a place to talk about Betaflight, ask configuration questions, or just hang out with fellow pilots." }, "defaultChangelogHead": { "message": "Configurator - Changelog" @@ -672,7 +678,7 @@ "message": "

If you want to contribute financially on an ongoing basis, you should consider becoming a patron for us on $t(patreonLink.message).

" }, "patreonLink": { - "message": "Patreon", + "message": "Patreon", "description": "Patreon is name, and should not require translation" }, "defaultDonate": { @@ -688,10 +694,10 @@ "message": "Betaflight documentation is available in release notes and wiki.

" }, "defaultDocumentation1": { - "message": "The Betaflight wiki is a great resource for information, it can be found here." + "message": "The Betaflight wiki is a great resource for information, it can be found here." }, "defaultDocumentation2": { - "message": "The release notes for the firmware can be read at GitHub releases page, here." + "message": "The release notes for the firmware can be read at GitHub releases page, here." }, "defaultSupportHead": { "message": "Support" @@ -706,19 +712,19 @@ "message": "For support please search the forums and wiki first or contact your vendor.

" }, "defaultSupport1": { - "message": "RC Groups thread" + "message": "RC Groups thread" }, "defaultSupport2": { - "message": "Betaflight Wiki" + "message": "Betaflight Wiki" }, "defaultSupport3": { - "message": "Joshua Bardwell Betaflight Videos" + "message": "Joshua Bardwell Betaflight Videos" }, "defaultSupport4": { - "message": "GitHub" + "message": "GitHub" }, "defaultSupport5": { - "message": "Betaflight devs on slack" + "message": "Betaflight devs on slack" }, "initialSetupBackupAndRestoreApiVersion": { @@ -2243,16 +2249,16 @@ "message": "Hexadecimal digits only, 0-9, A-F" }, "transponderHelp1": { - "message": "Configure your transponder code here. Note: Only valid codes will be recognised by race timing systems. Valid transponder codes can be obtained from Seriously Pro." + "message": "Configure your transponder code here. Note: Only valid codes will be recognised by race timing systems. Valid transponder codes can be obtained from Seriously Pro." }, "transponderHelp2": { - "message": "For more information please visit aRCiTimer site" + "message": "For more information please visit aRCiTimer site" }, "transponderDataHelp3": { "message": "Choose ERLT ID 0-63" }, "transponderHelp3": { - "message": "For more information please visit EasyRaceLapTimer site" + "message": "For more information please visit EasyRaceLapTimer site" }, "transponderButtonSave": { "message": "Save" @@ -2894,7 +2900,7 @@ "message": "Recovery / Lost communication" }, "firmwareFlasherRecoveryText": { - "message": "If you have lost communication with your board follow these steps to restore communication: " + "message": "If you have lost communication with your board follow these steps to restore communication: " }, "firmwareFlasherButtonLeave": { "message": "Leave Firmware Flasher" @@ -3657,7 +3663,7 @@ "message": "Dynamic Idle Value [rpm]" }, "pidTuningIdleMinRpmHelp": { - "message": "Set this parameter to provide an rpm based floor-value as a safety net against motor desync.
A racer might prefer very good response and low rates - therefore a low Dynamic Idle[rpm] and a high Dshot Idle value may be useful. Freestylers and LOS pilots will appreciate very low thrust at idle and might want to use less Dshot Idle value while using a bit more Dynamic Idle[rpm] to avoid desyncs at high rates. Note that the Dynamic Idle[rpm] value always must be less than Dshot Idle value.

Visit this wiki entry for more info." + "message": "Set this parameter to provide an rpm based floor-value as a safety net against motor desync.
A racer might prefer very good response and low rates - therefore a low Dynamic Idle[rpm] and a high Dshot Idle value may be useful. Freestylers and LOS pilots will appreciate very low thrust at idle and might want to use less Dshot Idle value while using a bit more Dynamic Idle[rpm] to avoid desyncs at high rates. Note that the Dynamic Idle[rpm] value always must be less than Dshot Idle value.

Visit this wiki entry for more info." }, "pidTuningAcroTrainerAngleLimit": { "message": "Acro Trainer Angle Limit" @@ -3669,7 +3675,7 @@ "message": "Integrated Yaw" }, "pidTuningIntegratedYawCaution": { - "message": "CAUTION: if you enable this feature, you must adjust the YAW PID accordingly. More info here" + "message": "CAUTION: if you enable this feature, you must adjust the YAW PID accordingly. More info here" }, "pidTuningIntegratedYawHelp": { "message": "Integrated Yaw is a feature which corrects a fundamental issue with quad control: while the pitch and roll axis are controlled by the thrust differentials the props generate yaw is different. Integrated Yaw fixes this by integrating the output of the yaw pid before applying them to the mixer. This normalizes the way the pids work. You can now tune as any other axis. It requires use of absolute control since no I is needed with Integrated Yaw." @@ -4113,7 +4119,7 @@ "message": "Your flight controller isn't responding to OSD commands. This probably means that it does not have an integrated BetaFlight OSD." }, "osdSetupUnsupportedNote2": { - "message": "Note that some flight controllers have an onboard MinimOSD that can be flashed and configured with scarab-osd, however the MinimOSD cannot be configured through this interface." + "message": "Note that some flight controllers have an onboard MinimOSD that can be flashed and configured with scarab-osd, however the MinimOSD cannot be configured through this interface." }, "osdSetupProfilesTitle": { "message": "OSD Profile number", diff --git a/src/css/dark-theme.css b/src/css/dark-theme.css index 7bfeafa6..6bb0d699 100644 --- a/src/css/dark-theme.css +++ b/src/css/dark-theme.css @@ -5,6 +5,7 @@ --defaultText: #ffffff; --subtleText: #c0c0c0; --mutedText: #d6d6d6; + --linkText: #ffc549; --boxBackground: #3a3a3a; --alternativeBackground: #4e4e4e; --sideBackground: #404040; @@ -23,10 +24,6 @@ body { color: white; } -a { - color: #ffc549; -} - #options-window { background-color: #393b3a; } diff --git a/src/css/main.css b/src/css/main.css index 89f5ce4b..91fc4a02 100644 --- a/src/css/main.css +++ b/src/css/main.css @@ -7,6 +7,7 @@ --defaultText: #000000; --subtleText: #c0c0c0; --mutedText: #616161; + --linkText: #2e2ebb; --boxBackground: #ffffff; --alternativeBackground: #f9f9f9; --sideBackground: #ffffff; @@ -41,7 +42,7 @@ body { a { text-decoration: none; - color: var(--defaultText); + color: var(--linkText); font-weight: bold; } diff --git a/src/js/RateCurve.js b/src/js/RateCurve.js index 19d73424..1e33e43c 100644 --- a/src/js/RateCurve.js +++ b/src/js/RateCurve.js @@ -157,7 +157,7 @@ RateCurve.prototype.rcCommandRawToDegreesPerSecond = function (rcData, rate, rcR if (rate !== undefined && rcRate !== undefined && rcExpo !== undefined) { let rcCommandf = this.rcCommand(rcData, 1, deadband); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { rcCommandf = rcCommandf / (500 - deadband); } else { rcCommandf = rcCommandf / 500; diff --git a/src/js/backup_restore.js b/src/js/backup_restore.js index 9edbb656..51d1adf3 100644 --- a/src/js/backup_restore.js +++ b/src/js/backup_restore.js @@ -334,7 +334,7 @@ function configuration_restore(callback) { // validate - if (typeof configuration.generatedBy !== 'undefined' && compareVersions(configuration.generatedBy, CONFIGURATOR.backupFileMinVersionAccepted)) { + if (typeof configuration.generatedBy !== 'undefined' && compareVersions(configuration.generatedBy, CONFIGURATOR.BACKUP_FILE_VERSION_MIN_SUPPORTED)) { if (!compareVersions(configuration.generatedBy, "1.14.0") && !migrate(configuration)) { GUI.log(i18n.getMessage('backupFileUnmigratable')); return; diff --git a/src/js/data_storage.js b/src/js/data_storage.js index babd4956..3ba4eca7 100644 --- a/src/js/data_storage.js +++ b/src/js/data_storage.js @@ -1,15 +1,21 @@ 'use strict'; +const API_VERSION_1_43 = '1.43.0'; + var CONFIGURATOR = { // all versions are specified and compared using semantic versioning http://semver.org/ - 'apiVersionAccepted': '1.2.1', - 'backupRestoreMinApiVersionAccepted': '1.5.0', - 'pidControllerChangeMinApiVersion': '1.5.0', - 'backupFileMinVersionAccepted': '0.55.0', // chrome.runtime.getManifest().version is stored as string, so does this one - - 'connectionValid': false, - 'connectionValidCliOnly': false, - 'cliActive': false, - 'cliValid': false, - 'gitChangesetId': 'unknown' + API_VERSION_ACCEPTED: '1.2.1', + API_VERSION_MIN_SUPPORTED_BACKUP_RESTORE: '1.5.0', + API_VERSION_MIN_SUPPORTED_PID_CONTROLLER_CHANGE: '1.5.0', + BACKUP_FILE_VERSION_MIN_SUPPORTED: '0.55.0', // chrome.runtime.getManifest().version is stored as string, so does this one + API_VERSION_MAX_SUPPORTED: API_VERSION_1_43, + + connectionValid: false, + connectionValidCliOnly: false, + cliActive: false, + cliValid: false, + gitChangesetId: 'unknown', + version: '0.0.1', + latestVersion: '0.0.1', + latestVersionReleaseUrl: 'https://github.com/betaflight/betaflight-configurator/releases', }; diff --git a/src/js/main.js b/src/js/main.js index 683085f4..428c6f21 100644 --- a/src/js/main.js +++ b/src/js/main.js @@ -573,12 +573,18 @@ function notifyOutdatedVersion(releaseData) { } }); - if (versions.length > 0 && semver.lt(CONFIGURATOR.version, versions[0].tag_name)) { - GUI.log(i18n.getMessage('configuratorUpdateNotice', [versions[0].tag_name, versions[0].html_url])); + if (versions.length > 0) { + CONFIGURATOR.latestVersion = versions[0].tag_name; + CONFIGURATOR.latestVersionReleaseUrl = versions[0].html_url; + } + + if (semver.lt(CONFIGURATOR.version, CONFIGURATOR.latestVersion)) { + const message = i18n.getMessage('configuratorUpdateNotice', [CONFIGURATOR.latestVersion, CONFIGURATOR.latestVersionReleaseUrl]); + GUI.log(message); const dialog = $('.dialogConfiguratorUpdate')[0]; - $('.dialogConfiguratorUpdate-content').html(i18n.getMessage('configuratorUpdateNotice', [versions[0].tag_name, versions[0].html_url])); + $('.dialogConfiguratorUpdate-content').html(message); $('.dialogConfiguratorUpdate-closebtn').click(function() { dialog.close(); @@ -587,7 +593,7 @@ function notifyOutdatedVersion(releaseData) { $('.dialogConfiguratorUpdate-websitebtn').click(function() { dialog.close(); - window.open(versions[0].html_url, '_blank'); + window.open(CONFIGURATOR.latestVersionReleaseUrl, '_blank'); }); dialog.showModal(); diff --git a/src/js/msp/MSPHelper.js b/src/js/msp/MSPHelper.js index 5d34b3a4..bd2c5ca6 100644 --- a/src/js/msp/MSPHelper.js +++ b/src/js/msp/MSPHelper.js @@ -357,7 +357,7 @@ MspHelper.prototype.process_data = function(dataHandler) { RC_tuning.pitch_rate_limit = data.readU16(); RC_tuning.yaw_rate_limit = data.readU16(); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { RC_tuning.rates_type = data.readU8(); } break; @@ -428,7 +428,7 @@ MspHelper.prototype.process_data = function(dataHandler) { GPS_CONFIG.auto_config = data.readU8(); GPS_CONFIG.auto_baud = data.readU8(); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { GPS_CONFIG.home_point_once = data.readU8(); GPS_CONFIG.ublox_use_galileo = data.readU8(); } @@ -444,7 +444,7 @@ MspHelper.prototype.process_data = function(dataHandler) { GPS_RESCUE.throttleHover = data.readU16(); GPS_RESCUE.sanityChecks = data.readU8(); GPS_RESCUE.minSats = data.readU8(); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { GPS_RESCUE.ascendRate = data.readU16(); GPS_RESCUE.descendRate = data.readU16(); GPS_RESCUE.allowArmingWithoutFix = data.readU8(); @@ -809,7 +809,7 @@ MspHelper.prototype.process_data = function(dataHandler) { CONFIG.configurationState = data.readU8(); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { CONFIG.sampleRateHz = data.readU16(); CONFIG.configurationProblems = data.readU32(); } else { @@ -1085,7 +1085,7 @@ MspHelper.prototype.process_data = function(dataHandler) { FILTER_CONFIG.gyro_rpm_notch_harmonics = data.readU8(); FILTER_CONFIG.gyro_rpm_notch_min_hz = data.readU8(); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { FILTER_CONFIG.dyn_notch_max_hz = data.readU16(); } } @@ -1150,7 +1150,7 @@ MspHelper.prototype.process_data = function(dataHandler) { if(semver.gte(CONFIG.apiVersion, "1.42.0")) { ADVANCED_TUNING.itermRelaxCutoff = data.readU8(); - if(semver.gte(CONFIG.apiVersion, "1.43.0")) { + if(semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { ADVANCED_TUNING.motorOutputLimit = data.readU8(); ADVANCED_TUNING.autoProfileCellCount = data.readU8(); ADVANCED_TUNING.idleMinRpm = data.readU8(); @@ -1696,7 +1696,7 @@ MspHelper.prototype.crunch = function(code) { buffer.push16(RC_tuning.pitch_rate_limit); buffer.push16(RC_tuning.yaw_rate_limit); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { buffer.push8(RC_tuning.rates_type); } break; @@ -1757,7 +1757,7 @@ MspHelper.prototype.crunch = function(code) { buffer.push8(GPS_CONFIG.auto_config) .push8(GPS_CONFIG.auto_baud); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { buffer.push8(GPS_CONFIG.home_point_once) .push8(GPS_CONFIG.ublox_use_galileo); } @@ -1774,7 +1774,7 @@ MspHelper.prototype.crunch = function(code) { .push8(GPS_RESCUE.sanityChecks) .push8(GPS_RESCUE.minSats); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { buffer.push16(GPS_RESCUE.ascendRate) .push16(GPS_RESCUE.descendRate) .push8(GPS_RESCUE.allowArmingWithoutFix) @@ -2026,7 +2026,7 @@ MspHelper.prototype.crunch = function(code) { .push8(FILTER_CONFIG.gyro_rpm_notch_harmonics) .push8(FILTER_CONFIG.gyro_rpm_notch_min_hz); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { buffer.push16(FILTER_CONFIG.dyn_notch_max_hz); } } @@ -2088,7 +2088,7 @@ MspHelper.prototype.crunch = function(code) { if(semver.gte(CONFIG.apiVersion, "1.42.0")) { buffer.push8(ADVANCED_TUNING.itermRelaxCutoff); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { buffer.push8(ADVANCED_TUNING.motorOutputLimit) .push8(ADVANCED_TUNING.autoProfileCellCount) .push8(ADVANCED_TUNING.idleMinRpm); @@ -2765,12 +2765,12 @@ MspHelper.prototype.setArmingEnabled = function(doEnable, disableRunawayTakeoffP } MspHelper.prototype.loadSerialConfig = function(callback) { - const mspCode = semver.gte(CONFIG.apiVersion, "1.43.0") ? MSPCodes.MSP2_COMMON_SERIAL_CONFIG : MSPCodes.MSP_CF_SERIAL_CONFIG; + const mspCode = semver.gte(CONFIG.apiVersion, API_VERSION_1_43) ? MSPCodes.MSP2_COMMON_SERIAL_CONFIG : MSPCodes.MSP_CF_SERIAL_CONFIG; MSP.send_message(mspCode, false, false, callback); }; MspHelper.prototype.sendSerialConfig = function(callback) { - const mspCode = semver.gte(CONFIG.apiVersion, "1.43.0") ? MSPCodes.MSP2_COMMON_SET_SERIAL_CONFIG : MSPCodes.MSP_SET_CF_SERIAL_CONFIG; + const mspCode = semver.gte(CONFIG.apiVersion, API_VERSION_1_43) ? MSPCodes.MSP2_COMMON_SET_SERIAL_CONFIG : MSPCodes.MSP_SET_CF_SERIAL_CONFIG; MSP.send_message(mspCode, mspHelper.crunch(mspCode), false, callback); }; diff --git a/src/js/serial_backend.js b/src/js/serial_backend.js index 44679d83..8a6fa63f 100644 --- a/src/js/serial_backend.js +++ b/src/js/serial_backend.js @@ -238,13 +238,13 @@ function onOpen(openInfo) { GUI.log(i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion])); - if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.apiVersionAccepted)) { + if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_ACCEPTED)) { MSP.send_message(MSPCodes.MSP_FC_VARIANT, false, false, function () { analytics.setFlightControllerData(analytics.DATA.FIRMWARE_TYPE, CONFIG.flightControllerIdentifier); if (CONFIG.flightControllerIdentifier === 'BTFL') { MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () { - analytics.setFlightControllerData(analytics.DATA.FIRMWARE_VERSION, CONFIG.flightControllerVersion); + analytics.setFlightControllerData(analytics.DATA.FIRMWARE_VERSION, CONFIG.flightControllerVersion); GUI.log(i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion])); updateStatusBarVersion(CONFIG.flightControllerVersion, CONFIG.flightControllerIdentifier); @@ -278,7 +278,7 @@ function onOpen(openInfo) { var dialog = $('.dialogConnectWarning')[0]; - $('.dialogConnectWarning-content').html(i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.apiVersionAccepted])); + $('.dialogConnectWarning-content').html(i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.API_VERSION_ACCEPTED])); $('.dialogConnectWarning-closebtn').click(function() { dialog.close(); @@ -373,12 +373,22 @@ function checkReportProblems() { const problemDialogList = $('#dialogReportProblems-list'); problemDialogList.empty(); - if (have_sensor(CONFIG.activeSensors, 'acc')) { - needsProblemReportingDialog = checkReportProblem('ACC_NEEDS_CALIBRATION', problemDialogList) || needsProblemReportingDialog; + if (semver.gt(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MAX_SUPPORTED)) { + const problemName = 'API_VERSION_MAX_SUPPORTED'; + problemItemTemplate.clone().html(i18n.getMessage(`reportProblemsDialog${problemName}`, + [CONFIGURATOR.latestVersion, CONFIGURATOR.latestVersionReleaseUrl, CONFIGURATOR.version, CONFIG.flightControllerVersion])).appendTo(problemDialogList); + needsProblemReportingDialog = true; + + analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, PROBLEM_ANALYTICS_EVENT, + `${problemName};${CONFIGURATOR.API_VERSION_MAX_SUPPORTED};${CONFIG.apiVersion}`); } needsProblemReportingDialog = checkReportProblem('MOTOR_PROTOCOL_DISABLED', problemDialogList) || needsProblemReportingDialog; + if (have_sensor(CONFIG.activeSensors, 'acc')) { + needsProblemReportingDialog = checkReportProblem('ACC_NEEDS_CALIBRATION', problemDialogList) || needsProblemReportingDialog; + } + if (needsProblemReportingDialog) { const problemDialog = $('#dialogReportProblems')[0]; $('#dialogReportProblems-closebtn').click(function() { diff --git a/src/js/tabs/configuration.js b/src/js/tabs/configuration.js index e50536c7..c71e6b41 100644 --- a/src/js/tabs/configuration.js +++ b/src/js/tabs/configuration.js @@ -641,7 +641,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('div.gyroUse32kHz').hide(); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { updateGyroDenomReadOnly(CONFIG.sampleRateHz); } else { updateGyroDenom(8); @@ -656,7 +656,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { const originalPidDenom = pidSelectElement.val(); let pidBaseFreq; - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { pidBaseFreq = CONFIG.sampleRateHz / 1000; } else { pidBaseFreq = 8; @@ -733,7 +733,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { i18n.getMessage('gpsSbasJapaneseMSAS'), i18n.getMessage('gpsSbasIndianGAGAN'), ]; - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { gpsSbas.push(i18n.getMessage('gpsSbasNone')); } @@ -747,7 +747,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { gps_protocol_e.change(function () { GPS_CONFIG.provider = parseInt($(this).val()); - const enableGalileoVisible = semver.gte(CONFIG.apiVersion, "1.43.0") && GPS_CONFIG.provider === gpsProtocols.indexOf('UBLOX'); + const enableGalileoVisible = semver.gte(CONFIG.apiVersion, API_VERSION_1_43) && GPS_CONFIG.provider === gpsProtocols.indexOf('UBLOX'); gps_ublox_galileo_e.toggle(enableGalileoVisible); }); gps_protocol_e.val(GPS_CONFIG.provider).change(); @@ -756,7 +756,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { GPS_CONFIG.ublox_use_galileo = $(this).is(':checked') ? 1 : 0; }).prop('checked', GPS_CONFIG.ublox_use_galileo > 0).change(); - $('.gps_home_once').toggle(semver.gte(CONFIG.apiVersion, "1.43.0")); + $('.gps_home_once').toggle(semver.gte(CONFIG.apiVersion, API_VERSION_1_43)); $('input[name="gps_home_once"]').change(function() { GPS_CONFIG.home_point_once = $(this).is(':checked') ? 1 : 0; }).prop('checked', GPS_CONFIG.home_point_once > 0).change(); @@ -889,7 +889,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { ); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { spiRxTypes.push( 'REDPINE', ); diff --git a/src/js/tabs/failsafe.js b/src/js/tabs/failsafe.js index 1ba11065..1e663c03 100644 --- a/src/js/tabs/failsafe.js +++ b/src/js/tabs/failsafe.js @@ -313,7 +313,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { $('input[name="gps_rescue_min_sats"]').val(GPS_RESCUE.minSats); $('select[name="gps_rescue_sanity_checks"]').val(GPS_RESCUE.sanityChecks); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { $('input[name="gps_rescue_ascend_rate"]').val((GPS_RESCUE.ascendRate / 100).toFixed(2)); $('input[name="gps_rescue_descend_rate"]').val((GPS_RESCUE.descendRate / 100).toFixed(2)); $('input[name="gps_rescue_allow_arming_without_fix"]').prop('checked', GPS_RESCUE.allowArmingWithoutFix > 0); @@ -379,7 +379,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { GPS_RESCUE.sanityChecks = $('select[name="gps_rescue_sanity_checks"]').val(); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { GPS_RESCUE.ascendRate = $('input[name="gps_rescue_ascend_rate"]').val() * 100; GPS_RESCUE.descendRate = $('input[name="gps_rescue_descend_rate"]').val() * 100; GPS_RESCUE.allowArmingWithoutFix = $('input[name="gps_rescue_allow_arming_without_fix"]').prop('checked') ? 1 : 0; diff --git a/src/js/tabs/onboard_logging.js b/src/js/tabs/onboard_logging.js index c67245af..534aff6a 100644 --- a/src/js/tabs/onboard_logging.js +++ b/src/js/tabs/onboard_logging.js @@ -195,7 +195,7 @@ TABS.onboard_logging.initialize = function (callback) { let loggingRates = []; let pidRate; - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { pidRate = CONFIG.sampleRateHz / PID_ADVANCED_CONFIG.pid_process_denom; } else { diff --git a/src/js/tabs/osd.js b/src/js/tabs/osd.js index 99dbd6f5..36ea4c5e 100644 --- a/src/js/tabs/osd.js +++ b/src/js/tabs/osd.js @@ -1536,7 +1536,7 @@ OSD.chooseFields = function () { F.OSD_PROFILE_NAME, F.RSSI_DBM_VALUE, ]); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([ F.RC_CHANNELS, F.CAMERA_FRAME, @@ -1686,7 +1686,7 @@ OSD.chooseFields = function () { F.RSSI_DBM, ]); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { OSD.constants.WARNINGS = OSD.constants.WARNINGS.concat([ F.OVER_CAP, ]); @@ -1819,7 +1819,7 @@ OSD.msp = { result.push8(OSD.data.parameters.overlayRadioMode); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { result.push8(OSD.data.parameters.cameraFrameWidth); result.push8(OSD.data.parameters.cameraFrameHeight); } @@ -1882,7 +1882,7 @@ OSD.msp = { d.state = {}; d.state.haveSomeOsd = (d.flags != 0) d.state.haveMax7456Video = bit_check(d.flags, 4) || (d.flags == 1 && semver.lt(CONFIG.apiVersion, "1.34.0")); - d.state.isMax7456Detected = bit_check(d.flags, 5) || (d.state.haveMax7456Video && semver.lt(CONFIG.apiVersion, "1.43.0")); + d.state.isMax7456Detected = bit_check(d.flags, 5) || (d.state.haveMax7456Video && semver.lt(CONFIG.apiVersion, API_VERSION_1_43)); d.state.haveOsdFeature = bit_check(d.flags, 0) || (d.flags == 1 && semver.lt(CONFIG.apiVersion, "1.34.0")); d.state.isOsdSlave = bit_check(d.flags, 1) && semver.gte(CONFIG.apiVersion, "1.34.0"); @@ -2004,7 +2004,7 @@ OSD.msp = { } // Camera frame size - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { d.parameters.cameraFrameWidth = view.readU8(); d.parameters.cameraFrameHeight = view.readU8(); } diff --git a/src/js/tabs/pid_tuning.js b/src/js/tabs/pid_tuning.js index 39a48cf1..418f6468 100644 --- a/src/js/tabs/pid_tuning.js +++ b/src/js/tabs/pid_tuning.js @@ -37,7 +37,7 @@ TABS.pid_tuning.initialize = function (callback) { // requesting MSP_STATUS manually because it contains CONFIG.profile MSP.promise(MSPCodes.MSP_STATUS).then(function() { - if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion)) { + if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_PID_CONTROLLER_CHANGE)) { return MSP.promise(MSPCodes.MSP_PID_CONTROLLER); } }).then(function() { @@ -181,7 +181,7 @@ TABS.pid_tuning.initialize = function (callback) { antiGravitySwitch.change(function() { var checked = $(this).is(':checked'); if (checked) { - const MAX_ACCELERATOR_GAIN = semver.gte(CONFIG.apiVersion, "1.43.0") ? 3.5 : 1.1; + const MAX_ACCELERATOR_GAIN = semver.gte(CONFIG.apiVersion, API_VERSION_1_43) ? 3.5 : 1.1; const itermAcceleratorGain = Math.max(ADVANCED_TUNING.itermAcceleratorGain / 1000, MAX_ACCELERATOR_GAIN); $('.antigravity input[name="itermAcceleratorGain"]').val(itermAcceleratorGain); $('.antigravity .suboption').show(); @@ -245,7 +245,7 @@ TABS.pid_tuning.initialize = function (callback) { $('select[id="itermrelaxType"]').val(ADVANCED_TUNING.itermRelaxType); $('input[name="itermRelaxCutoff"]').val(ADVANCED_TUNING.itermRelaxCutoff); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { $('.itermrelax input[name="itermRelaxCutoff"]').attr("max","50"); } @@ -364,12 +364,12 @@ TABS.pid_tuning.initialize = function (callback) { } else { $('.dynamicNotch').hide(); } - $('.dynamicNotchRange').toggle(semver.lt(CONFIG.apiVersion, "1.43.0")); + $('.dynamicNotchRange').toggle(semver.lt(CONFIG.apiVersion, API_VERSION_1_43)); $('.pid_filter select[name="dynamicNotchRange"]').val(FILTER_CONFIG.dyn_notch_range); $('.pid_filter input[name="dynamicNotchWidthPercent"]').val(FILTER_CONFIG.dyn_notch_width_percent); $('.pid_filter input[name="dynamicNotchQ"]').val(FILTER_CONFIG.dyn_notch_q); $('.pid_filter input[name="dynamicNotchMinHz"]').val(FILTER_CONFIG.dyn_notch_min_hz); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { $('.pid_filter input[name="dynamicNotchMinHz"]').attr("max","250"); $('.pid_filter input[name="dynamicNotchMaxHz"]').val(FILTER_CONFIG.dyn_notch_max_hz); } else { @@ -401,7 +401,7 @@ TABS.pid_tuning.initialize = function (callback) { $('.rpmFilter').hide(); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { $('.pid_tuning input[name="motorLimit"]').val(ADVANCED_TUNING.motorOutputLimit); $('.pid_tuning input[name="cellCount"]').val(ADVANCED_TUNING.autoProfileCellCount); $('input[name="idleMinRpm-number"]').val(ADVANCED_TUNING.idleMinRpm); @@ -410,7 +410,7 @@ TABS.pid_tuning.initialize = function (callback) { $('.idleMinRpm').hide(); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { const ratesTypeListElement = $('select[id="ratesType"]'); // generates list const ratesList = [ {name: "Betaflight"}, @@ -714,7 +714,7 @@ TABS.pid_tuning.initialize = function (callback) { RC_tuning.rcPitchRate = parseFloat(rc_rate_pitch_e.val()); RC_tuning.RC_PITCH_EXPO = parseFloat(rc_pitch_expo_e.val()); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { switch(self.currentRatesType) { case self.RATES_TYPE.RACEFLIGHT: RC_tuning.pitch_rate = parseFloat(pitch_rate_e.val()) / 100; @@ -875,7 +875,7 @@ TABS.pid_tuning.initialize = function (callback) { FILTER_CONFIG.gyro_rpm_notch_min_hz = parseInt($('.pid_filter input[name="rpmFilterMinHz"]').val()); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { FILTER_CONFIG.dyn_notch_max_hz = parseInt($('.pid_filter input[name="dynamicNotchMaxHz"]').val()); ADVANCED_TUNING.motorOutputLimit = parseInt($('.pid_tuning input[name="motorLimit"]').val()); ADVANCED_TUNING.autoProfileCellCount = parseInt($('.pid_tuning input[name="cellCount"]').val()); @@ -1051,7 +1051,7 @@ TABS.pid_tuning.initialize = function (callback) { self.currentRates.rc_expo_pitch = self.currentRates.rc_expo; } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { switch(RC_tuning.rates_type) { case self.RATES_TYPE.RACEFLIGHT: self.currentRates.roll_rate *= 100; @@ -1351,12 +1351,12 @@ TABS.pid_tuning.initialize = function (callback) { pidController_e.append(''); } - if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion)) { + if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_PID_CONTROLLER_CHANGE)) { pidController_e.val(PID.controller); self.updatePidControllerParameters(); } else { - GUI.log(i18n.getMessage('pidTuningUpgradeFirmwareToChangePidController', [CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion])); + GUI.log(i18n.getMessage('pidTuningUpgradeFirmwareToChangePidController', [CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_PID_CONTROLLER_CHANGE])); pidController_e.empty(); pidController_e.append(''); @@ -1449,7 +1449,7 @@ TABS.pid_tuning.initialize = function (callback) { self.currentRates.rc_pitch_expo = targetValue; } - if (targetElement.attr('id') === 'ratesType' && semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (targetElement.attr('id') === 'ratesType' && semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { self.changeRatesType(targetValue); updateNeeded = true; @@ -1889,7 +1889,7 @@ TABS.pid_tuning.initialize = function (callback) { Promise.resolve(true) .then(function () { var promise; - if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion) && semver.lt(CONFIG.apiVersion, "1.31.0")) { + if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_PID_CONTROLLER_CHANGE) && semver.lt(CONFIG.apiVersion, "1.31.0")) { PID.controller = pidController_e.val(); promise = MSP.promise(MSPCodes.MSP_SET_PID_CONTROLLER, mspHelper.crunch(MSPCodes.MSP_SET_PID_CONTROLLER)); } diff --git a/src/js/tabs/receiver.js b/src/js/tabs/receiver.js index f4f7c1ae..ecba88a7 100644 --- a/src/js/tabs/receiver.js +++ b/src/js/tabs/receiver.js @@ -326,7 +326,7 @@ TABS.receiver.initialize = function (callback) { }); let showBindButton = false; - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { showBindButton = bit_check(CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.SUPPORTS_RX_BIND); $("a.bind").click(function() { @@ -396,7 +396,7 @@ TABS.receiver.initialize = function (callback) { rcSmoothingnDerivativeNumberElement.val(RX_CONFIG.rcSmoothingDerivativeCutoff); var rc_smoothing_derivative_type = $('select[name="rcSmoothingDerivativeType-select"]'); - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { rc_smoothing_derivative_type.append($(``)); } diff --git a/src/js/tabs/setup.js b/src/js/tabs/setup.js index b9250b53..57bd401f 100644 --- a/src/js/tabs/setup.js +++ b/src/js/tabs/setup.js @@ -29,11 +29,11 @@ TABS.setup.initialize = function (callback) { // translate to user-selected language i18n.localizePage(); - if (semver.lt(CONFIG.apiVersion, CONFIGURATOR.backupRestoreMinApiVersionAccepted)) { + if (semver.lt(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_BACKUP_RESTORE)) { $('#content .backup').addClass('disabled'); $('#content .restore').addClass('disabled'); - GUI.log(i18n.getMessage('initialSetupBackupAndRestoreApiVersion', [CONFIG.apiVersion, CONFIGURATOR.backupRestoreMinApiVersionAccepted])); + GUI.log(i18n.getMessage('initialSetupBackupAndRestoreApiVersion', [CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_BACKUP_RESTORE])); } // initialize 3D Model @@ -239,7 +239,7 @@ TABS.setup.initialize = function (callback) { disarmFlagElements = disarmFlagElements.concat(['REBOOT_REQD', 'DSHOT_BBANG']); } - if (semver.gte(CONFIG.apiVersion, "1.43.0")) { + if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) { disarmFlagElements = disarmFlagElements.concat(['NO_ACC_CAL', 'MOTOR_PROTO']); }