mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-20 23:05:15 +03:00
Clean up profile loading.
This commit is contained in:
parent
f9ee83d52e
commit
622a4fb821
9 changed files with 136 additions and 91 deletions
|
@ -845,6 +845,12 @@
|
||||||
"pidTuningControllerHead": {
|
"pidTuningControllerHead": {
|
||||||
"message": "PID"
|
"message": "PID"
|
||||||
},
|
},
|
||||||
|
"pidTuningPidsReset": {
|
||||||
|
"message": "Loaded default PID values."
|
||||||
|
},
|
||||||
|
"pidTuningReceivedProfile": {
|
||||||
|
"message": "Flight controller set Profile: <strong style=\"color: #ffbb00\">$1</strong>"
|
||||||
|
},
|
||||||
"pidTuningLoadedProfile": {
|
"pidTuningLoadedProfile": {
|
||||||
"message": "Loaded Profile: <strong style=\"color: #ffbb00\">$1</strong>"
|
"message": "Loaded Profile: <strong style=\"color: #ffbb00\">$1</strong>"
|
||||||
},
|
},
|
||||||
|
|
3
js/fc.js
3
js/fc.js
|
@ -62,7 +62,8 @@ var FC = {
|
||||||
uid: [0, 0, 0],
|
uid: [0, 0, 0],
|
||||||
accelerometerTrims: [0, 0],
|
accelerometerTrims: [0, 0],
|
||||||
name: '',
|
name: '',
|
||||||
numProfiles: 3
|
numProfiles: 3,
|
||||||
|
rateProfile: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
BF_CONFIG = {
|
BF_CONFIG = {
|
||||||
|
|
|
@ -297,11 +297,9 @@ var MSP = {
|
||||||
CONFIG.profile = data.getUint8(10);
|
CONFIG.profile = data.getUint8(10);
|
||||||
CONFIG.cpuload = data.getUint16(11, 1);
|
CONFIG.cpuload = data.getUint16(11, 1);
|
||||||
CONFIG.numProfiles = data.getUint8(13);
|
CONFIG.numProfiles = data.getUint8(13);
|
||||||
$('.tab-pid_tuning select[name="profilechange"]').val(CONFIG.profile);
|
CONFIG.rateProfile = data.getUint8(14);
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")
|
|
||||||
&& CONFIG.numProfiles === 2) {
|
TABS.pid_tuning.checkUpdateProfile();
|
||||||
$('.tab-pid_tuning select[name="profilechange"] .profile3').hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
sensor_status(CONFIG.activeSensors);
|
sensor_status(CONFIG.activeSensors);
|
||||||
$('span.i2c-error').text(CONFIG.i2cError);
|
$('span.i2c-error').text(CONFIG.i2cError);
|
||||||
|
|
|
@ -212,8 +212,6 @@ function onOpen(openInfo) {
|
||||||
GUI.allowedTabs.splice(GUI.allowedTabs.indexOf('led_strip'), 1);
|
GUI.allowedTabs.splice(GUI.allowedTabs.indexOf('led_strip'), 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
GUI.canChangePidController = semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion);
|
|
||||||
|
|
||||||
onConnect();
|
onConnect();
|
||||||
|
|
||||||
$('#tabs ul.mode-connected .tab_setup a').click();
|
$('#tabs ul.mode-connected .tab_setup a').click();
|
||||||
|
|
6
main.js
6
main.js
|
@ -383,12 +383,6 @@ String.prototype.format = function () {
|
||||||
});
|
});
|
||||||
};
|
};
|
||||||
|
|
||||||
function updateActivatedTab() {
|
|
||||||
var activeTab = $('#tabs > ul li.active');
|
|
||||||
activeTab.removeClass('active');
|
|
||||||
$('a', activeTab).trigger('click');
|
|
||||||
}
|
|
||||||
|
|
||||||
function updateTabList(features) {
|
function updateTabList(features) {
|
||||||
if (features.isEnabled('GPS')) {
|
if (features.isEnabled('GPS')) {
|
||||||
$('#tabs ul.mode-connected li.tab_gps').show();
|
$('#tabs ul.mode-connected li.tab_gps').show();
|
||||||
|
|
|
@ -307,7 +307,7 @@
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="new_rates">
|
<tr class="new_rates">
|
||||||
<td i18n="pidTuningMaxAngularVelRoll"></td>
|
<td i18n="pidTuningMaxAngularVelRoll" style="width: 70%"></td>
|
||||||
<td class="maxAngularVelRoll"></td>
|
<td class="maxAngularVelRoll"></td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr class="new_rates">
|
<tr class="new_rates">
|
||||||
|
|
|
@ -1,7 +1,9 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
TABS.pid_tuning = {
|
TABS.pid_tuning = {
|
||||||
controllerChanged: false
|
showAllPids: false,
|
||||||
|
profileDirty: false,
|
||||||
|
loadingProfile: true
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.pid_tuning.initialize = function (callback) {
|
TABS.pid_tuning.initialize = function (callback) {
|
||||||
|
@ -44,6 +46,10 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
$('input[name="vbatpidcompensation"]').prop('checked', ADVANCED_TUNING.vbatPidCompensation !== 0);
|
$('input[name="vbatpidcompensation"]').prop('checked', ADVANCED_TUNING.vbatPidCompensation !== 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
|
$('.delta select').val(ADVANCED_TUNING.deltaMethod);
|
||||||
|
}
|
||||||
|
|
||||||
// Fill in the data from PIDs array
|
// Fill in the data from PIDs array
|
||||||
var i = 0;
|
var i = 0;
|
||||||
$('.pid_tuning .ROLL input').each(function () {
|
$('.pid_tuning .ROLL input').each(function () {
|
||||||
|
@ -204,7 +210,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
$('.pid_tuning input[name="dterm"]').val(FILTER_CONFIG.dterm_lpf_hz);
|
$('.pid_tuning input[name="dterm"]').val(FILTER_CONFIG.dterm_lpf_hz);
|
||||||
$('.pid_tuning input[name="yaw"]').val(FILTER_CONFIG.yaw_lpf_hz);
|
$('.pid_tuning input[name="yaw"]').val(FILTER_CONFIG.yaw_lpf_hz);
|
||||||
|
|
||||||
if (CONFIG.flightControllerIdentifier !== "BTFL" || semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
$('.pid_filter').hide();
|
$('.pid_filter').hide();
|
||||||
$('.pid_tuning input[name="rc_rate_yaw"]').hide();
|
$('.pid_tuning input[name="rc_rate_yaw"]').hide();
|
||||||
}
|
}
|
||||||
|
@ -219,6 +225,10 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
ADVANCED_TUNING.vbatPidCompensation = $('input[name="vbatpidcompensation"]').is(':checked') ? 1 : 0;
|
ADVANCED_TUNING.vbatPidCompensation = $('input[name="vbatpidcompensation"]').is(':checked') ? 1 : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
|
ADVANCED_TUNING.deltaMethod = $('.delta select').val();
|
||||||
|
}
|
||||||
|
|
||||||
// Fill in the data from PIDs array
|
// Fill in the data from PIDs array
|
||||||
// Catch all the changes and stuff the inside PIDs array
|
// Catch all the changes and stuff the inside PIDs array
|
||||||
var i = 0;
|
var i = 0;
|
||||||
|
@ -450,17 +460,25 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
$('#resetPIDs').on('click', function(){
|
$('#resetPIDs').on('click', function(){
|
||||||
MSP.send_message(MSP_codes.MSP_SET_RESET_CURR_PID, false, false, false);
|
TABS.pid_tuning.profileLoading = true;
|
||||||
updateActivatedTab();
|
MSP.promise(MSP_codes.MSP_SET_RESET_CURR_PID).then(function () {
|
||||||
|
TABS.pid_tuning.refresh(function () {
|
||||||
|
TABS.pid_tuning.profileDirty = false;
|
||||||
|
|
||||||
|
GUI.log(chrome.i18n.getMessage('pidTuningPidsReset'));
|
||||||
|
});
|
||||||
|
});
|
||||||
});
|
});
|
||||||
|
|
||||||
var profileElement = $('.tab-pid_tuning select[name="profilechange"]');
|
$('.tab-pid_tuning select[name="profilechange"]').change(function () {
|
||||||
|
|
||||||
profileElement.change(function () {
|
|
||||||
var profile = parseInt($(this).val());
|
var profile = parseInt($(this).val());
|
||||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [profile], false, function () {
|
TABS.pid_tuning.loadingProfile = true;
|
||||||
|
MSP.promise(MSP_codes.MSP_SELECT_SETTING, [profile]).then(function () {
|
||||||
|
TABS.pid_tuning.refresh(function () {
|
||||||
|
TABS.pid_tuning.loadingProfile = false;
|
||||||
|
|
||||||
GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1]));
|
GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1]));
|
||||||
updateActivatedTab();
|
});
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -504,9 +522,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
pidController_e.append('<option value="' + (i) + '">' + pidControllerList[i].name + '</option>');
|
pidController_e.append('<option value="' + (i) + '">' + pidControllerList[i].name + '</option>');
|
||||||
}
|
}
|
||||||
|
|
||||||
var form_e = $('#pid-tuning');
|
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion)) {
|
||||||
|
|
||||||
if (GUI.canChangePidController) {
|
|
||||||
pidController_e.val(PID.controller);
|
pidController_e.val(PID.controller);
|
||||||
} else {
|
} else {
|
||||||
GUI.log(chrome.i18n.getMessage('pidTuningUpgradeFirmwareToChangePidController', [CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion]));
|
GUI.log(chrome.i18n.getMessage('pidTuningUpgradeFirmwareToChangePidController', [CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion]));
|
||||||
|
@ -647,33 +663,26 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}).trigger('input');
|
}).trigger('input');
|
||||||
|
|
||||||
$('a.refresh').click(function () {
|
$('a.refresh').click(function () {
|
||||||
GUI.tab_switch_cleanup(function () {
|
TABS.pid_tuning.refresh(function () {
|
||||||
GUI.log(chrome.i18n.getMessage('pidTuningDataRefreshed'));
|
GUI.log(chrome.i18n.getMessage('pidTuningDataRefreshed'));
|
||||||
TABS.pid_tuning.initialize();
|
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
|
||||||
form_e.find('input').each(function (k, item) {
|
$('#pid-tuning').find('input').each(function (k, item) {
|
||||||
$(item).change(function () {
|
$(item).change(function () {
|
||||||
pidController_e.prop("disabled", true);
|
TABS.pid_tuning.profileDirty = true;
|
||||||
TABS.pid_tuning.controllerChanged = false;
|
|
||||||
})
|
})
|
||||||
});
|
});
|
||||||
|
|
||||||
pidController_e.change(function () {
|
pidController_e.change(function () {
|
||||||
if (PID.controller != pidController_e.val()) {
|
TABS.pid_tuning.profileDirty = true;
|
||||||
form_e.find('input').each(function (k, item) {
|
|
||||||
$(item).prop('disabled', true);
|
|
||||||
TABS.pid_tuning.controllerChanged = true;
|
|
||||||
});
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
$('.delta select').val(ADVANCED_TUNING.deltaMethod).change(function() {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
ADVANCED_TUNING.deltaMethod = $(this).val();
|
$('.delta select').change(function() {
|
||||||
|
TABS.pid_tuning.profileDirty = true;
|
||||||
});
|
});
|
||||||
|
} else {
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.lt(CONFIG.flightControllerVersion, "2.8.2")) {
|
|
||||||
$('.delta').hide();
|
$('.delta').hide();
|
||||||
$('.note').hide();
|
$('.note').hide();
|
||||||
}
|
}
|
||||||
|
@ -681,44 +690,47 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
// update == save.
|
// update == save.
|
||||||
$('a.update').click(function () {
|
$('a.update').click(function () {
|
||||||
form_to_pid_and_rc();
|
form_to_pid_and_rc();
|
||||||
if (GUI.canChangePidController && TABS.pid_tuning.controllerChanged) {
|
|
||||||
|
Promise.resolve(function () {
|
||||||
|
var promise;
|
||||||
|
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion)) {
|
||||||
PID.controller = pidController_e.val();
|
PID.controller = pidController_e.val();
|
||||||
MSP.send_message(MSP_codes.MSP_SET_PID_CONTROLLER, MSP.crunch(MSP_codes.MSP_SET_PID_CONTROLLER), false, function () {
|
promise = MSP.promise(MSP_codes.MSP_SET_PID_CONTROLLER, MSP.crunch(MSP_codes.MSP_SET_PID_CONTROLLER));
|
||||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
|
||||||
GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved'));
|
|
||||||
});
|
|
||||||
TABS.pid_tuning.initialize();
|
|
||||||
});
|
|
||||||
} else {
|
|
||||||
if (TABS.pid_tuning.controllerChanged) { return; }
|
|
||||||
MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID)).then(function() {
|
|
||||||
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
|
||||||
return MSP.promise(MSP_codes.MSP_SET_SPECIAL_PARAMETERS, MSP.crunch(MSP_codes.MSP_SET_SPECIAL_PARAMETERS));
|
|
||||||
}
|
}
|
||||||
}).then(function() {
|
|
||||||
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
return promise;
|
||||||
|
}).then(function () {
|
||||||
|
return MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID));
|
||||||
|
}).then(function () {
|
||||||
|
var promise;
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
|
promise = MSP.promise(MSP_codes.MSP_SET_SPECIAL_PARAMETERS, MSP.crunch(MSP_codes.MSP_SET_SPECIAL_PARAMETERS));
|
||||||
|
}
|
||||||
|
|
||||||
|
return promise;
|
||||||
|
}).then(function () {
|
||||||
return MSP.promise(MSP_codes.MSP_SET_ADVANCED_TUNING, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_TUNING));
|
return MSP.promise(MSP_codes.MSP_SET_ADVANCED_TUNING, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_TUNING));
|
||||||
}).then(function() {
|
}).then(function () {
|
||||||
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
var promise;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
return MSP.promise(MSP_codes.MSP_SET_FILTER_CONFIG, MSP.crunch(MSP_codes.MSP_SET_FILTER_CONFIG));
|
promise = MSP.promise(MSP_codes.MSP_SET_FILTER_CONFIG, MSP.crunch(MSP_codes.MSP_SET_FILTER_CONFIG));
|
||||||
}
|
}
|
||||||
}).then(function() {
|
|
||||||
|
return promise;
|
||||||
|
}).then(function () {
|
||||||
return MSP.promise(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING));
|
return MSP.promise(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING));
|
||||||
}).then(function() {
|
}).then(function () {
|
||||||
var promise = true;
|
var promise;
|
||||||
if (CONFIG.flightControllerIdentifier === "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||||
promise = MSP.promise(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG));
|
promise = MSP.promise(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG));
|
||||||
}
|
}
|
||||||
|
|
||||||
return promise;
|
return promise;
|
||||||
}).then(function() {
|
}).then(function () {
|
||||||
return MSP.promise(MSP_codes.MSP_EEPROM_WRITE);
|
return MSP.promise(MSP_codes.MSP_EEPROM_WRITE);
|
||||||
}).then(function() {
|
}).then(function () {
|
||||||
GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved'));
|
GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved'));
|
||||||
});
|
});
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// Setup model for rates preview
|
// Setup model for rates preview
|
||||||
|
@ -733,6 +745,8 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||||
}, 250, true);
|
}, 250, true);
|
||||||
|
|
||||||
|
TABS.pid_tuning.profileLoaded = true;
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -765,9 +779,39 @@ TABS.pid_tuning.renderModel = function () {
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.pid_tuning.cleanup = function (callback) {
|
TABS.pid_tuning.cleanup = function (callback) {
|
||||||
|
if (this.model) {
|
||||||
$(window).off('resize', $.proxy(this.model.resize, this.model));
|
$(window).off('resize', $.proxy(this.model.resize, this.model));
|
||||||
|
}
|
||||||
|
|
||||||
this.keepRendering = false;
|
this.keepRendering = false;
|
||||||
|
|
||||||
if (callback) callback();
|
if (callback) callback();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
TABS.pid_tuning.refresh = function (callback) {
|
||||||
|
GUI.tab_switch_cleanup(function () {
|
||||||
|
TABS.pid_tuning.initialize();
|
||||||
|
|
||||||
|
if (callback) {
|
||||||
|
callback();
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
TABS.pid_tuning.checkUpdateProfile = function () {
|
||||||
|
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")
|
||||||
|
&& CONFIG.numProfiles === 2) {
|
||||||
|
$('.tab-pid_tuning select[name="profilechange"] .profile3').hide();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!TABS.pid_tuning.loadingProfile && !TABS.pid_tuning.profileDirty) {
|
||||||
|
var profileElement = $('.tab-pid_tuning select[name="profilechange"]')
|
||||||
|
if (profileElement.length > 0 && parseInt(profileElement.val()) !== CONFIG.profile) {
|
||||||
|
profileElement.val(CONFIG.profile);
|
||||||
|
|
||||||
|
TABS.pid_tuning.refresh(function () {
|
||||||
|
GUI.log(chrome.i18n.getMessage('pidTuningReceivedProfile', [CONFIG.profile + 1]));
|
||||||
|
});
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -432,7 +432,9 @@ TABS.receiver.renderModel = function () {
|
||||||
|
|
||||||
TABS.receiver.cleanup = function (callback) {
|
TABS.receiver.cleanup = function (callback) {
|
||||||
$(window).off('resize', this.resize);
|
$(window).off('resize', this.resize);
|
||||||
|
if (this.model) {
|
||||||
$(window).off('resize', $.proxy(this.model.resize, this.model));
|
$(window).off('resize', $.proxy(this.model.resize, this.model));
|
||||||
|
}
|
||||||
|
|
||||||
this.keepRendering = false;
|
this.keepRendering = false;
|
||||||
|
|
||||||
|
|
|
@ -235,7 +235,9 @@ TABS.setup.renderModel = function () {
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.setup.cleanup = function (callback) {
|
TABS.setup.cleanup = function (callback) {
|
||||||
|
if (this.model) {
|
||||||
$(window).off('resize', $.proxy(this.model.resize, this.model));
|
$(window).off('resize', $.proxy(this.model.resize, this.model));
|
||||||
|
}
|
||||||
|
|
||||||
if (callback) callback();
|
if (callback) callback();
|
||||||
};
|
};
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue