mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-19 14:25:14 +03:00
Revise some new API_VERSION constants
This commit is contained in:
parent
7d57d24107
commit
cab4d89deb
3 changed files with 3 additions and 3 deletions
|
@ -692,7 +692,7 @@ var FC = {
|
|||
getPidDefaults: function() {
|
||||
var versionPidDefaults = DEFAULT_PIDS;
|
||||
// if defaults change they should go here
|
||||
if (semver.gte(CONFIG.apiVersion, "1.43.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
versionPidDefaults = [
|
||||
42, 85, 35, 23, 90,
|
||||
46, 90, 38, 25, 95,
|
||||
|
|
|
@ -472,7 +472,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
escProtocols.push('PROSHOT1000');
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.43.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
escProtocols.push('DISABLED');
|
||||
}
|
||||
|
||||
|
|
|
@ -483,7 +483,7 @@ 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")) {
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
$('.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));
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue