1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-26 01:35:28 +03:00

Raise PID profile count

This commit is contained in:
Mark Haslinghuis 2022-08-01 00:27:56 +02:00
parent 1c775439a1
commit 629df325f1

View file

@ -1458,14 +1458,10 @@ pid_tuning.initialize = function (callback) {
$('.tab-pid_tuning .tab-container .filter').on('click', () => activateSubtab('filter')); $('.tab-pid_tuning .tab-container .filter').on('click', () => activateSubtab('filter'));
function loadProfilesList() { function loadProfilesList() {
let numberOfProfiles = 3; const numberOfProfiles = semver.gte(FC.CONFIG.apiVersion, "1.16.0") ? FC.CONFIG.numProfiles : 3;
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")
&& FC.CONFIG.numProfiles === 2) {
numberOfProfiles = 2;
}
const profileElements = []; const profileElements = [];
for (let i=0; i<numberOfProfiles; i++) { for (let i = 0; i < numberOfProfiles; i++) {
profileElements.push(i18n.getMessage("pidTuningProfileOption",[(i + 1)])); profileElements.push(i18n.getMessage("pidTuningProfileOption",[(i + 1)]));
} }
return profileElements; return profileElements;
@ -1473,12 +1469,17 @@ pid_tuning.initialize = function (callback) {
function loadRateProfilesList() { function loadRateProfilesList() {
let numberOfRateProfiles = 6; let numberOfRateProfiles = 6;
if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_37)) { if (semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_37)) {
numberOfRateProfiles = 3; numberOfRateProfiles = 3;
} }
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45)) {
numberOfRateProfiles = 4;
}
const rateProfileElements = []; const rateProfileElements = [];
for (let i=0; i<numberOfRateProfiles; i++) { for (let i = 0; i < numberOfRateProfiles; i++) {
rateProfileElements.push(i18n.getMessage("pidTuningRateProfileOption",[(i + 1)])); rateProfileElements.push(i18n.getMessage("pidTuningRateProfileOption",[(i + 1)]));
} }
return rateProfileElements; return rateProfileElements;