1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-20 14:55:15 +03:00

Coordinated with new Dmin values

Move Default_pids down
This commit is contained in:
Asizon 2020-04-06 14:38:34 +02:00
parent a9c2184976
commit 19d4db4346
2 changed files with 13 additions and 1 deletions

View file

@ -690,8 +690,15 @@ var FC = {
},
getPidDefaults: function() {
var versionPidDefaults = DEFAULT_PIDS;
// if defaults change they should go here
if (semver.gte(CONFIG.apiVersion, "1.43.0")) {
DEFAULT_PIDS = [
42, 85, 35, 23, 90,
46, 90, 38, 25, 95,
30, 90, 0, 0, 90,
];
}
var versionPidDefaults = DEFAULT_PIDS;
return versionPidDefaults;
},
};

View file

@ -479,6 +479,11 @@ TABS.pid_tuning.initialize = function (callback) {
$('.pid_tuning input[name="dMinRoll"]').val(Math.min(Math.round($('.pid_tuning .ROLL input[name="d"]').val() * 0.57), 100));
$('.pid_tuning input[name="dMinPitch"]').val(Math.min(Math.round($('.pid_tuning .PITCH input[name="d"]').val() * 0.57), 100));
$('.pid_tuning input[name="dMinYaw"]').val(Math.min(Math.round($('.pid_tuning .YAW input[name="d"]').val() * 0.57), 100));
if (semver.gte(CONFIG.apiVersion, "1.43.0")) {
$('.pid_tuning input[name="dMinRoll"]').val(Math.min(Math.round($('.pid_tuning .ROLL input[name="d"]').val() * 0.65), 100));
$('.pid_tuning input[name="dMinPitch"]').val(Math.min(Math.round($('.pid_tuning .PITCH input[name="d"]').val() * 0.65), 100));
$('.pid_tuning input[name="dMinYaw"]').val(Math.min(Math.round($('.pid_tuning .YAW input[name="d"]').val() * 0.65), 100));
}
} else {
$('.pid_tuning input[name="dMinRoll"]').val(ADVANCED_TUNING.dMinRoll);
$('.pid_tuning input[name="dMinPitch"]').val(ADVANCED_TUNING.dMinPitch);