Move FC global vars inside FC object
parent
b9137a68e6
commit
24010a2e2a
|
@ -12,7 +12,7 @@ var CliAutoComplete = {
|
|||
};
|
||||
|
||||
CliAutoComplete.isEnabled = function() {
|
||||
return this.isBuilding() || (this.configEnabled && CONFIG.flightControllerIdentifier == "BTFL" && this.builder.state != 'fail');
|
||||
return this.isBuilding() || (this.configEnabled && FC.CONFIG.flightControllerIdentifier == "BTFL" && this.builder.state != 'fail');
|
||||
};
|
||||
|
||||
CliAutoComplete.isBuilding = function() {
|
||||
|
@ -397,7 +397,7 @@ CliAutoComplete._initTextcomplete = function() {
|
|||
search: function(term, callback, match) {
|
||||
sendOnEnter = false;
|
||||
var arr = cache.resources;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "4.0.0")) {
|
||||
if (semver.gte(FC.CONFIG.flightControllerVersion, "4.0.0")) {
|
||||
arr = ['show'].concat(arr);
|
||||
} else {
|
||||
arr = ['list'].concat(arr);
|
||||
|
@ -509,7 +509,7 @@ CliAutoComplete._initTextcomplete = function() {
|
|||
})
|
||||
]);
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "4.0.0")) {
|
||||
if (semver.gte(FC.CONFIG.flightControllerVersion, "4.0.0")) {
|
||||
$textarea.textcomplete('register', [
|
||||
strategy({ // "resource show all", from BF 4.0.0 onwards
|
||||
match: /^(\s*resource\s+show\s+)(\w*)$/i,
|
||||
|
@ -527,12 +527,12 @@ CliAutoComplete._initTextcomplete = function() {
|
|||
var diffArgs1 = ["master", "profile", "rates", "all"];
|
||||
var diffArgs2 = [];
|
||||
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "3.4.0")) {
|
||||
if (semver.lt(FC.CONFIG.flightControllerVersion, "3.4.0")) {
|
||||
diffArgs2.push("showdefaults");
|
||||
} else {
|
||||
// above 3.4.0
|
||||
diffArgs2.push("defaults");
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "4.0.0")) {
|
||||
if (semver.gte(FC.CONFIG.flightControllerVersion, "4.0.0")) {
|
||||
diffArgs1.push("hardware");
|
||||
diffArgs2.push("bare");
|
||||
}
|
||||
|
|
|
@ -33,27 +33,27 @@ var Features = function (config) {
|
|||
);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0") && !semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0") && !semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
features.push(
|
||||
{bit: 8, group: 'rxFailsafe', name: 'FAILSAFE', haveTip: true}
|
||||
);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.16.0")) {
|
||||
features.push(
|
||||
{bit: 21, group: 'other', name: 'TRANSPONDER', haveTip: true}
|
||||
);
|
||||
}
|
||||
|
||||
if (config.flightControllerVersion !== '') {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.16.0")) {
|
||||
features.push(
|
||||
{bit: 22, group: 'other', name: 'AIRMODE'}
|
||||
);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.16.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
features.push(
|
||||
{bit: 23, group: 'superexpoRates', name: 'SUPEREXPO_RATES'}
|
||||
);
|
||||
|
@ -64,32 +64,32 @@ var Features = function (config) {
|
|||
}
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
features.push(
|
||||
{bit: 18, group: 'other', name: 'OSD'}
|
||||
);
|
||||
if (!semver.gte(CONFIG.apiVersion, "1.35.0")) {
|
||||
if (!semver.gte(FC.CONFIG.apiVersion, "1.35.0")) {
|
||||
features.push(
|
||||
{bit: 24, group: 'other', name: 'VTX'}
|
||||
)
|
||||
}
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) {
|
||||
features.push(
|
||||
{bit: 25, group: 'rxMode', mode: 'select', name: 'RX_SPI'},
|
||||
{bit: 27, group: 'escSensor', name: 'ESC_SENSOR'}
|
||||
);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
features.push(
|
||||
{bit: 28, group: 'antiGravity', name: 'ANTI_GRAVITY', haveTip: true, hideName: true},
|
||||
{bit: 29, group: 'other', name: 'DYNAMIC_FILTER'}
|
||||
);
|
||||
}
|
||||
|
||||
if (!semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (!semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
features.push(
|
||||
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
|
||||
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'}
|
||||
|
|
|
@ -88,7 +88,7 @@ var RateCurve = function (useLegacyCurve) {
|
|||
var expoPower;
|
||||
var rcRateConstant;
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
expoPower = 3;
|
||||
rcRateConstant = 200;
|
||||
} else {
|
||||
|
@ -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, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
rcCommandf = rcCommandf / (500 - deadband);
|
||||
} else {
|
||||
rcCommandf = rcCommandf / 500;
|
||||
|
|
|
@ -85,14 +85,14 @@ TuningSliders.downscaleSliderValue = function(value) {
|
|||
TuningSliders.initPidSlidersPosition = function() {
|
||||
// used to estimate PID slider positions based on PIDF values, and set respective slider position
|
||||
// provides only an estimation due to limitation of feature without firmware support, to be improved in later versions
|
||||
this.MasterSliderValue = Math.round(PIDs[2][1] / this.PID_DEFAULT[11] * 10) / 10;
|
||||
this.PDRatioSliderValue = Math.round(PIDs[0][2] / PIDs[0][0] / this.defaultPDRatio * 10) / 10;
|
||||
this.MasterSliderValue = Math.round(FC.PIDS[2][1] / this.PID_DEFAULT[11] * 10) / 10;
|
||||
this.PDRatioSliderValue = Math.round(FC.PIDS[0][2] / FC.PIDS[0][0] / this.defaultPDRatio * 10) / 10;
|
||||
if (this.dMinFeatureEnabled) {
|
||||
this.PDGainSliderValue = Math.round(ADVANCED_TUNING.dMinRoll / this.PDRatioSliderValue / this.MasterSliderValue / this.PID_DEFAULT[3] * 10) / 10;
|
||||
this.PDGainSliderValue = Math.round(FC.ADVANCED_TUNING.dMinRoll / this.PDRatioSliderValue / this.MasterSliderValue / this.PID_DEFAULT[3] * 10) / 10;
|
||||
} else {
|
||||
this.PDGainSliderValue = Math.round(PIDs[0][0] / this.MasterSliderValue / (this.PID_DEFAULT[2] * (1 / D_MIN_RATIO)) * 10) / 10;
|
||||
this.PDGainSliderValue = Math.round(FC.PIDS[0][0] / this.MasterSliderValue / (this.PID_DEFAULT[2] * (1 / D_MIN_RATIO)) * 10) / 10;
|
||||
}
|
||||
this.ResponseSliderValue = Math.round(ADVANCED_TUNING.feedforwardRoll / this.MasterSliderValue / this.PID_DEFAULT[4] * 10) / 10;
|
||||
this.ResponseSliderValue = Math.round(FC.ADVANCED_TUNING.feedforwardRoll / this.MasterSliderValue / this.PID_DEFAULT[4] * 10) / 10;
|
||||
|
||||
$('output[name="tuningMasterSlider-number"]').val(this.MasterSliderValue);
|
||||
$('output[name="tuningPDRatioSlider-number"]').val(this.PDRatioSliderValue);
|
||||
|
@ -106,14 +106,14 @@ TuningSliders.initPidSlidersPosition = function() {
|
|||
};
|
||||
|
||||
TuningSliders.initGyroFilterSliderPosition = function() {
|
||||
this.gyroFilterSliderValue = Math.round((FILTER_CONFIG.gyro_lowpass_dyn_min_hz + FILTER_CONFIG.gyro_lowpass_dyn_max_hz + FILTER_CONFIG.gyro_lowpass2_hz) /
|
||||
this.gyroFilterSliderValue = Math.round((FC.FILTER_CONFIG.gyro_lowpass_dyn_min_hz + FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz + FC.FILTER_CONFIG.gyro_lowpass2_hz) /
|
||||
(this.FILTER_DEFAULT.gyro_lowpass_dyn_min_hz + this.FILTER_DEFAULT.gyro_lowpass_dyn_max_hz + this.FILTER_DEFAULT.gyro_lowpass2_hz) * 100) / 100;
|
||||
$('output[name="tuningGyroFilterSlider-number"]').val(this.gyroFilterSliderValue);
|
||||
$('#tuningGyroFilterSlider').val(this.downscaleSliderValue(this.gyroFilterSliderValue));
|
||||
};
|
||||
|
||||
TuningSliders.initDTermFilterSliderPosition = function() {
|
||||
this.dtermFilterSliderValue = Math.round((FILTER_CONFIG.dterm_lowpass_dyn_min_hz + FILTER_CONFIG.dterm_lowpass_dyn_max_hz + FILTER_CONFIG.dterm_lowpass2_hz) /
|
||||
this.dtermFilterSliderValue = Math.round((FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz + FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz + FC.FILTER_CONFIG.dterm_lowpass2_hz) /
|
||||
(this.FILTER_DEFAULT.dterm_lowpass_dyn_min_hz + this.FILTER_DEFAULT.dterm_lowpass_dyn_max_hz + this.FILTER_DEFAULT.dterm_lowpass2_hz) * 100) / 100;
|
||||
$('output[name="tuningDTermFilterSlider-number"]').val(this.dtermFilterSliderValue);
|
||||
$('#tuningDTermFilterSlider').val(this.downscaleSliderValue(this.dtermFilterSliderValue));
|
||||
|
@ -162,7 +162,7 @@ TuningSliders.updatePidSlidersDisplay = function() {
|
|||
|
||||
this.pidSlidersUnavailable = false;
|
||||
let currentPIDs = [];
|
||||
PID_names.forEach(function(elementPid, indexPid) {
|
||||
FC.PID_NAMES.forEach(function(elementPid, indexPid) {
|
||||
let searchRow = $('.pid_tuning .' + elementPid + ' input');
|
||||
searchRow.each(function (indexInput) {
|
||||
if (indexPid < 3 && indexInput < 5) {
|
||||
|
@ -171,7 +171,7 @@ TuningSliders.updatePidSlidersDisplay = function() {
|
|||
});
|
||||
});
|
||||
this.calculateNewPids();
|
||||
PID_names.forEach(function(elementPid, indexPid) {
|
||||
FC.PID_NAMES.forEach(function(elementPid, indexPid) {
|
||||
let searchRow = $('.pid_tuning .' + elementPid + ' input');
|
||||
searchRow.each(function (indexInput) {
|
||||
if (indexPid < 3 && indexInput < 5) {
|
||||
|
@ -196,8 +196,8 @@ TuningSliders.updatePidSlidersDisplay = function() {
|
|||
$('.tuningPIDSliders').toggle(!this.pidSlidersUnavailable);
|
||||
$('.subtab-pid .slidersDisabled').toggle(this.pidSlidersUnavailable);
|
||||
$('.subtab-pid .nonExpertModeSlidersNote').toggle(!this.pidSlidersUnavailable && !this.expertMode);
|
||||
$('.subtab-pid .slidersWarning').toggle((PIDs[1][0] > WARNING_P_GAIN || PIDs[1][1] > WARNING_I_GAIN || PIDs[1][2] > WARNING_DMAX_GAIN ||
|
||||
ADVANCED_TUNING.dMinPitch > WARNING_DMIN_GAIN) && !this.pidSlidersUnavailable);
|
||||
$('.subtab-pid .slidersWarning').toggle((FC.PIDS[1][0] > WARNING_P_GAIN || FC.PIDS[1][1] > WARNING_I_GAIN || FC.PIDS[1][2] > WARNING_DMAX_GAIN ||
|
||||
FC.ADVANCED_TUNING.dMinPitch > WARNING_DMIN_GAIN) && !this.pidSlidersUnavailable);
|
||||
};
|
||||
|
||||
TuningSliders.updateFilterSlidersDisplay = function() {
|
||||
|
@ -252,48 +252,48 @@ TuningSliders.calculateNewPids = function() {
|
|||
|
||||
if (this.dMinFeatureEnabled) {
|
||||
//dmin
|
||||
ADVANCED_TUNING.dMinRoll = Math.round(this.PID_DEFAULT[3] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
ADVANCED_TUNING.dMinPitch = Math.round(this.PID_DEFAULT[8] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
FC.ADVANCED_TUNING.dMinRoll = Math.round(this.PID_DEFAULT[3] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
FC.ADVANCED_TUNING.dMinPitch = Math.round(this.PID_DEFAULT[8] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
// dmax
|
||||
PIDs[0][2] = Math.round(this.PID_DEFAULT[2] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
PIDs[1][2] = Math.round(this.PID_DEFAULT[7] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
FC.PIDS[0][2] = Math.round(this.PID_DEFAULT[2] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
FC.PIDS[1][2] = Math.round(this.PID_DEFAULT[7] * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
} else {
|
||||
ADVANCED_TUNING.dMinRoll = 0;
|
||||
ADVANCED_TUNING.dMinPitch = 0;
|
||||
PIDs[0][2] = Math.round((this.PID_DEFAULT[2] * D_MIN_RATIO) * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
PIDs[1][2] = Math.round((this.PID_DEFAULT[7] * D_MIN_RATIO) * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
FC.ADVANCED_TUNING.dMinRoll = 0;
|
||||
FC.ADVANCED_TUNING.dMinPitch = 0;
|
||||
FC.PIDS[0][2] = Math.round((this.PID_DEFAULT[2] * D_MIN_RATIO) * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
FC.PIDS[1][2] = Math.round((this.PID_DEFAULT[7] * D_MIN_RATIO) * this.PDGainSliderValue * this.PDRatioSliderValue);
|
||||
}
|
||||
// p
|
||||
PIDs[0][0] = Math.round(this.PID_DEFAULT[0] * this.PDGainSliderValue);
|
||||
PIDs[1][0] = Math.round(this.PID_DEFAULT[5] * this.PDGainSliderValue);
|
||||
PIDs[2][0] = Math.round(this.PID_DEFAULT[10] * this.PDGainSliderValue);
|
||||
FC.PIDS[0][0] = Math.round(this.PID_DEFAULT[0] * this.PDGainSliderValue);
|
||||
FC.PIDS[1][0] = Math.round(this.PID_DEFAULT[5] * this.PDGainSliderValue);
|
||||
FC.PIDS[2][0] = Math.round(this.PID_DEFAULT[10] * this.PDGainSliderValue);
|
||||
// ff
|
||||
ADVANCED_TUNING.feedforwardRoll = Math.round(this.PID_DEFAULT[4] * this.ResponseSliderValue);
|
||||
ADVANCED_TUNING.feedforwardPitch = Math.round(this.PID_DEFAULT[9] * this.ResponseSliderValue);
|
||||
ADVANCED_TUNING.feedforwardYaw = Math.round(this.PID_DEFAULT[14] * this.ResponseSliderValue);
|
||||
FC.ADVANCED_TUNING.feedforwardRoll = Math.round(this.PID_DEFAULT[4] * this.ResponseSliderValue);
|
||||
FC.ADVANCED_TUNING.feedforwardPitch = Math.round(this.PID_DEFAULT[9] * this.ResponseSliderValue);
|
||||
FC.ADVANCED_TUNING.feedforwardYaw = Math.round(this.PID_DEFAULT[14] * this.ResponseSliderValue);
|
||||
|
||||
// master slider part
|
||||
// these are not calculated anywhere other than master slider multiplier therefore set at default before every calculation
|
||||
PIDs[0][1] = this.PID_DEFAULT[1];
|
||||
PIDs[1][1] = this.PID_DEFAULT[6];
|
||||
PIDs[2][1] = this.PID_DEFAULT[11];
|
||||
FC.PIDS[0][1] = this.PID_DEFAULT[1];
|
||||
FC.PIDS[1][1] = this.PID_DEFAULT[6];
|
||||
FC.PIDS[2][1] = this.PID_DEFAULT[11];
|
||||
// yaw d, dmin
|
||||
PIDs[2][2] = this.PID_DEFAULT[12];
|
||||
ADVANCED_TUNING.dMinYaw = this.PID_DEFAULT[13];
|
||||
FC.PIDS[2][2] = this.PID_DEFAULT[12];
|
||||
FC.ADVANCED_TUNING.dMinYaw = this.PID_DEFAULT[13];
|
||||
|
||||
//master slider multiplication, max value 200 for main PID values
|
||||
for (let i = 0; i < 3; i++) {
|
||||
for (let j = 0; j < 3; j++) {
|
||||
PIDs[j][i] = Math.min(Math.round(PIDs[j][i] * this.MasterSliderValue), MAX_PID_GAIN);
|
||||
FC.PIDS[j][i] = Math.min(Math.round(FC.PIDS[j][i] * this.MasterSliderValue), MAX_PID_GAIN);
|
||||
}
|
||||
}
|
||||
ADVANCED_TUNING.feedforwardRoll = Math.min(Math.round(ADVANCED_TUNING.feedforwardRoll * this.MasterSliderValue), MAX_FF_GAIN);
|
||||
ADVANCED_TUNING.feedforwardPitch = Math.min(Math.round(ADVANCED_TUNING.feedforwardPitch * this.MasterSliderValue), MAX_FF_GAIN);
|
||||
ADVANCED_TUNING.feedforwardYaw = Math.min(Math.round(ADVANCED_TUNING.feedforwardYaw * this.MasterSliderValue), MAX_FF_GAIN);
|
||||
FC.ADVANCED_TUNING.feedforwardRoll = Math.min(Math.round(FC.ADVANCED_TUNING.feedforwardRoll * this.MasterSliderValue), MAX_FF_GAIN);
|
||||
FC.ADVANCED_TUNING.feedforwardPitch = Math.min(Math.round(FC.ADVANCED_TUNING.feedforwardPitch * this.MasterSliderValue), MAX_FF_GAIN);
|
||||
FC.ADVANCED_TUNING.feedforwardYaw = Math.min(Math.round(FC.ADVANCED_TUNING.feedforwardYaw * this.MasterSliderValue), MAX_FF_GAIN);
|
||||
if (this.dMinFeatureEnabled) {
|
||||
ADVANCED_TUNING.dMinRoll = Math.min(Math.round(ADVANCED_TUNING.dMinRoll * this.MasterSliderValue), MAX_DMIN_GAIN);
|
||||
ADVANCED_TUNING.dMinPitch = Math.min(Math.round(ADVANCED_TUNING.dMinPitch * this.MasterSliderValue), MAX_DMIN_GAIN);
|
||||
ADVANCED_TUNING.dMinYaw = Math.min(Math.round(ADVANCED_TUNING.dMinYaw * this.MasterSliderValue), MAX_DMIN_GAIN);
|
||||
FC.ADVANCED_TUNING.dMinRoll = Math.min(Math.round(FC.ADVANCED_TUNING.dMinRoll * this.MasterSliderValue), MAX_DMIN_GAIN);
|
||||
FC.ADVANCED_TUNING.dMinPitch = Math.min(Math.round(FC.ADVANCED_TUNING.dMinPitch * this.MasterSliderValue), MAX_DMIN_GAIN);
|
||||
FC.ADVANCED_TUNING.dMinYaw = Math.min(Math.round(FC.ADVANCED_TUNING.dMinYaw * this.MasterSliderValue), MAX_DMIN_GAIN);
|
||||
}
|
||||
|
||||
$('output[name="tuningMasterSlider-number"]').val(this.MasterSliderValue);
|
||||
|
@ -302,52 +302,52 @@ TuningSliders.calculateNewPids = function() {
|
|||
$('output[name="tuningResponseSlider-number"]').val(this.ResponseSliderValue);
|
||||
|
||||
// updates values in forms
|
||||
PID_names.forEach(function(elementPid, indexPid) {
|
||||
FC.PID_NAMES.forEach(function(elementPid, indexPid) {
|
||||
let searchRow = $('.pid_tuning .' + elementPid + ' input');
|
||||
searchRow.each(function (indexInput) {
|
||||
if (indexPid < 3 && indexInput < 3) {
|
||||
$(this).val(PIDs[indexPid][indexInput]);
|
||||
$(this).val(FC.PIDS[indexPid][indexInput]);
|
||||
}
|
||||
});
|
||||
});
|
||||
$('.pid_tuning input[name="dMinRoll"]').val(ADVANCED_TUNING.dMinRoll);
|
||||
$('.pid_tuning input[name="dMinPitch"]').val(ADVANCED_TUNING.dMinPitch);
|
||||
$('.pid_tuning input[name="dMinYaw"]').val(ADVANCED_TUNING.dMinYaw);
|
||||
$('.pid_tuning .ROLL input[name="f"]').val(ADVANCED_TUNING.feedforwardRoll);
|
||||
$('.pid_tuning .PITCH input[name="f"]').val(ADVANCED_TUNING.feedforwardPitch);
|
||||
$('.pid_tuning .YAW input[name="f"]').val(ADVANCED_TUNING.feedforwardYaw);
|
||||
$('.pid_tuning input[name="dMinRoll"]').val(FC.ADVANCED_TUNING.dMinRoll);
|
||||
$('.pid_tuning input[name="dMinPitch"]').val(FC.ADVANCED_TUNING.dMinPitch);
|
||||
$('.pid_tuning input[name="dMinYaw"]').val(FC.ADVANCED_TUNING.dMinYaw);
|
||||
$('.pid_tuning .ROLL input[name="f"]').val(FC.ADVANCED_TUNING.feedforwardRoll);
|
||||
$('.pid_tuning .PITCH input[name="f"]').val(FC.ADVANCED_TUNING.feedforwardPitch);
|
||||
$('.pid_tuning .YAW input[name="f"]').val(FC.ADVANCED_TUNING.feedforwardYaw);
|
||||
|
||||
TABS.pid_tuning.updatePIDColors();
|
||||
};
|
||||
|
||||
TuningSliders.calculateNewGyroFilters = function() {
|
||||
// calculate, set and display new values in forms based on slider position
|
||||
FILTER_CONFIG.gyro_lowpass_dyn_min_hz = Math.round(this.FILTER_DEFAULT.gyro_lowpass_dyn_min_hz * this.gyroFilterSliderValue);
|
||||
FILTER_CONFIG.gyro_lowpass_dyn_max_hz = Math.round(this.FILTER_DEFAULT.gyro_lowpass_dyn_max_hz * this.gyroFilterSliderValue);
|
||||
FILTER_CONFIG.gyro_lowpass2_hz = Math.round(this.FILTER_DEFAULT.gyro_lowpass2_hz * this.gyroFilterSliderValue);
|
||||
FILTER_CONFIG.gyro_lowpass_type = this.FILTER_DEFAULT.gyro_lowpass_type;
|
||||
FILTER_CONFIG.gyro_lowpass2_type = this.FILTER_DEFAULT.gyro_lowpass2_type;
|
||||
FC.FILTER_CONFIG.gyro_lowpass_dyn_min_hz = Math.round(this.FILTER_DEFAULT.gyro_lowpass_dyn_min_hz * this.gyroFilterSliderValue);
|
||||
FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz = Math.round(this.FILTER_DEFAULT.gyro_lowpass_dyn_max_hz * this.gyroFilterSliderValue);
|
||||
FC.FILTER_CONFIG.gyro_lowpass2_hz = Math.round(this.FILTER_DEFAULT.gyro_lowpass2_hz * this.gyroFilterSliderValue);
|
||||
FC.FILTER_CONFIG.gyro_lowpass_type = this.FILTER_DEFAULT.gyro_lowpass_type;
|
||||
FC.FILTER_CONFIG.gyro_lowpass2_type = this.FILTER_DEFAULT.gyro_lowpass2_type;
|
||||
|
||||
$('.pid_filter input[name="gyroLowpassDynMinFrequency"]').val(FILTER_CONFIG.gyro_lowpass_dyn_min_hz);
|
||||
$('.pid_filter input[name="gyroLowpassDynMaxFrequency"]').val(FILTER_CONFIG.gyro_lowpass_dyn_max_hz);
|
||||
$('.pid_filter input[name="gyroLowpass2Frequency"]').val(FILTER_CONFIG.gyro_lowpass2_hz);
|
||||
$('.pid_filter select[name="gyroLowpassDynType').val(FILTER_CONFIG.gyro_lowpass_type);
|
||||
$('.pid_filter select[name="gyroLowpass2Type').val(FILTER_CONFIG.gyro_lowpass2_type);
|
||||
$('.pid_filter input[name="gyroLowpassDynMinFrequency"]').val(FC.FILTER_CONFIG.gyro_lowpass_dyn_min_hz);
|
||||
$('.pid_filter input[name="gyroLowpassDynMaxFrequency"]').val(FC.FILTER_CONFIG.gyro_lowpass_dyn_max_hz);
|
||||
$('.pid_filter input[name="gyroLowpass2Frequency"]').val(FC.FILTER_CONFIG.gyro_lowpass2_hz);
|
||||
$('.pid_filter select[name="gyroLowpassDynType').val(FC.FILTER_CONFIG.gyro_lowpass_type);
|
||||
$('.pid_filter select[name="gyroLowpass2Type').val(FC.FILTER_CONFIG.gyro_lowpass2_type);
|
||||
$('output[name="tuningGyroFilterSlider-number"]').val(this.gyroFilterSliderValue);
|
||||
};
|
||||
|
||||
TuningSliders.calculateNewDTermFilters = function() {
|
||||
// calculate, set and display new values in forms based on slider position
|
||||
FILTER_CONFIG.dterm_lowpass_dyn_min_hz = Math.round(this.FILTER_DEFAULT.dterm_lowpass_dyn_min_hz * this.dtermFilterSliderValue);
|
||||
FILTER_CONFIG.dterm_lowpass_dyn_max_hz = Math.round(this.FILTER_DEFAULT.dterm_lowpass_dyn_max_hz * this.dtermFilterSliderValue);
|
||||
FILTER_CONFIG.dterm_lowpass2_hz = Math.round(this.FILTER_DEFAULT.dterm_lowpass2_hz * this.dtermFilterSliderValue);
|
||||
FILTER_CONFIG.dterm_lowpass_type = this.FILTER_DEFAULT.dterm_lowpass_type;
|
||||
FILTER_CONFIG.dterm_lowpass2_type = this.FILTER_DEFAULT.dterm_lowpass2_type;
|
||||
FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz = Math.round(this.FILTER_DEFAULT.dterm_lowpass_dyn_min_hz * this.dtermFilterSliderValue);
|
||||
FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz = Math.round(this.FILTER_DEFAULT.dterm_lowpass_dyn_max_hz * this.dtermFilterSliderValue);
|
||||
FC.FILTER_CONFIG.dterm_lowpass2_hz = Math.round(this.FILTER_DEFAULT.dterm_lowpass2_hz * this.dtermFilterSliderValue);
|
||||
FC.FILTER_CONFIG.dterm_lowpass_type = this.FILTER_DEFAULT.dterm_lowpass_type;
|
||||
FC.FILTER_CONFIG.dterm_lowpass2_type = this.FILTER_DEFAULT.dterm_lowpass2_type;
|
||||
|
||||
$('.pid_filter input[name="dtermLowpassDynMinFrequency"]').val(FILTER_CONFIG.dterm_lowpass_dyn_min_hz);
|
||||
$('.pid_filter input[name="dtermLowpassDynMaxFrequency"]').val(FILTER_CONFIG.dterm_lowpass_dyn_max_hz);
|
||||
$('.pid_filter input[name="dtermLowpass2Frequency"]').val(FILTER_CONFIG.dterm_lowpass2_hz);
|
||||
$('.pid_filter select[name="dtermLowpassDynType').val(FILTER_CONFIG.dterm_lowpass_type);
|
||||
$('.pid_filter select[name="dtermLowpass2Type').val(FILTER_CONFIG.dterm_lowpass2_type);
|
||||
$('.pid_filter input[name="dtermLowpassDynMinFrequency"]').val(FC.FILTER_CONFIG.dterm_lowpass_dyn_min_hz);
|
||||
$('.pid_filter input[name="dtermLowpassDynMaxFrequency"]').val(FC.FILTER_CONFIG.dterm_lowpass_dyn_max_hz);
|
||||
$('.pid_filter input[name="dtermLowpass2Frequency"]').val(FC.FILTER_CONFIG.dterm_lowpass2_hz);
|
||||
$('.pid_filter select[name="dtermLowpassDynType').val(FC.FILTER_CONFIG.dterm_lowpass_type);
|
||||
$('.pid_filter select[name="dtermLowpass2Type').val(FC.FILTER_CONFIG.dterm_lowpass2_type);
|
||||
$('output[name="tuningDTermFilterSlider-number"]').val(this.dtermFilterSliderValue);
|
||||
};
|
||||
|
|
|
@ -13,7 +13,7 @@ function configuration_backup(callback) {
|
|||
|
||||
var configuration = {
|
||||
'generatedBy': version,
|
||||
'apiVersion': CONFIG.apiVersion,
|
||||
'apiVersion': FC.CONFIG.apiVersion,
|
||||
'profiles': [],
|
||||
};
|
||||
|
||||
|
@ -28,10 +28,10 @@ function configuration_backup(callback) {
|
|||
];
|
||||
|
||||
function update_profile_specific_data_list() {
|
||||
if (semver.gt(CONFIG.apiVersion, "1.12.0")) {
|
||||
if (semver.gt(FC.CONFIG.apiVersion, "1.12.0")) {
|
||||
profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
profileSpecificData.push(MSPCodes.MSP_RC_DEADBAND);
|
||||
}
|
||||
}
|
||||
|
@ -39,7 +39,7 @@ function configuration_backup(callback) {
|
|||
update_profile_specific_data_list();
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
|
||||
activeProfile = CONFIG.profile;
|
||||
activeProfile = FC.CONFIG.profile;
|
||||
select_profile();
|
||||
});
|
||||
|
||||
|
@ -56,7 +56,7 @@ function configuration_backup(callback) {
|
|||
codeKey = 0;
|
||||
|
||||
function fetch_specific_data_item() {
|
||||
if (fetchingProfile < CONFIG.numProfiles) {
|
||||
if (fetchingProfile < FC.CONFIG.numProfiles) {
|
||||
MSP.send_message(profileSpecificData[codeKey], false, false, function () {
|
||||
codeKey++;
|
||||
|
||||
|
@ -64,18 +64,18 @@ function configuration_backup(callback) {
|
|||
fetch_specific_data_item();
|
||||
} else {
|
||||
configuration.profiles.push({
|
||||
'PID': jQuery.extend(true, {}, PID),
|
||||
'PIDs': jQuery.extend(true, [], PIDs),
|
||||
'RC': jQuery.extend(true, {}, RC_tuning),
|
||||
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
|
||||
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
|
||||
'ServoRules': jQuery.extend(true, [], SERVO_RULES),
|
||||
'ModeRanges': jQuery.extend(true, [], MODE_RANGES),
|
||||
'AdjustmentRanges': jQuery.extend(true, [], ADJUSTMENT_RANGES)
|
||||
'PID': jQuery.extend(true, {}, FC.PID),
|
||||
'PIDs': jQuery.extend(true, [], FC.PIDS),
|
||||
'RC': jQuery.extend(true, {}, FC.RC_TUNING),
|
||||
'AccTrim': jQuery.extend(true, [], FC.CONFIG.accelerometerTrims),
|
||||
'ServoConfig': jQuery.extend(true, [], FC.SERVO_CONFIG),
|
||||
'ServoRules': jQuery.extend(true, [], FC.SERVO_RULES),
|
||||
'ModeRanges': jQuery.extend(true, [], FC.MODE_RANGES),
|
||||
'AdjustmentRanges': jQuery.extend(true, [], FC.ADJUSTMENT_RANGES)
|
||||
});
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.profiles[fetchingProfile].RCdeadband = jQuery.extend(true, {}, RC_DEADBAND_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.profiles[fetchingProfile].RCdeadband = jQuery.extend(true, {}, FC.RC_DEADBAND_CONFIG);
|
||||
}
|
||||
codeKey = 0;
|
||||
fetchingProfile++;
|
||||
|
@ -100,29 +100,29 @@ function configuration_backup(callback) {
|
|||
];
|
||||
|
||||
function update_unique_data_list() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.8.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_LOOP_TIME);
|
||||
uniqueData.push(MSPCodes.MSP_ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MOTOR_3D_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSPCodes.MSP_RX_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_FAILSAFE_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_RXFAIL_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_LED_STRIP_MODECOLOR);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MOTOR_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_RSSI_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_GPS_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_FEATURE_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MODE_RANGES_EXTRA);
|
||||
}
|
||||
}
|
||||
|
@ -139,44 +139,44 @@ function configuration_backup(callback) {
|
|||
fetch_unique_data_item();
|
||||
});
|
||||
} else {
|
||||
configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
|
||||
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG);
|
||||
configuration.LED_STRIP = jQuery.extend(true, [], LED_STRIP);
|
||||
configuration.LED_COLORS = jQuery.extend(true, [], LED_COLORS);
|
||||
configuration.BOARD_ALIGNMENT_CONFIG = jQuery.extend(true, {}, BOARD_ALIGNMENT_CONFIG);
|
||||
configuration.CRAFT_NAME = CONFIG.name;
|
||||
configuration.DISPLAY_NAME = CONFIG.displayName;
|
||||
configuration.MIXER_CONFIG = jQuery.extend(true, {}, MIXER_CONFIG);
|
||||
configuration.SENSOR_CONFIG = jQuery.extend(true, {}, SENSOR_CONFIG);
|
||||
configuration.PID_ADVANCED_CONFIG = jQuery.extend(true, {}, PID_ADVANCED_CONFIG);
|
||||
configuration.RCMAP = jQuery.extend(true, [], FC.RC_MAP);
|
||||
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, FC.SERIAL_CONFIG);
|
||||
configuration.LED_STRIP = jQuery.extend(true, [], FC.LED_STRIP);
|
||||
configuration.LED_COLORS = jQuery.extend(true, [], FC.LED_COLORS);
|
||||
configuration.BOARD_ALIGNMENT_CONFIG = jQuery.extend(true, {}, FC.BOARD_ALIGNMENT_CONFIG);
|
||||
configuration.CRAFT_NAME = FC.CONFIG.name;
|
||||
configuration.DISPLAY_NAME = FC.CONFIG.displayName;
|
||||
configuration.MIXER_CONFIG = jQuery.extend(true, {}, FC.MIXER_CONFIG);
|
||||
configuration.SENSOR_CONFIG = jQuery.extend(true, {}, FC.SENSOR_CONFIG);
|
||||
configuration.PID_ADVANCED_CONFIG = jQuery.extend(true, {}, FC.PID_ADVANCED_CONFIG);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
configuration.LED_MODE_COLORS = jQuery.extend(true, [], LED_MODE_COLORS);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
configuration.LED_MODE_COLORS = jQuery.extend(true, [], FC.LED_MODE_COLORS);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
configuration.FC_CONFIG = jQuery.extend(true, {}, FC_CONFIG);
|
||||
configuration.ARMING_CONFIG = jQuery.extend(true, {}, ARMING_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.8.0")) {
|
||||
configuration.FC_CONFIG = jQuery.extend(true, {}, FC.FC_CONFIG);
|
||||
configuration.ARMING_CONFIG = jQuery.extend(true, {}, FC.ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
configuration.MOTOR_3D_CONFIG = jQuery.extend(true, {}, MOTOR_3D_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
configuration.MOTOR_3D_CONFIG = jQuery.extend(true, {}, FC.MOTOR_3D_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.SENSOR_ALIGNMENT = jQuery.extend(true, {}, SENSOR_ALIGNMENT);
|
||||
configuration.RX_CONFIG = jQuery.extend(true, {}, RX_CONFIG);
|
||||
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FAILSAFE_CONFIG);
|
||||
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], RXFAIL_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.SENSOR_ALIGNMENT = jQuery.extend(true, {}, FC.SENSOR_ALIGNMENT);
|
||||
configuration.RX_CONFIG = jQuery.extend(true, {}, FC.RX_CONFIG);
|
||||
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FC.FAILSAFE_CONFIG);
|
||||
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], FC.RXFAIL_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
configuration.RSSI_CONFIG = jQuery.extend(true, {}, RSSI_CONFIG);
|
||||
configuration.FEATURE_CONFIG = jQuery.extend(true, {}, FEATURE_CONFIG);
|
||||
configuration.MOTOR_CONFIG = jQuery.extend(true, {}, MOTOR_CONFIG);
|
||||
configuration.GPS_CONFIG = jQuery.extend(true, {}, GPS_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
configuration.RSSI_CONFIG = jQuery.extend(true, {}, FC.RSSI_CONFIG);
|
||||
configuration.FEATURE_CONFIG = jQuery.extend(true, {}, FC.FEATURE_CONFIG);
|
||||
configuration.MOTOR_CONFIG = jQuery.extend(true, {}, FC.MOTOR_CONFIG);
|
||||
configuration.GPS_CONFIG = jQuery.extend(true, {}, FC.GPS_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
configuration.BEEPER_CONFIG = jQuery.extend(true, {}, BEEPER_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
configuration.BEEPER_CONFIG = jQuery.extend(true, {}, FC.BEEPER_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
configuration.MODE_RANGES_EXTRA = jQuery.extend(true, [], MODE_RANGES_EXTRA);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
configuration.MODE_RANGES_EXTRA = jQuery.extend(true, [], FC.MODE_RANGES_EXTRA);
|
||||
}
|
||||
|
||||
save();
|
||||
|
@ -339,7 +339,7 @@ function configuration_restore(callback) {
|
|||
return;
|
||||
}
|
||||
if (configuration.FEATURE_CONFIG.features._featureMask) {
|
||||
var features = new Features(CONFIG);
|
||||
var features = new Features(FC.CONFIG);
|
||||
features.setMask(configuration.FEATURE_CONFIG.features._featureMask);
|
||||
configuration.FEATURE_CONFIG.features = features;
|
||||
}
|
||||
|
@ -421,8 +421,8 @@ function configuration_restore(callback) {
|
|||
configuration.LED_STRIP = fixed_led_strip;
|
||||
}
|
||||
|
||||
for (var profileIndex = 0; profileIndex < 3; profileIndex++) {
|
||||
var RC = configuration.profiles[profileIndex].RC;
|
||||
for (let profileIndex = 0; profileIndex < 3; profileIndex++) {
|
||||
const RC = configuration.profiles[profileIndex].RC;
|
||||
// TPA breakpoint was added
|
||||
if (!RC.dynamic_THR_breakpoint) {
|
||||
RC.dynamic_THR_breakpoint = 1500; // firmware default
|
||||
|
@ -555,7 +555,7 @@ function configuration_restore(callback) {
|
|||
appliedMigrationsCount++;
|
||||
}
|
||||
|
||||
if (semver.lt(configuration.apiVersion, '1.14.0') && semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
if (semver.lt(configuration.apiVersion, '1.14.0') && semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
// api 1.14 removed old pid controllers
|
||||
for (var profileIndex = 0; profileIndex < configuration.profiles.length; profileIndex++) {
|
||||
var newPidControllerIndex = configuration.profiles[profileIndex].PID.controller;
|
||||
|
@ -659,8 +659,8 @@ function configuration_restore(callback) {
|
|||
|
||||
if (compareVersions(migratedVersion, '1.2.0')) {
|
||||
// old version of the configurator incorrectly had a 'disabled' option for GPS SBAS mode.
|
||||
if (GPS_CONFIG.ublox_sbas < 0) {
|
||||
GPS_CONFIG.ublox_sbas = 0;
|
||||
if (FC.GPS_CONFIG.ublox_sbas < 0) {
|
||||
FC.GPS_CONFIG.ublox_sbas = 0;
|
||||
}
|
||||
migratedVersion = '1.2.0';
|
||||
|
||||
|
@ -693,7 +693,7 @@ function configuration_restore(callback) {
|
|||
function configuration_upload(configuration, callback) {
|
||||
function upload() {
|
||||
var activeProfile = null;
|
||||
var numProfiles = CONFIG.numProfiles;
|
||||
var numProfiles = FC.CONFIG.numProfiles;
|
||||
if (configuration.profiles.length < numProfiles) {
|
||||
numProfiles = configuration.profiles.length;
|
||||
}
|
||||
|
@ -705,12 +705,12 @@ function configuration_restore(callback) {
|
|||
MSPCodes.MSP_SET_ACC_TRIM
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
profileSpecificData.push(MSPCodes.MSP_SET_RC_DEADBAND);
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
|
||||
activeProfile = CONFIG.profile;
|
||||
activeProfile = FC.CONFIG.profile;
|
||||
select_profile();
|
||||
});
|
||||
|
||||
|
@ -727,15 +727,15 @@ function configuration_restore(callback) {
|
|||
codeKey = 0;
|
||||
|
||||
function load_objects(profile) {
|
||||
PID = configuration.profiles[profile].PID;
|
||||
PIDs = configuration.profiles[profile].PIDs;
|
||||
RC_tuning = configuration.profiles[profile].RC;
|
||||
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||
SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||
MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||
RC_DEADBAND_CONFIG = configuration.profiles[profile].RCdeadband;
|
||||
FC.PID = configuration.profiles[profile].PID;
|
||||
FC.PIDS = configuration.profiles[profile].PIDs;
|
||||
FC.RC_TUNING = configuration.profiles[profile].RC;
|
||||
FC.CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||
FC.SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||
FC.SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||
FC.MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||
FC.ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||
FC.RC_DEADBAND_CONFIG = configuration.profiles[profile].RCdeadband;
|
||||
}
|
||||
|
||||
function upload_using_specific_commands() {
|
||||
|
@ -768,20 +768,20 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function upload_mode_ranges() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
if (configuration.MODE_RANGES_EXTRA == undefined) {
|
||||
MODE_RANGES_EXTRA = [];
|
||||
FC.MODE_RANGES_EXTRA = [];
|
||||
|
||||
for (var modeIndex = 0; modeIndex < MODE_RANGES.length; modeIndex++) {
|
||||
for (var modeIndex = 0; modeIndex < FC.MODE_RANGES.length; modeIndex++) {
|
||||
var defaultModeRangeExtra = {
|
||||
modeId: MODE_RANGES[modeIndex].modeId,
|
||||
modeId: FC.MODE_RANGES[modeIndex].modeId,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
FC.MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
}
|
||||
} else {
|
||||
MODE_RANGES_EXTRA = configuration.MODE_RANGES_EXTRA;
|
||||
FC.MODE_RANGES_EXTRA = configuration.MODE_RANGES_EXTRA;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -812,19 +812,19 @@ function configuration_restore(callback) {
|
|||
uniqueData.push(MSPCodes.MSP_SET_BOARD_ALIGNMENT_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_ADVANCED_CONFIG);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.8.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_LOOP_TIME);
|
||||
uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_MOTOR_3D_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_FEATURE_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_MOTOR_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_GPS_CONFIG);
|
||||
|
@ -833,35 +833,35 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function load_objects() {
|
||||
MISC = configuration.MISC;
|
||||
RC_MAP = configuration.RCMAP;
|
||||
SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
||||
LED_STRIP = configuration.LED_STRIP;
|
||||
LED_COLORS = configuration.LED_COLORS;
|
||||
LED_MODE_COLORS = configuration.LED_MODE_COLORS;
|
||||
ARMING_CONFIG = configuration.ARMING_CONFIG;
|
||||
FC_CONFIG = configuration.FC_CONFIG;
|
||||
MOTOR_3D_CONFIG = configuration.MOTOR_3D_CONFIG;
|
||||
SENSOR_ALIGNMENT = configuration.SENSOR_ALIGNMENT;
|
||||
RX_CONFIG = configuration.RX_CONFIG;
|
||||
FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
|
||||
RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
|
||||
FEATURE_CONFIG = configuration.FEATURE_CONFIG;
|
||||
MOTOR_CONFIG = configuration.MOTOR_CONFIG;
|
||||
GPS_CONFIG = configuration.GPS_CONFIG;
|
||||
RSSI_CONFIG = configuration.RSSI_CONFIG;
|
||||
BOARD_ALIGNMENT_CONFIG = configuration.BOARD_ALIGNMENT_CONFIG;
|
||||
CONFIG.name = configuration.CRAFT_NAME;
|
||||
CONFIG.displayName = configuration.DISPLAY_NAME;
|
||||
MIXER_CONFIG = configuration.MIXER_CONFIG;
|
||||
SENSOR_CONFIG = configuration.SENSOR_CONFIG;
|
||||
PID_ADVANCED_CONFIG = configuration.PID_ADVANCED_CONFIG;
|
||||
FC.MISC = configuration.MISC;
|
||||
FC.RC_MAP = configuration.RCMAP;
|
||||
FC.SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
||||
FC.LED_STRIP = configuration.LED_STRIP;
|
||||
FC.LED_COLORS = configuration.LED_COLORS;
|
||||
FC.LED_MODE_COLORS = configuration.LED_MODE_COLORS;
|
||||
FC.ARMING_CONFIG = configuration.ARMING_CONFIG;
|
||||
FC.FC_CONFIG = configuration.FC_CONFIG;
|
||||
FC.MOTOR_3D_CONFIG = configuration.MOTOR_3D_CONFIG;
|
||||
FC.SENSOR_ALIGNMENT = configuration.SENSOR_ALIGNMENT;
|
||||
FC.RX_CONFIG = configuration.RX_CONFIG;
|
||||
FC.FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
|
||||
FC.RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
|
||||
FC.FEATURE_CONFIG = configuration.FEATURE_CONFIG;
|
||||
FC.MOTOR_CONFIG = configuration.MOTOR_CONFIG;
|
||||
FC.GPS_CONFIG = configuration.GPS_CONFIG;
|
||||
FC.RSSI_CONFIG = configuration.RSSI_CONFIG;
|
||||
FC.BOARD_ALIGNMENT_CONFIG = configuration.BOARD_ALIGNMENT_CONFIG;
|
||||
FC.CONFIG.name = configuration.CRAFT_NAME;
|
||||
FC.CONFIG.displayName = configuration.DISPLAY_NAME;
|
||||
FC.MIXER_CONFIG = configuration.MIXER_CONFIG;
|
||||
FC.SENSOR_CONFIG = configuration.SENSOR_CONFIG;
|
||||
FC.PID_ADVANCED_CONFIG = configuration.PID_ADVANCED_CONFIG;
|
||||
|
||||
BEEPER_CONFIG.beepers = new Beepers(CONFIG);
|
||||
BEEPER_CONFIG.beepers.setMask(configuration.BEEPER_CONFIG.beepers._beeperMask);
|
||||
BEEPER_CONFIG.dshotBeaconTone = configuration.BEEPER_CONFIG.dshotBeaconTone;
|
||||
BEEPER_CONFIG.dshotBeaconConditions = new Beepers(CONFIG, [ "RX_LOST", "RX_SET" ]);
|
||||
BEEPER_CONFIG.dshotBeaconConditions.setMask(configuration.BEEPER_CONFIG.dshotBeaconConditions._beeperMask);
|
||||
FC.BEEPER_CONFIG.beepers = new Beepers(FC.CONFIG);
|
||||
FC.BEEPER_CONFIG.beepers.setMask(configuration.BEEPER_CONFIG.beepers._beeperMask);
|
||||
FC.BEEPER_CONFIG.dshotBeaconTone = configuration.BEEPER_CONFIG.dshotBeaconTone;
|
||||
FC.BEEPER_CONFIG.dshotBeaconConditions = new Beepers(FC.CONFIG, [ "RX_LOST", "RX_SET" ]);
|
||||
FC.BEEPER_CONFIG.dshotBeaconConditions.setMask(configuration.BEEPER_CONFIG.dshotBeaconConditions._beeperMask);
|
||||
}
|
||||
|
||||
function send_unique_data_item() {
|
||||
|
@ -892,14 +892,14 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function send_led_strip_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0"))
|
||||
mspHelper.sendLedStripModeColors(send_rxfail_config);
|
||||
else
|
||||
send_rxfail_config();
|
||||
}
|
||||
|
||||
function send_rxfail_config() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
mspHelper.sendRxFailConfig(save_to_eeprom);
|
||||
} else {
|
||||
save_to_eeprom();
|
||||
|
|
366
src/js/fc.js
366
src/js/fc.js
|
@ -1,75 +1,77 @@
|
|||
'use strict';
|
||||
|
||||
// define all the global variables that are uses to hold FC state
|
||||
var CONFIG;
|
||||
var BF_CONFIG; // Remove when we officialy retire BF 3.1
|
||||
var FEATURE_CONFIG;
|
||||
var BEEPER_CONFIG;
|
||||
var MIXER_CONFIG;
|
||||
var BOARD_ALIGNMENT_CONFIG;
|
||||
var LED_STRIP;
|
||||
var LED_COLORS;
|
||||
var LED_MODE_COLORS;
|
||||
var PID;
|
||||
var PID_names;
|
||||
var PIDS_ACTIVE;
|
||||
var PIDs;
|
||||
var RC_MAP;
|
||||
var RC;
|
||||
var RC_tuning;
|
||||
var AUX_CONFIG;
|
||||
var AUX_CONFIG_IDS;
|
||||
var MODE_RANGES;
|
||||
var MODE_RANGES_EXTRA;
|
||||
var ADJUSTMENT_RANGES;
|
||||
var SERVO_CONFIG;
|
||||
var SERVO_RULES;
|
||||
var SERIAL_CONFIG;
|
||||
var SENSOR_DATA;
|
||||
var MOTOR_DATA;
|
||||
var MOTOR_TELEMETRY_DATA;
|
||||
var SERVO_DATA;
|
||||
var GPS_DATA;
|
||||
var ANALOG;
|
||||
var VOLTAGE_METERS;
|
||||
var VOLTAGE_METER_CONFIGS;
|
||||
var CURRENT_METERS;
|
||||
var CURRENT_METER_CONFIGS;
|
||||
var BATTERY_STATE;
|
||||
var BATTERY_CONFIG;
|
||||
var ARMING_CONFIG;
|
||||
var FC_CONFIG;
|
||||
var MISC; // DEPRECATED
|
||||
var MOTOR_CONFIG;
|
||||
var GPS_CONFIG;
|
||||
var RSSI_CONFIG;
|
||||
var MOTOR_3D_CONFIG;
|
||||
var DATAFLASH;
|
||||
var SDCARD;
|
||||
var BLACKBOX;
|
||||
var TRANSPONDER;
|
||||
var RC_DEADBAND_CONFIG;
|
||||
var SENSOR_ALIGNMENT;
|
||||
var RX_CONFIG;
|
||||
var FAILSAFE_CONFIG;
|
||||
var GPS_RESCUE;
|
||||
var RXFAIL_CONFIG;
|
||||
var PID_ADVANCED_CONFIG;
|
||||
var FILTER_CONFIG;
|
||||
var ADVANCED_TUNING_ACTIVE;
|
||||
var ADVANCED_TUNING;
|
||||
var SENSOR_CONFIG;
|
||||
var COPY_PROFILE;
|
||||
var VTX_CONFIG;
|
||||
var VTXTABLE_BAND;
|
||||
var VTXTABLE_POWERLEVEL;
|
||||
var MULTIPLE_MSP;
|
||||
var DEFAULT;
|
||||
var DEFAULT_PIDS;
|
||||
const FC = {
|
||||
|
||||
var FC = {
|
||||
resetState: function () {
|
||||
CONFIG = {
|
||||
// define all the global variables that are uses to hold FC state
|
||||
// the default state must be defined inside the resetState() method
|
||||
ADJUSTMENT_RANGES: null,
|
||||
ADVANCED_TUNING: null,
|
||||
ADVANCED_TUNING_ACTIVE: null,
|
||||
ANALOG: null,
|
||||
ARMING_CONFIG: null,
|
||||
AUX_CONFIG: null,
|
||||
AUX_CONFIG_IDS: null,
|
||||
BATTERY_CONFIG: null,
|
||||
BATTERY_STATE: null,
|
||||
BEEPER_CONFIG: null,
|
||||
BF_CONFIG: null, // Remove when we officialy retire BF 3.1
|
||||
BLACKBOX: null,
|
||||
BOARD_ALIGNMENT_CONFIG: null,
|
||||
CONFIG: null,
|
||||
COPY_PROFILE: null,
|
||||
CURRENT_METERS: null,
|
||||
CURRENT_METER_CONFIGS: null,
|
||||
DATAFLASH: null,
|
||||
DEFAULT: null,
|
||||
DEFAULT_PIDS: null,
|
||||
FAILSAFE_CONFIG: null,
|
||||
FC_CONFIG: null,
|
||||
FEATURE_CONFIG: null,
|
||||
FILTER_CONFIG: null,
|
||||
GPS_CONFIG: null,
|
||||
GPS_DATA: null,
|
||||
GPS_RESCUE: null,
|
||||
LED_COLORS: null,
|
||||
LED_MODE_COLORS: null,
|
||||
LED_STRIP: null,
|
||||
MISC: null, // DEPRECATED
|
||||
MIXER_CONFIG: null,
|
||||
MODE_RANGES: null,
|
||||
MODE_RANGES_EXTRA: null,
|
||||
MOTOR_3D_CONFIG: null,
|
||||
MOTOR_CONFIG: null,
|
||||
MOTOR_DATA: null,
|
||||
MOTOR_TELEMETRY_DATA: null,
|
||||
MULTIPLE_MSP: null,
|
||||
PID: null,
|
||||
PIDS_ACTIVE: null,
|
||||
PID_ADVANCED_CONFIG: null,
|
||||
PID_NAMES: null,
|
||||
PIDS: null,
|
||||
RC: null,
|
||||
RC_DEADBAND_CONFIG: null,
|
||||
RC_MAP: null,
|
||||
RC_TUNING: null,
|
||||
RSSI_CONFIG: null,
|
||||
RXFAIL_CONFIG: null,
|
||||
RX_CONFIG: null,
|
||||
SDCARD: null,
|
||||
SENSOR_ALIGNMENT: null,
|
||||
SENSOR_CONFIG: null,
|
||||
SENSOR_DATA: null,
|
||||
SERIAL_CONFIG: null,
|
||||
SERVO_CONFIG: null,
|
||||
SERVO_DATA: null,
|
||||
SERVO_RULES: null,
|
||||
TRANSPONDER: null,
|
||||
VOLTAGE_METERS: null,
|
||||
VOLTAGE_METER_CONFIGS: null,
|
||||
VTXTABLE_BAND: null,
|
||||
VTXTABLE_POWERLEVEL: null,
|
||||
VTX_CONFIG: null,
|
||||
|
||||
resetState () {
|
||||
this.CONFIG = {
|
||||
apiVersion: "0.0.0",
|
||||
flightControllerIdentifier: '',
|
||||
flightControllerVersion: '',
|
||||
|
@ -107,66 +109,66 @@ var FC = {
|
|||
configurationProblems: 0,
|
||||
};
|
||||
|
||||
BF_CONFIG = {
|
||||
this.BF_CONFIG = {
|
||||
currentscale: 0,
|
||||
currentoffset: 0,
|
||||
currentmetertype: 0,
|
||||
batterycapacity: 0,
|
||||
};
|
||||
|
||||
COPY_PROFILE = {
|
||||
this.COPY_PROFILE = {
|
||||
type: 0,
|
||||
dstProfile: 0,
|
||||
srcProfile: 0,
|
||||
};
|
||||
|
||||
FEATURE_CONFIG = {
|
||||
|
||||
this.FEATURE_CONFIG = {
|
||||
features: 0,
|
||||
};
|
||||
|
||||
BEEPER_CONFIG = {
|
||||
this.BEEPER_CONFIG = {
|
||||
beepers: 0,
|
||||
dshotBeaconTone: 0,
|
||||
dshotBeaconConditions: 0,
|
||||
};
|
||||
|
||||
MIXER_CONFIG = {
|
||||
|
||||
this.MIXER_CONFIG = {
|
||||
mixer: 0,
|
||||
reverseMotorDir: 0,
|
||||
};
|
||||
};
|
||||
|
||||
BOARD_ALIGNMENT_CONFIG = {
|
||||
this.BOARD_ALIGNMENT_CONFIG = {
|
||||
roll: 0,
|
||||
pitch: 0,
|
||||
yaw: 0,
|
||||
};
|
||||
|
||||
LED_STRIP = [];
|
||||
LED_COLORS = [];
|
||||
LED_MODE_COLORS = [];
|
||||
this.LED_STRIP = [];
|
||||
this.LED_COLORS = [];
|
||||
this.LED_MODE_COLORS = [];
|
||||
|
||||
PID = {
|
||||
controller: 0
|
||||
this.PID = {
|
||||
controller: 0,
|
||||
};
|
||||
|
||||
PID_names = [];
|
||||
PIDS_ACTIVE = new Array(10);
|
||||
PIDs = new Array(10);
|
||||
for (var i = 0; i < 10; i++) {
|
||||
PIDS_ACTIVE[i] = new Array(3);
|
||||
PIDs[i] = new Array(3);
|
||||
this.PID_NAMES = [];
|
||||
this.PIDS_ACTIVE = Array.from({length: 10});
|
||||
this.PIDS = Array.from({length: 10});
|
||||
for (let i = 0; i < 10; i++) {
|
||||
this.PIDS_ACTIVE[i] = Array.from({length: 3});
|
||||
this.PIDS[i] = Array.from({length: 3});
|
||||
}
|
||||
|
||||
RC_MAP = [];
|
||||
this.RC_MAP = [];
|
||||
|
||||
// defaults
|
||||
// roll, pitch, yaw, throttle, aux 1, ... aux n
|
||||
RC = {
|
||||
this.RC = {
|
||||
active_channels: 0,
|
||||
channels: new Array(32),
|
||||
channels: Array.from({length: 32}),
|
||||
};
|
||||
|
||||
RC_tuning = {
|
||||
this.RC_TUNING = {
|
||||
RC_RATE: 0,
|
||||
RC_EXPO: 0,
|
||||
roll_pitch_rate: 0, // pre 1.7 api only
|
||||
|
@ -186,17 +188,17 @@ var FC = {
|
|||
yaw_rate_limit: 1998,
|
||||
};
|
||||
|
||||
AUX_CONFIG = [];
|
||||
AUX_CONFIG_IDS = [];
|
||||
this.AUX_CONFIG = [];
|
||||
this.AUX_CONFIG_IDS = [];
|
||||
|
||||
MODE_RANGES = [];
|
||||
MODE_RANGES_EXTRA = [];
|
||||
ADJUSTMENT_RANGES = [];
|
||||
this.MODE_RANGES = [];
|
||||
this.MODE_RANGES_EXTRA = [];
|
||||
this.ADJUSTMENT_RANGES = [];
|
||||
|
||||
SERVO_CONFIG = [];
|
||||
SERVO_RULES = [];
|
||||
this.SERVO_CONFIG = [];
|
||||
this.SERVO_RULES = [];
|
||||
|
||||
SERIAL_CONFIG = {
|
||||
this.SERIAL_CONFIG = {
|
||||
ports: [],
|
||||
|
||||
// pre 1.6 settings
|
||||
|
@ -206,7 +208,7 @@ var FC = {
|
|||
cliBaudRate: 0,
|
||||
};
|
||||
|
||||
SENSOR_DATA = {
|
||||
this.SENSOR_DATA = {
|
||||
gyroscope: [0, 0, 0],
|
||||
accelerometer: [0, 0, 0],
|
||||
magnetometer: [0, 0, 0],
|
||||
|
@ -216,10 +218,10 @@ var FC = {
|
|||
debug: [0, 0, 0, 0],
|
||||
};
|
||||
|
||||
MOTOR_DATA = new Array(8);
|
||||
SERVO_DATA = new Array(8);
|
||||
this.MOTOR_DATA = Array.from({length: 8});
|
||||
this.SERVO_DATA = Array.from({length: 8});
|
||||
|
||||
MOTOR_TELEMETRY_DATA = {
|
||||
this.MOTOR_TELEMETRY_DATA = {
|
||||
rpm: [0, 0, 0, 0, 0, 0, 0, 0],
|
||||
invalidPercent: [0, 0, 0, 0, 0, 0, 0, 0],
|
||||
temperature: [0, 0, 0, 0, 0, 0, 0, 0],
|
||||
|
@ -228,7 +230,7 @@ var FC = {
|
|||
consumption: [0, 0, 0, 0, 0, 0, 0, 0],
|
||||
};
|
||||
|
||||
GPS_DATA = {
|
||||
this.GPS_DATA = {
|
||||
fix: 0,
|
||||
numSat: 0,
|
||||
lat: 0,
|
||||
|
@ -243,24 +245,24 @@ var FC = {
|
|||
chn: [],
|
||||
svid: [],
|
||||
quality: [],
|
||||
cno: []
|
||||
cno: [],
|
||||
};
|
||||
|
||||
ANALOG = {
|
||||
this.ANALOG = {
|
||||
voltage: 0,
|
||||
mAhdrawn: 0,
|
||||
rssi: 0,
|
||||
amperage: 0,
|
||||
last_received_timestamp: Date.now() // FIXME this code lies, it's never been received at this point
|
||||
last_received_timestamp: Date.now(), // FIXME this code lies, it's never been received at this point
|
||||
};
|
||||
|
||||
VOLTAGE_METERS = [];
|
||||
VOLTAGE_METER_CONFIGS = [];
|
||||
CURRENT_METERS = [];
|
||||
CURRENT_METER_CONFIGS = [];
|
||||
this.VOLTAGE_METERS = [];
|
||||
this.VOLTAGE_METER_CONFIGS = [];
|
||||
this.CURRENT_METERS = [];
|
||||
this.CURRENT_METER_CONFIGS = [];
|
||||
|
||||
BATTERY_STATE = {};
|
||||
BATTERY_CONFIG = {
|
||||
this.BATTERY_STATE = {};
|
||||
this.BATTERY_CONFIG = {
|
||||
vbatmincellvoltage: 0,
|
||||
vbatmaxcellvoltage: 0,
|
||||
vbatwarningcellvoltage: 0,
|
||||
|
@ -269,17 +271,17 @@ var FC = {
|
|||
currentMeterSource: 0,
|
||||
};
|
||||
|
||||
ARMING_CONFIG = {
|
||||
this.ARMING_CONFIG = {
|
||||
auto_disarm_delay: 0,
|
||||
disarm_kill_switch: 0,
|
||||
small_angle: 0,
|
||||
};
|
||||
|
||||
FC_CONFIG = {
|
||||
loopTime: 0
|
||||
this.FC_CONFIG = {
|
||||
loopTime: 0,
|
||||
};
|
||||
|
||||
MISC = {
|
||||
this.MISC = {
|
||||
// DEPRECATED = only used to store values that are written back to the fc as-is, do NOT use for any other purpose
|
||||
failsafe_throttle: 0,
|
||||
gps_baudrate: 0,
|
||||
|
@ -291,7 +293,7 @@ var FC = {
|
|||
vbatwarningcellvoltage: 0,
|
||||
batterymetertype: 1, // 1=ADC, 2=ESC
|
||||
};
|
||||
MOTOR_CONFIG = {
|
||||
this.MOTOR_CONFIG = {
|
||||
minthrottle: 0,
|
||||
maxthrottle: 0,
|
||||
mincommand: 0,
|
||||
|
@ -301,7 +303,7 @@ var FC = {
|
|||
use_esc_sensor: false,
|
||||
};
|
||||
|
||||
GPS_CONFIG = {
|
||||
this.GPS_CONFIG = {
|
||||
provider: 0,
|
||||
ublox_sbas: 0,
|
||||
auto_config: 0,
|
||||
|
@ -310,25 +312,25 @@ var FC = {
|
|||
ublox_use_galileo: 0,
|
||||
};
|
||||
|
||||
RSSI_CONFIG = {
|
||||
this.RSSI_CONFIG = {
|
||||
channel: 0,
|
||||
};
|
||||
|
||||
MOTOR_3D_CONFIG = {
|
||||
this.MOTOR_3D_CONFIG = {
|
||||
deadband3d_low: 0,
|
||||
deadband3d_high: 0,
|
||||
neutral: 0,
|
||||
};
|
||||
|
||||
DATAFLASH = {
|
||||
this.DATAFLASH = {
|
||||
ready: false,
|
||||
supported: false,
|
||||
sectors: 0,
|
||||
totalSize: 0,
|
||||
usedSize: 0
|
||||
usedSize: 0,
|
||||
};
|
||||
|
||||
SDCARD = {
|
||||
this.SDCARD = {
|
||||
supported: false,
|
||||
state: 0,
|
||||
filesystemLastError: 0,
|
||||
|
@ -336,7 +338,7 @@ var FC = {
|
|||
totalSizeKB: 0,
|
||||
};
|
||||
|
||||
BLACKBOX = {
|
||||
this.BLACKBOX = {
|
||||
supported: false,
|
||||
blackboxDevice: 0,
|
||||
blackboxRateNum: 1,
|
||||
|
@ -345,21 +347,21 @@ var FC = {
|
|||
blackboxSampleRate: 0,
|
||||
};
|
||||
|
||||
TRANSPONDER = {
|
||||
this.TRANSPONDER = {
|
||||
supported: false,
|
||||
data: [],
|
||||
provider: 0,
|
||||
providers: [],
|
||||
};
|
||||
|
||||
RC_DEADBAND_CONFIG = {
|
||||
this.RC_DEADBAND_CONFIG = {
|
||||
deadband: 0,
|
||||
yaw_deadband: 0,
|
||||
alt_hold_deadband: 0,
|
||||
deadband3d_throttle: 0,
|
||||
};
|
||||
|
||||
SENSOR_ALIGNMENT = {
|
||||
this.SENSOR_ALIGNMENT = {
|
||||
align_gyro: 0,
|
||||
align_acc: 0,
|
||||
align_mag: 0,
|
||||
|
@ -369,7 +371,7 @@ var FC = {
|
|||
gyro_2_align: 0,
|
||||
};
|
||||
|
||||
PID_ADVANCED_CONFIG = {
|
||||
this.PID_ADVANCED_CONFIG = {
|
||||
gyro_sync_denom: 0,
|
||||
pid_process_denom: 0,
|
||||
use_unsyncedPwm: 0,
|
||||
|
@ -387,7 +389,7 @@ var FC = {
|
|||
debugModeCount: 0,
|
||||
};
|
||||
|
||||
FILTER_CONFIG = {
|
||||
this.FILTER_CONFIG = {
|
||||
gyro_hardware_lpf: 0,
|
||||
gyro_32khz_hardware_lpf: 0,
|
||||
gyro_lowpass_hz: 0,
|
||||
|
@ -419,7 +421,7 @@ var FC = {
|
|||
gyro_rpm_notch_min_hz: 0,
|
||||
};
|
||||
|
||||
ADVANCED_TUNING = {
|
||||
this.ADVANCED_TUNING = {
|
||||
rollPitchItermIgnoreRate: 0,
|
||||
yawItermIgnoreRate: 0,
|
||||
yaw_p_limit: 0,
|
||||
|
@ -464,15 +466,15 @@ var FC = {
|
|||
ff_boost: 0,
|
||||
vbat_sag_compensation: 0,
|
||||
};
|
||||
ADVANCED_TUNING_ACTIVE = { ...ADVANCED_TUNING };
|
||||
this.ADVANCED_TUNING_ACTIVE = { ...this.ADVANCED_TUNING };
|
||||
|
||||
SENSOR_CONFIG = {
|
||||
this.SENSOR_CONFIG = {
|
||||
acc_hardware: 0,
|
||||
baro_hardware: 0,
|
||||
mag_hardware: 0,
|
||||
};
|
||||
|
||||
RX_CONFIG = {
|
||||
this.RX_CONFIG = {
|
||||
serialrx_provider: 0,
|
||||
stick_max: 0,
|
||||
stick_center: 0,
|
||||
|
@ -490,14 +492,14 @@ var FC = {
|
|||
fpvCamAngleDegrees: 0,
|
||||
rcSmoothingType: 0,
|
||||
rcSmoothingInputCutoff: 0,
|
||||
rcSmoothingDerivativeCutoff: 0,
|
||||
rcSmoothingDerivativeCutoff: 0,
|
||||
rcSmoothingInputType: 0,
|
||||
rcSmoothingDerivativeType: 0,
|
||||
rcSmoothingAutoSmoothness: 0,
|
||||
usbCdcHidType: 0,
|
||||
};
|
||||
|
||||
FAILSAFE_CONFIG = {
|
||||
this.FAILSAFE_CONFIG = {
|
||||
failsafe_delay: 0,
|
||||
failsafe_off_delay: 0,
|
||||
failsafe_throttle: 0,
|
||||
|
@ -506,7 +508,7 @@ var FC = {
|
|||
failsafe_procedure: 0,
|
||||
};
|
||||
|
||||
GPS_RESCUE = {
|
||||
this.GPS_RESCUE = {
|
||||
angle: 0,
|
||||
initialAltitudeM: 0,
|
||||
descentDistanceM: 0,
|
||||
|
@ -522,9 +524,9 @@ var FC = {
|
|||
altitudeMode: 0,
|
||||
};
|
||||
|
||||
RXFAIL_CONFIG = [];
|
||||
this.RXFAIL_CONFIG = [];
|
||||
|
||||
VTX_CONFIG = {
|
||||
this.VTX_CONFIG = {
|
||||
vtx_type: 0,
|
||||
vtx_band: 0,
|
||||
vtx_channel: 0,
|
||||
|
@ -541,7 +543,7 @@ var FC = {
|
|||
vtx_table_clear: false,
|
||||
};
|
||||
|
||||
VTXTABLE_BAND = {
|
||||
this.VTXTABLE_BAND = {
|
||||
vtxtable_band_number: 0,
|
||||
vtxtable_band_name: '',
|
||||
vtxtable_band_letter: '',
|
||||
|
@ -549,23 +551,23 @@ var FC = {
|
|||
vtxtable_band_frequencies: [],
|
||||
};
|
||||
|
||||
VTXTABLE_POWERLEVEL = {
|
||||
this.VTXTABLE_POWERLEVEL = {
|
||||
vtxtable_powerlevel_number: 0,
|
||||
vtxtable_powerlevel_value: 0,
|
||||
vtxtable_powerlevel_label: 0,
|
||||
};
|
||||
|
||||
MULTIPLE_MSP = {
|
||||
this.MULTIPLE_MSP = {
|
||||
msp_commands: [],
|
||||
};
|
||||
|
||||
DEFAULT = {
|
||||
this.DEFAULT = {
|
||||
gyro_lowpass_hz: 100,
|
||||
gyro_lowpass_dyn_min_hz: 150,
|
||||
gyro_lowpass_dyn_max_hz: 450,
|
||||
gyro_lowpass_type: FC.FILTER_TYPE_FLAGS.PT1,
|
||||
gyro_lowpass_type: this.FILTER_TYPE_FLAGS.PT1,
|
||||
gyro_lowpass2_hz: 300,
|
||||
gyro_lowpass2_type: FC.FILTER_TYPE_FLAGS.PT1,
|
||||
gyro_lowpass2_type: this.FILTER_TYPE_FLAGS.PT1,
|
||||
gyro_notch_cutoff: 300,
|
||||
gyro_notch_hz: 400,
|
||||
gyro_notch2_cutoff: 100,
|
||||
|
@ -575,9 +577,9 @@ var FC = {
|
|||
dterm_lowpass_dyn_min_hz: 150,
|
||||
dterm_lowpass_dyn_max_hz: 250,
|
||||
dyn_lpf_curve_expo: 5,
|
||||
dterm_lowpass_type: FC.FILTER_TYPE_FLAGS.PT1,
|
||||
dterm_lowpass_type: this.FILTER_TYPE_FLAGS.PT1,
|
||||
dterm_lowpass2_hz: 150,
|
||||
dterm_lowpass2_type: FC.FILTER_TYPE_FLAGS.BIQUAD,
|
||||
dterm_lowpass2_type: this.FILTER_TYPE_FLAGS.BIQUAD,
|
||||
dterm_notch_cutoff: 160,
|
||||
dterm_notch_hz: 260,
|
||||
yaw_lowpass_hz: 100,
|
||||
|
@ -587,27 +589,27 @@ var FC = {
|
|||
dyn_notch_width_percent_rpm: 0,
|
||||
};
|
||||
|
||||
DEFAULT_PIDS = [
|
||||
this.DEFAULT_PIDS = [
|
||||
42, 85, 35, 20, 90,
|
||||
46, 90, 38, 22, 95,
|
||||
30, 90, 0, 0, 90,
|
||||
];
|
||||
},
|
||||
|
||||
getHardwareName: function () {
|
||||
getHardwareName() {
|
||||
let name;
|
||||
if (CONFIG.targetName) {
|
||||
name = CONFIG.targetName;
|
||||
if (this.CONFIG.targetName) {
|
||||
name = this.CONFIG.targetName;
|
||||
} else {
|
||||
name = CONFIG.boardIdentifier;
|
||||
name = this.CONFIG.boardIdentifier;
|
||||
}
|
||||
|
||||
if (CONFIG.boardName && CONFIG.boardName !== name) {
|
||||
name = CONFIG.boardName + "(" + name + ")";
|
||||
if (this.CONFIG.boardName && this.CONFIG.boardName !== name) {
|
||||
name = `${this.CONFIG.boardName}(${name})`;
|
||||
}
|
||||
|
||||
if (CONFIG.manufacturerId) {
|
||||
name = CONFIG.manufacturerId + "/" + name;
|
||||
if (this.CONFIG.manufacturerId) {
|
||||
name = `${this.CONFIG.manufacturerId}/${name}`;
|
||||
}
|
||||
|
||||
return name;
|
||||
|
@ -627,8 +629,8 @@ var FC = {
|
|||
255: "Unknown MCU",
|
||||
},
|
||||
|
||||
getMcuType: function () {
|
||||
return FC.MCU_TYPES[CONFIG.mcuTypeId];
|
||||
getMcuType() {
|
||||
return this.MCU_TYPES[this.CONFIG.mcuTypeId];
|
||||
},
|
||||
|
||||
CONFIGURATION_STATES: {
|
||||
|
@ -652,12 +654,12 @@ var FC = {
|
|||
MOTOR_PROTOCOL_DISABLED: 1,
|
||||
},
|
||||
|
||||
boardHasVcp: function () {
|
||||
var hasVcp = false;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
hasVcp = bit_check(CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.HAS_VCP);
|
||||
boardHasVcp() {
|
||||
let hasVcp = false;
|
||||
if (semver.gte(this.CONFIG.apiVersion, "1.37.0")) {
|
||||
hasVcp = bit_check(this.CONFIG.targetCapabilities, this.TARGET_CAPABILITIES_FLAGS.HAS_VCP);
|
||||
} else {
|
||||
hasVcp = BOARD.find_board_definition(CONFIG.boardIdentifier).vcp;
|
||||
hasVcp = BOARD.find_board_definition(this.CONFIG.boardIdentifier).vcp;
|
||||
}
|
||||
|
||||
return hasVcp;
|
||||
|
@ -668,42 +670,42 @@ var FC = {
|
|||
BIQUAD: 1,
|
||||
},
|
||||
|
||||
getFilterDefaults: function() {
|
||||
var versionFilterDefaults = DEFAULT;
|
||||
getFilterDefaults() {
|
||||
const versionFilterDefaults = this.DEFAULT;
|
||||
|
||||
if (semver.eq(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.eq(this.CONFIG.apiVersion, "1.40.0")) {
|
||||
versionFilterDefaults.dterm_lowpass2_hz = 200;
|
||||
} else if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
} else if (semver.gte(this.CONFIG.apiVersion, "1.41.0")) {
|
||||
versionFilterDefaults.gyro_lowpass_hz = 150;
|
||||
versionFilterDefaults.gyro_lowpass_type = FC.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
versionFilterDefaults.gyro_lowpass_type = this.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
versionFilterDefaults.gyro_lowpass2_hz = 0;
|
||||
versionFilterDefaults.gyro_lowpass2_type = FC.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
versionFilterDefaults.gyro_lowpass2_type = this.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
versionFilterDefaults.dterm_lowpass_hz = 150;
|
||||
versionFilterDefaults.dterm_lowpass_type = FC.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
versionFilterDefaults.dterm_lowpass_type = this.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
versionFilterDefaults.dterm_lowpass2_hz = 150;
|
||||
versionFilterDefaults.dterm_lowpass2_type = FC.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
versionFilterDefaults.dterm_lowpass2_type = this.FILTER_TYPE_FLAGS.BIQUAD;
|
||||
if (semver.gte(this.CONFIG.apiVersion, "1.42.0")) {
|
||||
versionFilterDefaults.gyro_lowpass_hz = 200;
|
||||
versionFilterDefaults.gyro_lowpass_dyn_min_hz = 200;
|
||||
versionFilterDefaults.gyro_lowpass_dyn_max_hz = 500;
|
||||
versionFilterDefaults.gyro_lowpass_type = FC.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.gyro_lowpass_type = this.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.gyro_lowpass2_hz = 250;
|
||||
versionFilterDefaults.gyro_lowpass2_type = FC.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.gyro_lowpass2_type = this.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.dterm_lowpass_hz = 150;
|
||||
versionFilterDefaults.dterm_lowpass_dyn_min_hz = 70;
|
||||
versionFilterDefaults.dterm_lowpass_dyn_max_hz = 170;
|
||||
versionFilterDefaults.dterm_lowpass_type = FC.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.dterm_lowpass_type = this.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.dterm_lowpass2_hz = 150;
|
||||
versionFilterDefaults.dterm_lowpass2_type = FC.FILTER_TYPE_FLAGS.PT1;
|
||||
versionFilterDefaults.dterm_lowpass2_type = this.FILTER_TYPE_FLAGS.PT1;
|
||||
}
|
||||
}
|
||||
}
|
||||
return versionFilterDefaults;
|
||||
},
|
||||
|
||||
getPidDefaults: function() {
|
||||
var versionPidDefaults = DEFAULT_PIDS;
|
||||
getPidDefaults() {
|
||||
let versionPidDefaults = this.DEFAULT_PIDS;
|
||||
// if defaults change they should go here
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(this.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
versionPidDefaults = [
|
||||
42, 85, 35, 23, 90,
|
||||
46, 90, 38, 25, 95,
|
||||
|
|
|
@ -126,8 +126,8 @@ function closeSerial() {
|
|||
checksum = bufView[3] ^ bufView[4];
|
||||
|
||||
for (let i = 0; i < 16; i += 2) {
|
||||
bufView[i + 5] = MOTOR_CONFIG.mincommand & 0x00FF;
|
||||
bufView[i + 6] = MOTOR_CONFIG.mincommand >> 8;
|
||||
bufView[i + 5] = FC.MOTOR_CONFIG.mincommand & 0x00FF;
|
||||
bufView[i + 6] = FC.MOTOR_CONFIG.mincommand >> 8;
|
||||
|
||||
checksum ^= bufView[i + 5];
|
||||
checksum ^= bufView[i + 6];
|
||||
|
@ -483,8 +483,8 @@ function startProcess() {
|
|||
analyticsService.setDimension(analyticsService.DIMENSIONS.CONFIGURATOR_EXPERT_MODE, checked ? 'On' : 'Off');
|
||||
});
|
||||
|
||||
if (FEATURE_CONFIG && FEATURE_CONFIG.features !== 0) {
|
||||
updateTabList(FEATURE_CONFIG.features);
|
||||
if (FC.FEATURE_CONFIG && FC.FEATURE_CONFIG.features !== 0) {
|
||||
updateTabList(FC.FEATURE_CONFIG.features);
|
||||
}
|
||||
}).change();
|
||||
});
|
||||
|
@ -648,13 +648,13 @@ function updateTabList(features) {
|
|||
$('#tabs ul.mode-connected li.tab_osd').hide();
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
$('#tabs ul.mode-connected li.tab_power').show();
|
||||
} else {
|
||||
$('#tabs ul.mode-connected li.tab_power').hide();
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
$('#tabs ul.mode-connected li.tab_vtx').show();
|
||||
} else {
|
||||
$('#tabs ul.mode-connected li.tab_vtx').hide();
|
||||
|
@ -677,12 +677,12 @@ function generateFilename(prefix, suffix) {
|
|||
const date = new Date();
|
||||
let filename = prefix;
|
||||
|
||||
if (CONFIG) {
|
||||
if (CONFIG.flightControllerIdentifier) {
|
||||
filename = `${CONFIG.flightControllerIdentifier}_${filename}`;
|
||||
if (FC.CONFIG) {
|
||||
if (FC.CONFIG.flightControllerIdentifier) {
|
||||
filename = `${FC.CONFIG.flightControllerIdentifier}_${filename}`;
|
||||
}
|
||||
if(CONFIG.name && CONFIG.name.trim() !== '') {
|
||||
filename = `${filename}_${CONFIG.name.trim().replace(' ', '_')}`;
|
||||
if(FC.CONFIG.name && FC.CONFIG.name.trim() !== '') {
|
||||
filename = `${filename}_${FC.CONFIG.name.trim().replace(' ', '_')}`;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -47,7 +47,7 @@ var Model = function (wrapper, canvas) {
|
|||
this.renderer.setSize(this.wrapper.width() * 2, this.wrapper.height() * 2);
|
||||
|
||||
// load the model including materials
|
||||
var model_file = useWebGLRenderer ? mixerList[MIXER_CONFIG.mixer - 1].model : 'fallback';
|
||||
var model_file = useWebGLRenderer ? mixerList[FC.MIXER_CONFIG.mixer - 1].model : 'fallback';
|
||||
|
||||
// Temporary workaround for 'custom' model until akfreak's custom model is merged.
|
||||
if (model_file == 'custom') { model_file = 'fallback'; }
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -2,8 +2,8 @@
|
|||
|
||||
// return true if user has choose a special peripheral
|
||||
function isPeripheralSelected(peripheralName) {
|
||||
for (var portIndex = 0; portIndex < SERIAL_CONFIG.ports.length; portIndex++) {
|
||||
var serialPort = SERIAL_CONFIG.ports[portIndex];
|
||||
for (var portIndex = 0; portIndex < FC.SERIAL_CONFIG.ports.length; portIndex++) {
|
||||
var serialPort = FC.SERIAL_CONFIG.ports[portIndex];
|
||||
if (serialPort.functions.indexOf(peripheralName) >= 0) {
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -139,9 +139,9 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
|||
|
||||
var onConnectHandler = function () {
|
||||
|
||||
GUI.log(i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
||||
GUI.log(i18n.getMessage('apiVersionReceived', [FC.CONFIG.apiVersion]));
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
|
||||
self.msp_connector.disconnect(function (disconnectionResult) {
|
||||
|
||||
|
@ -153,7 +153,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
|||
|
||||
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, function () {
|
||||
var rebootMode = 0; // FIRMWARE
|
||||
if (bit_check(CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.HAS_FLASH_BOOTLOADER)) {
|
||||
if (bit_check(FC.CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.HAS_FLASH_BOOTLOADER)) {
|
||||
// Board has flash bootloader
|
||||
GUI.log(i18n.getMessage('deviceRebooting_flashBootloader'));
|
||||
console.log('flash bootloader detected');
|
||||
|
|
|
@ -122,8 +122,8 @@ var serial = {
|
|||
case 'device_lost':
|
||||
default:
|
||||
console.log("serial disconnecting: " + info.error);
|
||||
CONFIG.armingDisabled = false;
|
||||
CONFIG.runawayTakeoffPreventionDisabled = false;
|
||||
FC.CONFIG.armingDisabled = false;
|
||||
FC.CONFIG.runawayTakeoffPreventionDisabled = false;
|
||||
|
||||
if (GUI.connected_to || GUI.connecting_to) {
|
||||
$('a.connect').click();
|
||||
|
|
|
@ -178,7 +178,7 @@ function finishClose(finishedCallback) {
|
|||
// Reset various UI elements
|
||||
$('span.i2c-error').text(0);
|
||||
$('span.cycle-time').text(0);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0"))
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0"))
|
||||
$('span.cpu-load').text('');
|
||||
|
||||
// unlock port select & baud
|
||||
|
@ -247,31 +247,31 @@ function onOpen(openInfo) {
|
|||
|
||||
// request configuration data
|
||||
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
|
||||
analytics.setFlightControllerData(analytics.DATA.API_VERSION, CONFIG.apiVersion);
|
||||
analytics.setFlightControllerData(analytics.DATA.API_VERSION, FC.CONFIG.apiVersion);
|
||||
|
||||
GUI.log(i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
||||
GUI.log(i18n.getMessage('apiVersionReceived', [FC.CONFIG.apiVersion]));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_ACCEPTED)) {
|
||||
if (semver.gte(FC.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') {
|
||||
analytics.setFlightControllerData(analytics.DATA.FIRMWARE_TYPE, FC.CONFIG.flightControllerIdentifier);
|
||||
if (FC.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, FC.CONFIG.flightControllerVersion);
|
||||
|
||||
GUI.log(i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
|
||||
updateStatusBarVersion(CONFIG.flightControllerVersion, CONFIG.flightControllerIdentifier);
|
||||
updateTopBarVersion(CONFIG.flightControllerVersion, CONFIG.flightControllerIdentifier);
|
||||
GUI.log(i18n.getMessage('fcInfoReceived', [FC.CONFIG.flightControllerIdentifier, FC.CONFIG.flightControllerVersion]));
|
||||
updateStatusBarVersion(FC.CONFIG.flightControllerVersion, FC.CONFIG.flightControllerIdentifier);
|
||||
updateTopBarVersion(FC.CONFIG.flightControllerVersion, FC.CONFIG.flightControllerIdentifier);
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_BUILD_INFO, false, false, function () {
|
||||
|
||||
GUI.log(i18n.getMessage('buildInfoReceived', [CONFIG.buildInfo]));
|
||||
GUI.log(i18n.getMessage('buildInfoReceived', [FC.CONFIG.buildInfo]));
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, processBoardInfo);
|
||||
});
|
||||
});
|
||||
} else {
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'ConnectionRefusedFirmwareType', CONFIG.flightControllerIdentifier);
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'ConnectionRefusedFirmwareType', FC.CONFIG.flightControllerIdentifier);
|
||||
|
||||
var dialog = $('.dialogConnectWarning')[0];
|
||||
|
||||
|
@ -287,7 +287,7 @@ function onOpen(openInfo) {
|
|||
}
|
||||
});
|
||||
} else {
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'ConnectionRefusedFirmwareVersion', CONFIG.apiVersion);
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'ConnectionRefusedFirmwareVersion', FC.CONFIG.apiVersion);
|
||||
|
||||
var dialog = $('.dialogConnectWarning')[0];
|
||||
|
||||
|
@ -324,17 +324,17 @@ function abortConnect() {
|
|||
}
|
||||
|
||||
function processBoardInfo() {
|
||||
analytics.setFlightControllerData(analytics.DATA.BOARD_TYPE, CONFIG.boardIdentifier);
|
||||
analytics.setFlightControllerData(analytics.DATA.TARGET_NAME, CONFIG.targetName);
|
||||
analytics.setFlightControllerData(analytics.DATA.BOARD_NAME, CONFIG.boardName);
|
||||
analytics.setFlightControllerData(analytics.DATA.MANUFACTURER_ID, CONFIG.manufacturerId);
|
||||
analytics.setFlightControllerData(analytics.DATA.BOARD_TYPE, FC.CONFIG.boardIdentifier);
|
||||
analytics.setFlightControllerData(analytics.DATA.TARGET_NAME, FC.CONFIG.targetName);
|
||||
analytics.setFlightControllerData(analytics.DATA.BOARD_NAME, FC.CONFIG.boardName);
|
||||
analytics.setFlightControllerData(analytics.DATA.MANUFACTURER_ID, FC.CONFIG.manufacturerId);
|
||||
analytics.setFlightControllerData(analytics.DATA.MCU_TYPE, FC.getMcuType());
|
||||
|
||||
GUI.log(i18n.getMessage('boardInfoReceived', [FC.getHardwareName(), CONFIG.boardVersion]));
|
||||
updateStatusBarVersion(CONFIG.flightControllerVersion, CONFIG.flightControllerIdentifier, FC.getHardwareName());
|
||||
updateTopBarVersion(CONFIG.flightControllerVersion, CONFIG.flightControllerIdentifier, FC.getHardwareName());
|
||||
GUI.log(i18n.getMessage('boardInfoReceived', [FC.getHardwareName(), FC.CONFIG.boardVersion]));
|
||||
updateStatusBarVersion(FC.CONFIG.flightControllerVersion, FC.CONFIG.flightControllerIdentifier, FC.getHardwareName());
|
||||
updateTopBarVersion(FC.CONFIG.flightControllerVersion, FC.CONFIG.flightControllerIdentifier, FC.getHardwareName());
|
||||
|
||||
if (bit_check(CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.SUPPORTS_CUSTOM_DEFAULTS) && bit_check(CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.HAS_CUSTOM_DEFAULTS) && CONFIG.configurationState === FC.CONFIGURATION_STATES.DEFAULTS_BARE) {
|
||||
if (bit_check(FC.CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.SUPPORTS_CUSTOM_DEFAULTS) && bit_check(FC.CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.HAS_CUSTOM_DEFAULTS) && FC.CONFIG.configurationState === FC.CONFIGURATION_STATES.DEFAULTS_BARE) {
|
||||
var dialog = $('#dialogResetToCustomDefaults')[0];
|
||||
|
||||
$('#dialogResetToCustomDefaults-acceptbtn').click(function() {
|
||||
|
@ -374,7 +374,7 @@ function checkReportProblems() {
|
|||
const problemItemTemplate = $('#dialogReportProblems-listItemTemplate');
|
||||
|
||||
function checkReportProblem(problemName, problemDialogList) {
|
||||
if (bit_check(CONFIG.configurationProblems, FC.CONFIGURATION_PROBLEM_FLAGS[problemName])) {
|
||||
if (bit_check(FC.CONFIG.configurationProblems, FC.CONFIGURATION_PROBLEM_FLAGS[problemName])) {
|
||||
problemItemTemplate.clone().html(i18n.getMessage(`reportProblemsDialog${problemName}`)).appendTo(problemDialogList);
|
||||
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, PROBLEM_ANALYTICS_EVENT, problemName);
|
||||
|
@ -390,19 +390,19 @@ function checkReportProblems() {
|
|||
const problemDialogList = $('#dialogReportProblems-list');
|
||||
problemDialogList.empty();
|
||||
|
||||
if (semver.gt(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MAX_SUPPORTED)) {
|
||||
if (semver.gt(FC.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);
|
||||
[CONFIGURATOR.latestVersion, CONFIGURATOR.latestVersionReleaseUrl, CONFIGURATOR.version, FC.CONFIG.flightControllerVersion])).appendTo(problemDialogList);
|
||||
needsProblemReportingDialog = true;
|
||||
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, PROBLEM_ANALYTICS_EVENT,
|
||||
`${problemName};${CONFIGURATOR.API_VERSION_MAX_SUPPORTED};${CONFIG.apiVersion}`);
|
||||
`${problemName};${CONFIGURATOR.API_VERSION_MAX_SUPPORTED};${FC.CONFIG.apiVersion}`);
|
||||
}
|
||||
|
||||
needsProblemReportingDialog = checkReportProblem('MOTOR_PROTOCOL_DISABLED', problemDialogList) || needsProblemReportingDialog;
|
||||
|
||||
if (have_sensor(CONFIG.activeSensors, 'acc')) {
|
||||
if (have_sensor(FC.CONFIG.activeSensors, 'acc')) {
|
||||
needsProblemReportingDialog = checkReportProblem('ACC_NEEDS_CALIBRATION', problemDialogList) || needsProblemReportingDialog;
|
||||
}
|
||||
|
||||
|
@ -422,14 +422,14 @@ function checkReportProblems() {
|
|||
|
||||
function processUid() {
|
||||
MSP.send_message(MSPCodes.MSP_UID, false, false, function () {
|
||||
var uniqueDeviceIdentifier = CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16);
|
||||
var uniqueDeviceIdentifier = FC.CONFIG.uid[0].toString(16) + FC.CONFIG.uid[1].toString(16) + FC.CONFIG.uid[2].toString(16);
|
||||
|
||||
analytics.setFlightControllerData(analytics.DATA.MCU_ID, objectHash.sha1(uniqueDeviceIdentifier));
|
||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'Connected');
|
||||
connectionTimestamp = Date.now();
|
||||
GUI.log(i18n.getMessage('uniqueDeviceIdReceived', [uniqueDeviceIdentifier]));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
processName();
|
||||
} else {
|
||||
setRtc();
|
||||
|
@ -439,15 +439,15 @@ function processUid() {
|
|||
|
||||
function processName() {
|
||||
MSP.send_message(MSPCodes.MSP_NAME, false, false, function () {
|
||||
GUI.log(i18n.getMessage('craftNameReceived', [CONFIG.name]));
|
||||
GUI.log(i18n.getMessage('craftNameReceived', [FC.CONFIG.name]));
|
||||
|
||||
CONFIG.armingDisabled = false;
|
||||
FC.CONFIG.armingDisabled = false;
|
||||
mspHelper.setArmingEnabled(false, false, setRtc);
|
||||
});
|
||||
}
|
||||
|
||||
function setRtc() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_RTC, mspHelper.crunch(MSPCodes.MSP_SET_RTC), false, finishOpen);
|
||||
} else {
|
||||
finishOpen();
|
||||
|
@ -457,7 +457,7 @@ function setRtc() {
|
|||
function finishOpen() {
|
||||
CONFIGURATOR.connectionValid = true;
|
||||
GUI.allowedTabs = GUI.defaultAllowedFCTabsWhenConnected.slice();
|
||||
if (semver.lt(CONFIG.apiVersion, "1.4.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.4.0")) {
|
||||
GUI.allowedTabs.splice(GUI.allowedTabs.indexOf('led_strip'), 1);
|
||||
}
|
||||
|
||||
|
@ -502,7 +502,7 @@ function onConnect() {
|
|||
}
|
||||
});
|
||||
|
||||
if (CONFIG.boardType == 0) {
|
||||
if (FC.CONFIG.boardType == 0) {
|
||||
if (classes.indexOf("osd-required") >= 0) {
|
||||
found = false;
|
||||
}
|
||||
|
@ -511,21 +511,21 @@ function onConnect() {
|
|||
return found;
|
||||
}).show();
|
||||
|
||||
if (CONFIG.flightControllerVersion !== '') {
|
||||
FEATURE_CONFIG.features = new Features(CONFIG);
|
||||
BEEPER_CONFIG.beepers = new Beepers(CONFIG);
|
||||
BEEPER_CONFIG.dshotBeaconConditions = new Beepers(CONFIG, [ "RX_LOST", "RX_SET" ]);
|
||||
if (FC.CONFIG.flightControllerVersion !== '') {
|
||||
FC.FEATURE_CONFIG.features = new Features(FC.CONFIG);
|
||||
FC.BEEPER_CONFIG.beepers = new Beepers(FC.CONFIG);
|
||||
FC.BEEPER_CONFIG.dshotBeaconConditions = new Beepers(FC.CONFIG, [ "RX_LOST", "RX_SET" ]);
|
||||
|
||||
$('#tabs ul.mode-connected').show();
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_BATTERY_CONFIG, false, false);
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false);
|
||||
|
||||
if (CONFIG.boardType == 0 || CONFIG.boardType == 2) {
|
||||
if (FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2) {
|
||||
startLiveDataRefreshTimer();
|
||||
}
|
||||
}
|
||||
|
@ -606,7 +606,7 @@ function sensor_status(sensors_detected) {
|
|||
$('.accicon', e_sensor_status).removeClass('active');
|
||||
}
|
||||
|
||||
if ((CONFIG.boardType == 0 || CONFIG.boardType == 2) && have_sensor(sensors_detected, 'gyro')) {
|
||||
if ((FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2) && have_sensor(sensors_detected, 'gyro')) {
|
||||
$('.gyro', e_sensor_status).addClass('on');
|
||||
$('.gyroicon', e_sensor_status).addClass('active');
|
||||
} else {
|
||||
|
@ -660,7 +660,7 @@ function have_sensor(sensors_detected, sensor_code) {
|
|||
case 'sonar':
|
||||
return bit_check(sensors_detected, 4);
|
||||
case 'gyro':
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
return bit_check(sensors_detected, 5);
|
||||
} else {
|
||||
return true;
|
||||
|
@ -684,7 +684,7 @@ function update_live_status() {
|
|||
|
||||
if (GUI.active_tab != 'cli') {
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.32.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.32.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
} else {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
||||
|
@ -692,55 +692,55 @@ function update_live_status() {
|
|||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false);
|
||||
}
|
||||
|
||||
var active = ((Date.now() - ANALOG.last_received_timestamp) < 300);
|
||||
var active = ((Date.now() - FC.ANALOG.last_received_timestamp) < 300);
|
||||
|
||||
for (var i = 0; i < AUX_CONFIG.length; i++) {
|
||||
if (AUX_CONFIG[i] == 'ARM') {
|
||||
if (bit_check(CONFIG.mode, i))
|
||||
for (var i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
if (FC.AUX_CONFIG[i] == 'ARM') {
|
||||
if (bit_check(FC.CONFIG.mode, i))
|
||||
$(".armedicon").addClass('active');
|
||||
else
|
||||
$(".armedicon").removeClass('active');
|
||||
}
|
||||
if (AUX_CONFIG[i] == 'FAILSAFE') {
|
||||
if (bit_check(CONFIG.mode, i))
|
||||
if (FC.AUX_CONFIG[i] == 'FAILSAFE') {
|
||||
if (bit_check(FC.CONFIG.mode, i))
|
||||
$(".failsafeicon").addClass('active');
|
||||
else
|
||||
$(".failsafeicon").removeClass('active');
|
||||
}
|
||||
}
|
||||
|
||||
if (ANALOG != undefined) {
|
||||
var nbCells = Math.floor(ANALOG.voltage / BATTERY_CONFIG.vbatmaxcellvoltage) + 1;
|
||||
if (FC.ANALOG != undefined) {
|
||||
var nbCells = Math.floor(FC.ANALOG.voltage / FC.BATTERY_CONFIG.vbatmaxcellvoltage) + 1;
|
||||
|
||||
if (ANALOG.voltage == 0) {
|
||||
if (FC.ANALOG.voltage == 0) {
|
||||
nbCells = 1;
|
||||
}
|
||||
|
||||
var min = BATTERY_CONFIG.vbatmincellvoltage * nbCells;
|
||||
var max = BATTERY_CONFIG.vbatmaxcellvoltage * nbCells;
|
||||
var warn = BATTERY_CONFIG.vbatwarningcellvoltage * nbCells;
|
||||
var min = FC.BATTERY_CONFIG.vbatmincellvoltage * nbCells;
|
||||
var max = FC.BATTERY_CONFIG.vbatmaxcellvoltage * nbCells;
|
||||
var warn = FC.BATTERY_CONFIG.vbatwarningcellvoltage * nbCells;
|
||||
|
||||
const NO_BATTERY_VOLTAGE_MAXIMUM = 1.8; // Maybe is better to add a call to MSP_BATTERY_STATE but is not available for all versions
|
||||
|
||||
if (ANALOG.voltage < min && ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM) {
|
||||
if (FC.ANALOG.voltage < min && FC.ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM) {
|
||||
$(".battery-status").addClass('state-empty').removeClass('state-ok').removeClass('state-warning');
|
||||
$(".battery-status").css({
|
||||
width: "100%",
|
||||
});
|
||||
} else {
|
||||
$(".battery-status").css({
|
||||
width: ((ANALOG.voltage - min) / (max - min) * 100) + "%",
|
||||
width: ((FC.ANALOG.voltage - min) / (max - min) * 100) + "%",
|
||||
});
|
||||
|
||||
if (ANALOG.voltage < warn) {
|
||||
if (FC.ANALOG.voltage < warn) {
|
||||
$(".battery-status").addClass('state-warning').removeClass('state-empty').removeClass('state-ok');
|
||||
} else {
|
||||
$(".battery-status").addClass('state-ok').removeClass('state-warning').removeClass('state-empty');
|
||||
}
|
||||
}
|
||||
|
||||
let cellsText = (ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM)? nbCells + 'S' : 'USB';
|
||||
$(".battery-legend").text(ANALOG.voltage.toFixed(2) + "V (" + cellsText + ")");
|
||||
let cellsText = (FC.ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM)? nbCells + 'S' : 'USB';
|
||||
$(".battery-legend").text(FC.ANALOG.voltage.toFixed(2) + "V (" + cellsText + ")");
|
||||
|
||||
}
|
||||
|
||||
|
@ -787,7 +787,7 @@ function update_dataflash_global() {
|
|||
return megabytes.toFixed(1) + "MB";
|
||||
}
|
||||
|
||||
var supportsDataflash = DATAFLASH.totalSize > 0;
|
||||
var supportsDataflash = FC.DATAFLASH.totalSize > 0;
|
||||
|
||||
if (supportsDataflash){
|
||||
$(".noflash_global").css({
|
||||
|
@ -799,10 +799,10 @@ function update_dataflash_global() {
|
|||
});
|
||||
|
||||
$(".dataflash-free_global").css({
|
||||
width: (100-(DATAFLASH.totalSize - DATAFLASH.usedSize) / DATAFLASH.totalSize * 100) + "%",
|
||||
width: (100-(FC.DATAFLASH.totalSize - FC.DATAFLASH.usedSize) / FC.DATAFLASH.totalSize * 100) + "%",
|
||||
display: 'block'
|
||||
});
|
||||
$(".dataflash-free_global div").text('Dataflash: free ' + formatFilesize(DATAFLASH.totalSize - DATAFLASH.usedSize));
|
||||
$(".dataflash-free_global div").text('Dataflash: free ' + formatFilesize(FC.DATAFLASH.totalSize - FC.DATAFLASH.usedSize));
|
||||
} else {
|
||||
$(".noflash_global").css({
|
||||
display: 'block'
|
||||
|
|
|
@ -37,7 +37,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
// update selected slot
|
||||
//
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
var adjustmentList = $(newAdjustment).find('.adjustmentSlot .slot');
|
||||
adjustmentList.val(adjustmentRange.slotIndex);
|
||||
}
|
||||
|
@ -156,16 +156,16 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
self.adjust_template();
|
||||
|
||||
var auxChannelCount = RC.active_channels - 4;
|
||||
var auxChannelCount = FC.RC.active_channels - 4;
|
||||
|
||||
var modeTableBodyElement = $('.tab-adjustments .adjustments tbody');
|
||||
for (var adjustmentIndex = 0; adjustmentIndex < ADJUSTMENT_RANGES.length; adjustmentIndex++) {
|
||||
var newAdjustment = addAdjustment(adjustmentIndex, ADJUSTMENT_RANGES[adjustmentIndex], auxChannelCount);
|
||||
for (var adjustmentIndex = 0; adjustmentIndex < FC.ADJUSTMENT_RANGES.length; adjustmentIndex++) {
|
||||
var newAdjustment = addAdjustment(adjustmentIndex, FC.ADJUSTMENT_RANGES[adjustmentIndex], auxChannelCount);
|
||||
modeTableBodyElement.append(newAdjustment);
|
||||
}
|
||||
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
$('.tab-adjustments .adjustmentSlotsHelp').hide();
|
||||
$('.tab-adjustments .adjustmentSlotHeader').hide();
|
||||
$('.tab-adjustments .adjustmentSlot').hide();
|
||||
|
@ -178,9 +178,9 @@ TABS.adjustments.initialize = function (callback) {
|
|||
$('a.save').click(function () {
|
||||
|
||||
// update internal data structures based on current UI elements
|
||||
var requiredAdjustmentRangeCount = ADJUSTMENT_RANGES.length;
|
||||
var requiredAdjustmentRangeCount = FC.ADJUSTMENT_RANGES.length;
|
||||
|
||||
ADJUSTMENT_RANGES = [];
|
||||
FC.ADJUSTMENT_RANGES = [];
|
||||
|
||||
var defaultAdjustmentRange = {
|
||||
slotIndex: 0,
|
||||
|
@ -199,7 +199,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
if ($(adjustmentElement).find('.enable').prop("checked")) {
|
||||
var rangeValues = $(this).find('.range .channel-slider').val();
|
||||
var slotIndex = 0;
|
||||
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
slotIndex = parseInt($(this).find('.adjustmentSlot .slot').val());
|
||||
}
|
||||
|
||||
|
@ -213,14 +213,14 @@ TABS.adjustments.initialize = function (callback) {
|
|||
adjustmentFunction: parseInt($(this).find('.functionSelection .function').val()),
|
||||
auxSwitchChannelIndex: parseInt($(this).find('.functionSwitchChannel .channel').val())
|
||||
};
|
||||
ADJUSTMENT_RANGES.push(adjustmentRange);
|
||||
FC.ADJUSTMENT_RANGES.push(adjustmentRange);
|
||||
} else {
|
||||
ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
|
||||
FC.ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
|
||||
}
|
||||
});
|
||||
|
||||
for (var adjustmentRangeIndex = ADJUSTMENT_RANGES.length; adjustmentRangeIndex < requiredAdjustmentRangeCount; adjustmentRangeIndex++) {
|
||||
ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
|
||||
for (var adjustmentRangeIndex = FC.ADJUSTMENT_RANGES.length; adjustmentRangeIndex < requiredAdjustmentRangeCount; adjustmentRangeIndex++) {
|
||||
FC.ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
|
||||
}
|
||||
|
||||
//
|
||||
|
@ -260,10 +260,10 @@ TABS.adjustments.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function update_ui() {
|
||||
var auxChannelCount = RC.active_channels - 4;
|
||||
var auxChannelCount = FC.RC.active_channels - 4;
|
||||
|
||||
for (var auxChannelIndex = 0; auxChannelIndex < auxChannelCount; auxChannelIndex++) {
|
||||
update_marker(auxChannelIndex, RC.channels[auxChannelIndex + 4]);
|
||||
update_marker(auxChannelIndex, FC.RC.channels[auxChannelIndex + 4]);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -291,13 +291,13 @@ TABS.adjustments.adjust_template = function () {
|
|||
var selectFunction = $('#functionSelectionSelect');
|
||||
var elementsNumber;
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
elementsNumber = 31; // OSD Profile Select & LED Profile Select
|
||||
} else if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
} else if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
elementsNumber = 29; // PID Audio
|
||||
} else if (semver.gte(CONFIG.apiVersion, "1.39.0")) {
|
||||
} else if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
elementsNumber = 26; // PID Audio
|
||||
} else if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
} else if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
elementsNumber = 25; // Horizon Strength
|
||||
} else {
|
||||
elementsNumber = 24; // Setpoint transition
|
||||
|
@ -308,7 +308,7 @@ TABS.adjustments.adjust_template = function () {
|
|||
}
|
||||
|
||||
// For 1.40, the D Setpoint has been replaced, so we replace it with the correct values
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
|
||||
var element22 = selectFunction.find("option[value='22']");
|
||||
var element23 = selectFunction.find("option[value='23']");
|
||||
|
|
|
@ -9,7 +9,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
|
||||
function get_mode_ranges() {
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false,
|
||||
semver.gte(CONFIG.apiVersion, "1.41.0") ? get_mode_ranges_extra : get_box_ids);
|
||||
semver.gte(FC.CONFIG.apiVersion, "1.41.0") ? get_mode_ranges_extra : get_box_ids);
|
||||
}
|
||||
|
||||
function get_mode_ranges_extra() {
|
||||
|
@ -42,7 +42,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
var modeTemplate = $('#tab-auxiliary-templates .mode');
|
||||
var newMode = modeTemplate.clone();
|
||||
|
||||
var modeName = AUX_CONFIG[modeIndex];
|
||||
var modeName = FC.AUX_CONFIG[modeIndex];
|
||||
// Adjust the name of the box if a peripheral is selected
|
||||
modeName = adjustBoxNameIfPeripheralWithModeID(modeId, modeName);
|
||||
|
||||
|
@ -57,7 +57,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
$(newMode).find('a.addLink').data('modeElement', newMode);
|
||||
|
||||
// hide link button for ARM
|
||||
if (modeId == 0 || semver.lt(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (modeId == 0 || semver.lt(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
$(newMode).find('.addLink').hide();
|
||||
}
|
||||
|
||||
|
@ -75,7 +75,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
logicOption.val(0);
|
||||
logicList.append(logicOption);
|
||||
|
||||
if(semver.gte(CONFIG.apiVersion, "1.41.0")){
|
||||
if(semver.gte(FC.CONFIG.apiVersion, "1.41.0")){
|
||||
var logicOption = logicOptionTemplate.clone();
|
||||
logicOption.text(i18n.getMessage('auxiliaryModeLogicAND'));
|
||||
logicOption.val(1);
|
||||
|
@ -122,10 +122,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
linkOption.val(0);
|
||||
linkList.append(linkOption);
|
||||
|
||||
for (var index = 1; index < AUX_CONFIG.length; index++) {
|
||||
for (var index = 1; index < FC.AUX_CONFIG.length; index++) {
|
||||
var linkOption = linkOptionTemplate.clone();
|
||||
linkOption.text(AUX_CONFIG[index]);
|
||||
linkOption.val(AUX_CONFIG_IDS[index]); // set value to mode id
|
||||
linkOption.text(FC.AUX_CONFIG[index]);
|
||||
linkOption.val(FC.AUX_CONFIG_IDS[index]); // set value to mode id
|
||||
linkList.append(linkOption);
|
||||
}
|
||||
|
||||
|
@ -249,30 +249,30 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function process_html() {
|
||||
var auxChannelCount = RC.active_channels - 4;
|
||||
var auxChannelCount = FC.RC.active_channels - 4;
|
||||
|
||||
configureRangeTemplate(auxChannelCount);
|
||||
configureLinkTemplate();
|
||||
|
||||
const modeTableBodyElement = $('.tab-auxiliary .modes');
|
||||
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
||||
for (var modeIndex = 0; modeIndex < FC.AUX_CONFIG.length; modeIndex++) {
|
||||
|
||||
var modeId = AUX_CONFIG_IDS[modeIndex];
|
||||
var modeId = FC.AUX_CONFIG_IDS[modeIndex];
|
||||
var newMode = createMode(modeIndex, modeId);
|
||||
modeTableBodyElement.append(newMode);
|
||||
|
||||
// generate ranges from the supplied AUX names and MODE_RANGES[_EXTRA] data
|
||||
// skip linked modes for now
|
||||
for (var modeRangeIndex = 0; modeRangeIndex < MODE_RANGES.length; modeRangeIndex++) {
|
||||
var modeRange = MODE_RANGES[modeRangeIndex];
|
||||
for (var modeRangeIndex = 0; modeRangeIndex < FC.MODE_RANGES.length; modeRangeIndex++) {
|
||||
var modeRange = FC.MODE_RANGES[modeRangeIndex];
|
||||
|
||||
var modeRangeExtra = {
|
||||
id: modeRange.id,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
modeRangeExtra = MODE_RANGES_EXTRA[modeRangeIndex];
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
modeRangeExtra = FC.MODE_RANGES_EXTRA[modeRangeIndex];
|
||||
}
|
||||
|
||||
if (modeRange.id != modeId || modeRangeExtra.id != modeId) {
|
||||
|
@ -314,10 +314,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
// update internal data structures based on current UI elements
|
||||
|
||||
// we must send this many back to the FC - overwrite all of the old ones to be sure.
|
||||
var requiredModesRangeCount = MODE_RANGES.length;
|
||||
var requiredModesRangeCount = FC.MODE_RANGES.length;
|
||||
|
||||
MODE_RANGES = [];
|
||||
MODE_RANGES_EXTRA = [];
|
||||
FC.MODE_RANGES = [];
|
||||
FC.MODE_RANGES_EXTRA = [];
|
||||
|
||||
$('.tab-auxiliary .modes .mode').each(function () {
|
||||
var modeElement = $(this);
|
||||
|
@ -333,14 +333,14 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
end: rangeValues[1]
|
||||
}
|
||||
};
|
||||
MODE_RANGES.push(modeRange);
|
||||
FC.MODE_RANGES.push(modeRange);
|
||||
|
||||
var modeRangeExtra = {
|
||||
id: modeId,
|
||||
modeLogic: parseInt($(this).find('.logic').val()),
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
FC.MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
});
|
||||
|
||||
$(modeElement).find('.link').each(function() {
|
||||
|
@ -357,19 +357,19 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
end: 900
|
||||
}
|
||||
};
|
||||
MODE_RANGES.push(modeRange);
|
||||
FC.MODE_RANGES.push(modeRange);
|
||||
|
||||
var modeRangeExtra = {
|
||||
id: modeId,
|
||||
modeLogic: parseInt($(this).find('.logic').val()),
|
||||
linkedTo: linkedToSelection
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
FC.MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
}
|
||||
});
|
||||
});
|
||||
|
||||
for (var modeRangeIndex = MODE_RANGES.length; modeRangeIndex < requiredModesRangeCount; modeRangeIndex++) {
|
||||
for (var modeRangeIndex = FC.MODE_RANGES.length; modeRangeIndex < requiredModesRangeCount; modeRangeIndex++) {
|
||||
var defaultModeRange = {
|
||||
id: 0,
|
||||
auxChannelIndex: 0,
|
||||
|
@ -378,14 +378,14 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
end: 900
|
||||
}
|
||||
};
|
||||
MODE_RANGES.push(defaultModeRange);
|
||||
FC.MODE_RANGES.push(defaultModeRange);
|
||||
|
||||
var defaultModeRangeExtra = {
|
||||
id: 0,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
FC.MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
}
|
||||
|
||||
//
|
||||
|
@ -430,7 +430,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
|
||||
function update_ui() {
|
||||
let hasUsedMode = false;
|
||||
for (let i = 0; i < AUX_CONFIG.length; i++) {
|
||||
for (let i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
let modeElement = $('#mode-' + i);
|
||||
if (modeElement.find(' .range').length == 0 && modeElement.find(' .link').length == 0) {
|
||||
// if the mode is unused, skip it
|
||||
|
@ -438,12 +438,12 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
continue;
|
||||
}
|
||||
|
||||
if (bit_check(CONFIG.mode, i)) {
|
||||
if (bit_check(FC.CONFIG.mode, i)) {
|
||||
$('.mode .name').eq(i).data('modeElement').addClass('on').removeClass('off').removeClass('disabled');
|
||||
|
||||
// ARM mode is a special case
|
||||
if (i == 0) {
|
||||
$('.mode .name').eq(i).html(AUX_CONFIG[i]);
|
||||
$('.mode .name').eq(i).html(FC.AUX_CONFIG[i]);
|
||||
}
|
||||
} else {
|
||||
|
||||
|
@ -451,11 +451,11 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
if (i == 0) {
|
||||
var armSwitchActive = false;
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (CONFIG.armingDisableCount > 0) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
if (FC.CONFIG.armingDisableCount > 0) {
|
||||
// check the highest bit of the armingDisableFlags. This will be the ARMING_DISABLED_ARMSWITCH flag.
|
||||
var armSwitchMask = 1 << (CONFIG.armingDisableCount - 1);
|
||||
if ((CONFIG.armingDisableFlags & armSwitchMask) > 0) {
|
||||
var armSwitchMask = 1 << (FC.CONFIG.armingDisableCount - 1);
|
||||
if ((FC.CONFIG.armingDisableFlags & armSwitchMask) > 0) {
|
||||
armSwitchActive = true;
|
||||
}
|
||||
}
|
||||
|
@ -466,10 +466,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
// that arming is disabled.
|
||||
if (armSwitchActive) {
|
||||
$('.mode .name').eq(i).data('modeElement').removeClass('on').removeClass('off').addClass('disabled');
|
||||
$('.mode .name').eq(i).html(AUX_CONFIG[i] + '<br>' + i18n.getMessage('auxiliaryDisabled'));
|
||||
$('.mode .name').eq(i).html(FC.AUX_CONFIG[i] + '<br>' + i18n.getMessage('auxiliaryDisabled'));
|
||||
} else {
|
||||
$('.mode .name').eq(i).data('modeElement').removeClass('on').removeClass('disabled').addClass('off');
|
||||
$('.mode .name').eq(i).html(AUX_CONFIG[i]);
|
||||
$('.mode .name').eq(i).html(FC.AUX_CONFIG[i]);
|
||||
}
|
||||
} else {
|
||||
$('.mode .name').eq(i).data('modeElement').removeClass('on').removeClass('disabled').addClass('off');
|
||||
|
@ -479,19 +479,19 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
let hideUnused = hideUnusedModes && hasUsedMode;
|
||||
for (let i = 0; i < AUX_CONFIG.length; i++) {
|
||||
for (let i = 0; i < FC.AUX_CONFIG.length; i++) {
|
||||
let modeElement = $('#mode-' + i);
|
||||
if (modeElement.find(' .range').length == 0 && modeElement.find(' .link').length == 0) {
|
||||
modeElement.toggle(!hideUnused);
|
||||
}
|
||||
}
|
||||
|
||||
auto_select_channel(RC.channels, RSSI_CONFIG.channel);
|
||||
auto_select_channel(FC.RC.channels, FC.RSSI_CONFIG.channel);
|
||||
|
||||
var auxChannelCount = RC.active_channels - 4;
|
||||
var auxChannelCount = FC.RC.active_channels - 4;
|
||||
|
||||
for (var i = 0; i < (auxChannelCount); i++) {
|
||||
update_marker(i, limit_channel(RC.channels[i + 4]));
|
||||
update_marker(i, limit_channel(FC.RC.channels[i + 4]));
|
||||
}
|
||||
|
||||
}
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -19,7 +19,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function load_rxfail_config() {
|
||||
MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false,
|
||||
semver.gte(CONFIG.apiVersion, "1.41.0") ? load_gps_rescue : get_box_names);
|
||||
semver.gte(FC.CONFIG.apiVersion, "1.41.0") ? load_gps_rescue : get_box_names);
|
||||
}
|
||||
|
||||
function load_gps_rescue() {
|
||||
|
@ -89,21 +89,21 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
i,
|
||||
element;
|
||||
|
||||
for (var channelIndex = 0; channelIndex < RC.active_channels - 4; channelIndex++) {
|
||||
for (var channelIndex = 0; channelIndex < FC.RC.active_channels - 4; channelIndex++) {
|
||||
auxAssignment.push("");
|
||||
}
|
||||
|
||||
if (typeof RSSI_CONFIG.channel !== 'undefined') {
|
||||
auxAssignment[RSSI_CONFIG.channel - 5] += "<span class=\"modename\">" + "RSSI" + "</span>"; // Aux channels start at 5 in backend so we have to substract 5
|
||||
if (typeof FC.RSSI_CONFIG.channel !== 'undefined') {
|
||||
auxAssignment[FC.RSSI_CONFIG.channel - 5] += "<span class=\"modename\">" + "RSSI" + "</span>"; // Aux channels start at 5 in backend so we have to substract 5
|
||||
}
|
||||
|
||||
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
||||
for (var modeIndex = 0; modeIndex < FC.AUX_CONFIG.length; modeIndex++) {
|
||||
|
||||
var modeId = AUX_CONFIG_IDS[modeIndex];
|
||||
var modeId = FC.AUX_CONFIG_IDS[modeIndex];
|
||||
|
||||
// scan mode ranges to find assignments
|
||||
for (var modeRangeIndex = 0; modeRangeIndex < MODE_RANGES.length; modeRangeIndex++) {
|
||||
var modeRange = MODE_RANGES[modeRangeIndex];
|
||||
for (var modeRangeIndex = 0; modeRangeIndex < FC.MODE_RANGES.length; modeRangeIndex++) {
|
||||
var modeRange = FC.MODE_RANGES[modeRangeIndex];
|
||||
|
||||
if (modeRange.id != modeId) {
|
||||
continue;
|
||||
|
@ -115,7 +115,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
// Search for the real name if it belongs to a peripheral
|
||||
var modeName = AUX_CONFIG[modeIndex];
|
||||
var modeName = FC.AUX_CONFIG[modeIndex];
|
||||
modeName = adjustBoxNameIfPeripheralWithModeID(modeId, modeName);
|
||||
|
||||
auxAssignment[modeRange.auxChannelIndex] += "<span class=\"modename\">" + modeName + "</span>";
|
||||
|
@ -133,9 +133,9 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
aux_index = 1,
|
||||
aux_assignment_index = 0;
|
||||
|
||||
for (i = 0; i < RXFAIL_CONFIG.length; i++) {
|
||||
for (i = 0; i < FC.RXFAIL_CONFIG.length; i++) {
|
||||
if (i < channelNames.length) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
fullChannels_e.append('\
|
||||
<div class="number">\
|
||||
<div class="channelprimary">\
|
||||
|
@ -202,7 +202,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
channelMode.change(function () {
|
||||
var currentMode = parseInt($(this).val());
|
||||
var i = parseInt($(this).prop("id"));
|
||||
RXFAIL_CONFIG[i].mode = currentMode;
|
||||
FC.RXFAIL_CONFIG[i].mode = currentMode;
|
||||
if (currentMode == 2) {
|
||||
channel_value_array[i].prop("disabled", false);
|
||||
channel_value_array[i].show();
|
||||
|
@ -215,7 +215,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
// UI hooks
|
||||
channelValue.change(function () {
|
||||
var i = parseInt($(this).prop("id"));
|
||||
RXFAIL_CONFIG[i].value = parseInt($(this).val());
|
||||
FC.RXFAIL_CONFIG[i].value = parseInt($(this).val());
|
||||
});
|
||||
|
||||
// for some odd reason chrome 38+ changes scroll according to the touched select element
|
||||
|
@ -224,19 +224,19 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
||||
|
||||
// fill stage 1 Valid Pulse Range Settings
|
||||
$('input[name="rx_min_usec"]').val(RX_CONFIG.rx_min_usec);
|
||||
$('input[name="rx_max_usec"]').val(RX_CONFIG.rx_max_usec);
|
||||
$('input[name="rx_min_usec"]').val(FC.RX_CONFIG.rx_min_usec);
|
||||
$('input[name="rx_max_usec"]').val(FC.RX_CONFIG.rx_max_usec);
|
||||
|
||||
// fill fallback settings (mode and value) for all channels
|
||||
for (i = 0; i < RXFAIL_CONFIG.length; i++) {
|
||||
channel_value_array[i].val(RXFAIL_CONFIG[i].value);
|
||||
channel_mode_array[i].val(RXFAIL_CONFIG[i].mode);
|
||||
for (i = 0; i < FC.RXFAIL_CONFIG.length; i++) {
|
||||
channel_value_array[i].val(FC.RXFAIL_CONFIG[i].value);
|
||||
channel_mode_array[i].val(FC.RXFAIL_CONFIG[i].mode);
|
||||
channel_mode_array[i].change();
|
||||
}
|
||||
|
||||
FEATURE_CONFIG.features.generateElements($('.tab-failsafe .featuresNew'));
|
||||
FC.FEATURE_CONFIG.features.generateElements($('.tab-failsafe .featuresNew'));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
$('tbody.rxFailsafe').hide();
|
||||
toggleStage2(true);
|
||||
} else {
|
||||
|
@ -244,13 +244,13 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
failsafeFeature.change(function () {
|
||||
toggleStage2($(this).is(':checked'));
|
||||
});
|
||||
toggleStage2(FEATURE_CONFIG.features.isEnabled('FAILSAFE'));
|
||||
toggleStage2(FC.FEATURE_CONFIG.features.isEnabled('FAILSAFE'));
|
||||
}
|
||||
|
||||
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
|
||||
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
||||
$('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay);
|
||||
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
|
||||
$('input[name="failsafe_throttle"]').val(FC.FAILSAFE_CONFIG.failsafe_throttle);
|
||||
$('input[name="failsafe_off_delay"]').val(FC.FAILSAFE_CONFIG.failsafe_off_delay);
|
||||
$('input[name="failsafe_throttle_low_delay"]').val(FC.FAILSAFE_CONFIG.failsafe_throttle_low_delay);
|
||||
$('input[name="failsafe_delay"]').val(FC.FAILSAFE_CONFIG.failsafe_delay);
|
||||
|
||||
// set stage 2 failsafe procedure
|
||||
$('input[type="radio"].procedure').change(function () {
|
||||
|
@ -264,7 +264,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
element.parent().parent().find(':input').attr('disabled',false);
|
||||
});
|
||||
|
||||
switch(FAILSAFE_CONFIG.failsafe_procedure) {
|
||||
switch(FC.FAILSAFE_CONFIG.failsafe_procedure) {
|
||||
default:
|
||||
case 0:
|
||||
element = $('input[id="land"]') ;
|
||||
|
@ -283,37 +283,37 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
break;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.39.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
// `failsafe_kill_switch` has been renamed to `failsafe_switch_mode`.
|
||||
// It is backwards compatible with `failsafe_kill_switch`
|
||||
$('select[name="failsafe_switch_mode"]').val(FAILSAFE_CONFIG.failsafe_switch_mode);
|
||||
$('select[name="failsafe_switch_mode"]').val(FC.FAILSAFE_CONFIG.failsafe_switch_mode);
|
||||
$('div.kill_switch').hide();
|
||||
}
|
||||
else {
|
||||
$('input[name="failsafe_kill_switch"]').prop('checked', FAILSAFE_CONFIG.failsafe_switch_mode);
|
||||
$('input[name="failsafe_kill_switch"]').prop('checked', FC.FAILSAFE_CONFIG.failsafe_switch_mode);
|
||||
$('div.failsafe_switch').hide();
|
||||
}
|
||||
|
||||
// The GPS Rescue tab is only available for 1.40 or later, and the parameters for 1.41
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
// Load GPS Rescue parameters
|
||||
$('input[name="gps_rescue_angle"]').val(GPS_RESCUE.angle);
|
||||
$('input[name="gps_rescue_initial_altitude"]').val(GPS_RESCUE.initialAltitudeM);
|
||||
$('input[name="gps_rescue_descent_distance"]').val(GPS_RESCUE.descentDistanceM);
|
||||
$('input[name="gps_rescue_ground_speed"]').val((GPS_RESCUE.rescueGroundspeed / 100).toFixed(2));
|
||||
$('input[name="gps_rescue_throttle_min"]').val(GPS_RESCUE.throttleMin);
|
||||
$('input[name="gps_rescue_throttle_max"]').val(GPS_RESCUE.throttleMax);
|
||||
$('input[name="gps_rescue_throttle_hover"]').val(GPS_RESCUE.throttleHover);
|
||||
$('input[name="gps_rescue_min_sats"]').val(GPS_RESCUE.minSats);
|
||||
$('select[name="gps_rescue_sanity_checks"]').val(GPS_RESCUE.sanityChecks);
|
||||
$('input[name="gps_rescue_angle"]').val(FC.GPS_RESCUE.angle);
|
||||
$('input[name="gps_rescue_initial_altitude"]').val(FC.GPS_RESCUE.initialAltitudeM);
|
||||
$('input[name="gps_rescue_descent_distance"]').val(FC.GPS_RESCUE.descentDistanceM);
|
||||
$('input[name="gps_rescue_ground_speed"]').val((FC.GPS_RESCUE.rescueGroundspeed / 100).toFixed(2));
|
||||
$('input[name="gps_rescue_throttle_min"]').val(FC.GPS_RESCUE.throttleMin);
|
||||
$('input[name="gps_rescue_throttle_max"]').val(FC.GPS_RESCUE.throttleMax);
|
||||
$('input[name="gps_rescue_throttle_hover"]').val(FC.GPS_RESCUE.throttleHover);
|
||||
$('input[name="gps_rescue_min_sats"]').val(FC.GPS_RESCUE.minSats);
|
||||
$('select[name="gps_rescue_sanity_checks"]').val(FC.GPS_RESCUE.sanityChecks);
|
||||
|
||||
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);
|
||||
$('select[name="gps_rescue_altitude_mode"]').val(GPS_RESCUE.altitudeMode);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
$('input[name="gps_rescue_ascend_rate"]').val((FC.GPS_RESCUE.ascendRate / 100).toFixed(2));
|
||||
$('input[name="gps_rescue_descend_rate"]').val((FC.GPS_RESCUE.descendRate / 100).toFixed(2));
|
||||
$('input[name="gps_rescue_allow_arming_without_fix"]').prop('checked', FC.GPS_RESCUE.allowArmingWithoutFix > 0);
|
||||
$('select[name="gps_rescue_altitude_mode"]').val(FC.GPS_RESCUE.altitudeMode);
|
||||
} else {
|
||||
$('input[name="gps_rescue_ascend_rate"]').closest('.number').hide();
|
||||
$('input[name="gps_rescue_descend_rate"]').closest('.number').hide();
|
||||
|
@ -337,49 +337,49 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
$('a.save').click(function () {
|
||||
// gather data that doesn't have automatic change event bound
|
||||
|
||||
FEATURE_CONFIG.features.updateData($('input[name="FAILSAFE"]'));
|
||||
FC.FEATURE_CONFIG.features.updateData($('input[name="FAILSAFE"]'));
|
||||
|
||||
RX_CONFIG.rx_min_usec = parseInt($('input[name="rx_min_usec"]').val());
|
||||
RX_CONFIG.rx_max_usec = parseInt($('input[name="rx_max_usec"]').val());
|
||||
FC.RX_CONFIG.rx_min_usec = parseInt($('input[name="rx_min_usec"]').val());
|
||||
FC.RX_CONFIG.rx_max_usec = parseInt($('input[name="rx_max_usec"]').val());
|
||||
|
||||
FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val());
|
||||
FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val());
|
||||
FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val());
|
||||
FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
|
||||
FC.FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val());
|
||||
FC.FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val());
|
||||
FC.FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val());
|
||||
FC.FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
|
||||
|
||||
if( $('input[id="land"]').is(':checked')) {
|
||||
FAILSAFE_CONFIG.failsafe_procedure = 0;
|
||||
FC.FAILSAFE_CONFIG.failsafe_procedure = 0;
|
||||
} else if( $('input[id="drop"]').is(':checked')) {
|
||||
FAILSAFE_CONFIG.failsafe_procedure = 1;
|
||||
FC.FAILSAFE_CONFIG.failsafe_procedure = 1;
|
||||
} else if( $('input[id="gps_rescue"]').is(':checked')) {
|
||||
FAILSAFE_CONFIG.failsafe_procedure = 2;
|
||||
FC.FAILSAFE_CONFIG.failsafe_procedure = 2;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.39.0")) {
|
||||
FAILSAFE_CONFIG.failsafe_switch_mode = $('select[name="failsafe_switch_mode"]').val();
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
FC.FAILSAFE_CONFIG.failsafe_switch_mode = $('select[name="failsafe_switch_mode"]').val();
|
||||
}
|
||||
else {
|
||||
FAILSAFE_CONFIG.failsafe_switch_mode = $('input[name="failsafe_kill_switch"]').is(':checked') ? 1 : 0;
|
||||
FC.FAILSAFE_CONFIG.failsafe_switch_mode = $('input[name="failsafe_kill_switch"]').is(':checked') ? 1 : 0;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
// Load GPS Rescue parameters
|
||||
GPS_RESCUE.angle = $('input[name="gps_rescue_angle"]').val();
|
||||
GPS_RESCUE.initialAltitudeM = $('input[name="gps_rescue_initial_altitude"]').val();
|
||||
GPS_RESCUE.descentDistanceM = $('input[name="gps_rescue_descent_distance"]').val();
|
||||
GPS_RESCUE.rescueGroundspeed = $('input[name="gps_rescue_ground_speed"]').val() * 100;
|
||||
GPS_RESCUE.throttleMin = $('input[name="gps_rescue_throttle_min"]').val();
|
||||
GPS_RESCUE.throttleMax = $('input[name="gps_rescue_throttle_max"]').val();
|
||||
GPS_RESCUE.throttleHover = $('input[name="gps_rescue_throttle_hover"]').val();
|
||||
GPS_RESCUE.minSats = $('input[name="gps_rescue_min_sats"]').val();
|
||||
GPS_RESCUE.sanityChecks = $('select[name="gps_rescue_sanity_checks"]').val();
|
||||
FC.GPS_RESCUE.angle = $('input[name="gps_rescue_angle"]').val();
|
||||
FC.GPS_RESCUE.initialAltitudeM = $('input[name="gps_rescue_initial_altitude"]').val();
|
||||
FC.GPS_RESCUE.descentDistanceM = $('input[name="gps_rescue_descent_distance"]').val();
|
||||
FC.GPS_RESCUE.rescueGroundspeed = $('input[name="gps_rescue_ground_speed"]').val() * 100;
|
||||
FC.GPS_RESCUE.throttleMin = $('input[name="gps_rescue_throttle_min"]').val();
|
||||
FC.GPS_RESCUE.throttleMax = $('input[name="gps_rescue_throttle_max"]').val();
|
||||
FC.GPS_RESCUE.throttleHover = $('input[name="gps_rescue_throttle_hover"]').val();
|
||||
FC.GPS_RESCUE.minSats = $('input[name="gps_rescue_min_sats"]').val();
|
||||
FC.GPS_RESCUE.sanityChecks = $('select[name="gps_rescue_sanity_checks"]').val();
|
||||
}
|
||||
|
||||
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;
|
||||
GPS_RESCUE.altitudeMode = parseInt($('select[name="gps_rescue_altitude_mode"]').val());
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
FC.GPS_RESCUE.ascendRate = $('input[name="gps_rescue_ascend_rate"]').val() * 100;
|
||||
FC.GPS_RESCUE.descendRate = $('input[name="gps_rescue_descend_rate"]').val() * 100;
|
||||
FC.GPS_RESCUE.allowArmingWithoutFix = $('input[name="gps_rescue_allow_arming_without_fix"]').prop('checked') ? 1 : 0;
|
||||
FC.GPS_RESCUE.altitudeMode = parseInt($('select[name="gps_rescue_altitude_mode"]').val());
|
||||
}
|
||||
|
||||
function save_failssafe_config() {
|
||||
|
@ -392,7 +392,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function save_feature_config() {
|
||||
MSP.send_message(MSPCodes.MSP_SET_FEATURE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE_CONFIG), false,
|
||||
semver.gte(CONFIG.apiVersion, "1.41.0") ? save_gps_rescue : save_to_eeprom);
|
||||
semver.gte(FC.CONFIG.apiVersion, "1.41.0") ? save_gps_rescue : save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_gps_rescue() {
|
||||
|
|
|
@ -46,31 +46,31 @@ TABS.gps.initialize = function (callback) {
|
|||
var gpsWasFixed = false;
|
||||
|
||||
function update_ui() {
|
||||
var lat = GPS_DATA.lat / 10000000;
|
||||
var lon = GPS_DATA.lon / 10000000;
|
||||
var lat = FC.GPS_DATA.lat / 10000000;
|
||||
var lon = FC.GPS_DATA.lon / 10000000;
|
||||
var url = 'https://maps.google.com/?q=' + lat + ',' + lon;
|
||||
var alt = GPS_DATA.alt;
|
||||
if (semver.lt(CONFIG.apiVersion, "1.39.0")) {
|
||||
var alt = FC.GPS_DATA.alt;
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
alt = alt / 10;
|
||||
}
|
||||
|
||||
$('.GPS_info td.fix').html((GPS_DATA.fix) ? i18n.getMessage('gpsFixTrue') : i18n.getMessage('gpsFixFalse'));
|
||||
$('.GPS_info td.fix').html((FC.GPS_DATA.fix) ? i18n.getMessage('gpsFixTrue') : i18n.getMessage('gpsFixFalse'));
|
||||
$('.GPS_info td.alt').text(alt + ' m');
|
||||
$('.GPS_info td.lat a').prop('href', url).text(lat.toFixed(4) + ' deg');
|
||||
$('.GPS_info td.lon a').prop('href', url).text(lon.toFixed(4) + ' deg');
|
||||
$('.GPS_info td.speed').text(GPS_DATA.speed + ' cm/s');
|
||||
$('.GPS_info td.sats').text(GPS_DATA.numSat);
|
||||
$('.GPS_info td.distToHome').text(GPS_DATA.distanceToHome + ' m');
|
||||
$('.GPS_info td.speed').text(FC.GPS_DATA.speed + ' cm/s');
|
||||
$('.GPS_info td.sats').text(FC.GPS_DATA.numSat);
|
||||
$('.GPS_info td.distToHome').text(FC.GPS_DATA.distanceToHome + ' m');
|
||||
|
||||
// Update GPS Signal Strengths
|
||||
var e_ss_table = $('div.GPS_signal_strength table tr:not(.titles)');
|
||||
|
||||
for (var i = 0; i < GPS_DATA.chn.length; i++) {
|
||||
for (var i = 0; i < FC.GPS_DATA.chn.length; i++) {
|
||||
var row = e_ss_table.eq(i);
|
||||
|
||||
$('td', row).eq(0).text(GPS_DATA.svid[i]);
|
||||
$('td', row).eq(1).text(GPS_DATA.quality[i]);
|
||||
$('td', row).eq(2).find('progress').val(GPS_DATA.cno[i]);
|
||||
$('td', row).eq(0).text(FC.GPS_DATA.svid[i]);
|
||||
$('td', row).eq(1).text(FC.GPS_DATA.quality[i]);
|
||||
$('td', row).eq(2).find('progress').val(FC.GPS_DATA.cno[i]);
|
||||
}
|
||||
|
||||
|
||||
|
@ -84,7 +84,7 @@ TABS.gps.initialize = function (callback) {
|
|||
if (navigator.onLine) {
|
||||
$('#connect').hide();
|
||||
|
||||
if (GPS_DATA.fix) {
|
||||
if (FC.GPS_DATA.fix) {
|
||||
gpsWasFixed = true;
|
||||
frame.contentWindow.postMessage(message, '*');
|
||||
$('#loadmap').show();
|
||||
|
@ -107,7 +107,7 @@ TABS.gps.initialize = function (callback) {
|
|||
// enable data pulling
|
||||
GUI.interval_add('gps_pull', function gps_update() {
|
||||
// avoid usage of the GPS commands until a GPS sensor is detected for targets that are compiled without GPS support.
|
||||
if (!have_sensor(CONFIG.activeSensors, 'gps')) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'gps')) {
|
||||
//return;
|
||||
}
|
||||
|
||||
|
|
|
@ -11,14 +11,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
var selectedColorIndex = null;
|
||||
var selectedModeColor = null;
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
TABS.led_strip.functions = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b'];
|
||||
TABS.led_strip.baseFuncs = ['c', 'f', 'a', 'b', 'g', 'r'];
|
||||
TABS.led_strip.overlays = ['t', 's', 'i', 'w'];
|
||||
} else {
|
||||
TABS.led_strip.functions = ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l', 'o', 'n'];
|
||||
TABS.led_strip.baseFuncs = ['c', 'f', 'a', 'l', 's', 'g', 'r'];
|
||||
if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
TABS.led_strip.overlays = ['t', 'o', 'b', 'n', 'i', 'w'];
|
||||
} else {
|
||||
TABS.led_strip.overlays = ['t', 'o', 'b', 'v', 'i', 'w'];
|
||||
|
@ -40,7 +40,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_led_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0"))
|
||||
MSP.send_message(MSPCodes.MSP_LED_STRIP_MODECOLOR, false, false, load_html);
|
||||
else
|
||||
load_html();
|
||||
|
@ -73,9 +73,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
var theHTML = [];
|
||||
var theHTMLlength = 0;
|
||||
for (var i = 0; i < 256; i++) {
|
||||
if (semver.lte(CONFIG.apiVersion, "1.19.0")) {
|
||||
if (semver.lte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
theHTML[theHTMLlength++] = ('<div class="gPoint"><div class="indicators"><span class="north"></span><span class="south"></span><span class="west"></span><span class="east"></span><span class="up">U</span><span class="down">D</span></div><span class="wire"></span><span class="overlay-t"> </span><span class="overlay-s"> </span><span class="overlay-w"> </span><span class="overlay-i"> </span><span class="overlay-color"> </span></div>');
|
||||
} else if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
} else if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
theHTML[theHTMLlength++] = ('<div class="gPoint"><div class="indicators"><span class="north"></span><span class="south"></span><span class="west"></span><span class="east"></span><span class="up">U</span><span class="down">D</span></div><span class="wire"></span><span class="overlay-t"> </span><span class="overlay-o"> </span><span class="overlay-b"> </span><span class="overlay-n"> </span><span class="overlay-i"> </span><span class="overlay-w"> </span><span class="overlay-color"> </span></div>');
|
||||
} else {
|
||||
theHTML[theHTMLlength++] = ('<div class="gPoint"><div class="indicators"><span class="north"></span><span class="south"></span><span class="west"></span><span class="east"></span><span class="up">U</span><span class="down">D</span></div><span class="wire"></span><span class="overlay-t"> </span><span class="overlay-o"> </span><span class="overlay-b"> </span><span class="overlay-v"> </span><span class="overlay-i"> </span><span class="overlay-w"> </span><span class="overlay-color"> </span></div>');
|
||||
|
@ -88,7 +88,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
});
|
||||
|
||||
// Aux channel drop-down
|
||||
if (semver.lte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.lte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
$('.auxSelect').hide();
|
||||
$('.labelSelect').show();
|
||||
} else {
|
||||
|
@ -105,7 +105,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
});
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
$('.vtxOverlay').hide();
|
||||
$('.landingBlinkOverlay').show();
|
||||
}
|
||||
|
@ -178,7 +178,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
// Mode Color Buttons
|
||||
$('.mode_colors').on('click', 'button', function() {
|
||||
var that = this;
|
||||
LED_MODE_COLORS.forEach(function(mc) {
|
||||
FC.LED_MODE_COLORS.forEach(function(mc) {
|
||||
if ($(that).is('.mode_color-' + mc.mode + '-' + mc.direction)) {
|
||||
if ($(that).is('.btnOn')) {
|
||||
$(that).removeClass('btnOn');
|
||||
|
@ -320,7 +320,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
if (TABS.led_strip.wireMode) {
|
||||
if ($(this).find('.wire').html() == '' && nextWireNumber < LED_STRIP.length) {
|
||||
if ($(this).find('.wire').html() == '' && nextWireNumber < FC.LED_STRIP.length) {
|
||||
$(this).find('.wire').html(nextWireNumber);
|
||||
}
|
||||
}
|
||||
|
@ -571,7 +571,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function send_led_strip_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0"))
|
||||
mspHelper.sendLedStripModeColors(save_to_eeprom);
|
||||
else
|
||||
save_to_eeprom();
|
||||
|
@ -608,8 +608,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
|
||||
|
||||
function findLed(x, y) {
|
||||
for (var ledIndex = 0; ledIndex < LED_STRIP.length; ledIndex++) {
|
||||
var led = LED_STRIP[ledIndex];
|
||||
for (var ledIndex = 0; ledIndex < FC.LED_STRIP.length; ledIndex++) {
|
||||
var led = FC.LED_STRIP[ledIndex];
|
||||
if (led.x == x && led.y == y) {
|
||||
return { index: ledIndex, led: led };
|
||||
}
|
||||
|
@ -619,9 +619,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
|
||||
|
||||
function updateBulkCmd() {
|
||||
var ledStripLength = LED_STRIP.length;
|
||||
var ledStripLength = FC.LED_STRIP.length;
|
||||
|
||||
LED_STRIP = [];
|
||||
FC.LED_STRIP = [];
|
||||
|
||||
$('.gPoint').each(function(){
|
||||
if ($(this).is('[class*="function"]')) {
|
||||
|
@ -667,7 +667,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
color: colorIndex
|
||||
}
|
||||
|
||||
LED_STRIP[wireNumber] = led;
|
||||
FC.LED_STRIP[wireNumber] = led;
|
||||
}
|
||||
}
|
||||
});
|
||||
|
@ -680,22 +680,22 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
};
|
||||
|
||||
for (var i = 0; i < ledStripLength; i++) {
|
||||
if (LED_STRIP[i]) {
|
||||
if (FC.LED_STRIP[i]) {
|
||||
continue;
|
||||
}
|
||||
LED_STRIP[i] = defaultLed;
|
||||
FC.LED_STRIP[i] = defaultLed;
|
||||
}
|
||||
|
||||
var usedWireNumbers = buildUsedWireNumbers();
|
||||
|
||||
var remaining = LED_STRIP.length - usedWireNumbers.length;
|
||||
var remaining = FC.LED_STRIP.length - usedWireNumbers.length;
|
||||
|
||||
$('.wires-remaining div').html(remaining);
|
||||
}
|
||||
|
||||
// refresh mode color buttons
|
||||
function setModeBackgroundColor(element) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
element.find('[class*="mode_color"]').each(function() {
|
||||
var m = 0;
|
||||
var d = 0;
|
||||
|
@ -704,7 +704,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
if (match) {
|
||||
m = Number(match[2]);
|
||||
d = Number(match[3]);
|
||||
$(this).css('background-color', HsvToColor(LED_COLORS[getModeColor(m, d)]));
|
||||
$(this).css('background-color', HsvToColor(FC.LED_COLORS[getModeColor(m, d)]));
|
||||
}
|
||||
});
|
||||
}
|
||||
|
@ -717,7 +717,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
var match = element.attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/);
|
||||
if (match) {
|
||||
colorIndex = match[2];
|
||||
element.css('background-color', HsvToColor(LED_COLORS[colorIndex]));
|
||||
element.css('background-color', HsvToColor(FC.LED_COLORS[colorIndex]));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -734,7 +734,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function areOverlaysActive(activeFunction) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
switch (activeFunction) {
|
||||
case "function-c":
|
||||
case "function-a":
|
||||
|
@ -762,7 +762,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function areBlinkersActive(activeFunction) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
switch (activeFunction) {
|
||||
case "function-c":
|
||||
case "function-a":
|
||||
|
@ -783,7 +783,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
break;
|
||||
case "function-r":
|
||||
case "function-b":
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0"))
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0"))
|
||||
return false;
|
||||
break;
|
||||
default:
|
||||
|
@ -793,7 +793,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function isVtxActive(activeFunction) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
switch (activeFunction) {
|
||||
case "function-v":
|
||||
case "function-c":
|
||||
|
@ -814,7 +814,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
$('select.functionSelect').addClass(activeFunction);
|
||||
|
||||
|
||||
if (semver.lte(CONFIG.apiVersion, "1.18.0")) {
|
||||
if (semver.lte(FC.CONFIG.apiVersion, "1.18.0")) {
|
||||
// <= 18
|
||||
// Hide GPS (Func)
|
||||
// Hide RSSI (O/L), Blink (Func)
|
||||
|
@ -856,7 +856,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
|
||||
|
||||
// set directions visibility
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
switch (activeFunction) {
|
||||
case "function-r":
|
||||
$('.indicatorOverlay').hide();
|
||||
|
@ -870,10 +870,10 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
$('.mode_colors').hide();
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
// set mode colors visibility
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0"))
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0"))
|
||||
if (activeFunction == "function-f")
|
||||
$('.mode_colors').show();
|
||||
|
||||
|
@ -944,7 +944,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function unselectOverlays(letter) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
if (letter == 'b' || letter == 'r') {
|
||||
unselectOverlay(letter, 'i');
|
||||
}
|
||||
|
@ -992,23 +992,23 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
if ($(className).hasClass('btnOn')) {
|
||||
switch (hsvIndex) {
|
||||
case 0:
|
||||
if (LED_COLORS[selectedColorIndex].h != value) {
|
||||
LED_COLORS[selectedColorIndex].h = value;
|
||||
$('.colorDefineSliderValue.Hvalue').text(LED_COLORS[selectedColorIndex].h);
|
||||
if (FC.LED_COLORS[selectedColorIndex].h != value) {
|
||||
FC.LED_COLORS[selectedColorIndex].h = value;
|
||||
$('.colorDefineSliderValue.Hvalue').text(FC.LED_COLORS[selectedColorIndex].h);
|
||||
change = true
|
||||
}
|
||||
break;
|
||||
case 1:
|
||||
if (LED_COLORS[selectedColorIndex].s != value) {
|
||||
LED_COLORS[selectedColorIndex].s = value;
|
||||
$('.colorDefineSliderValue.Svalue').text(LED_COLORS[selectedColorIndex].s);
|
||||
if (FC.LED_COLORS[selectedColorIndex].s != value) {
|
||||
FC.LED_COLORS[selectedColorIndex].s = value;
|
||||
$('.colorDefineSliderValue.Svalue').text(FC.LED_COLORS[selectedColorIndex].s);
|
||||
change = true
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
if (LED_COLORS[selectedColorIndex].v != value) {
|
||||
LED_COLORS[selectedColorIndex].v = value;
|
||||
$('.colorDefineSliderValue.Vvalue').text(LED_COLORS[selectedColorIndex].v);
|
||||
if (FC.LED_COLORS[selectedColorIndex].v != value) {
|
||||
FC.LED_COLORS[selectedColorIndex].v = value;
|
||||
$('.colorDefineSliderValue.Vvalue').text(FC.LED_COLORS[selectedColorIndex].v);
|
||||
change = true
|
||||
}
|
||||
break;
|
||||
|
@ -1036,7 +1036,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
var className = 'color-' + colorIndex;
|
||||
if ($(this).is('.' + className)) {
|
||||
$(this).find('.overlay-color').addClass(className);
|
||||
$(this).find('.overlay-color').css('background-color', HsvToColor(LED_COLORS[colorIndex]))
|
||||
$(this).find('.overlay-color').css('background-color', HsvToColor(FC.LED_COLORS[colorIndex]))
|
||||
} else {
|
||||
if ($(this).find('.overlay-color').is('.' + className))
|
||||
$(this).find('.overlay-color').removeClass(className);
|
||||
|
@ -1053,24 +1053,24 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
var sliders = $('div.colorDefineSliders input');
|
||||
var change = false;
|
||||
|
||||
if (!LED_COLORS[colorIndex])
|
||||
if (!FC.LED_COLORS[colorIndex])
|
||||
return;
|
||||
|
||||
if (LED_COLORS[colorIndex].h != Number(sliders.eq(0).val())) {
|
||||
sliders.eq(0).val(LED_COLORS[colorIndex].h);
|
||||
$('.colorDefineSliderValue.Hvalue').text(LED_COLORS[colorIndex].h);
|
||||
if (FC.LED_COLORS[colorIndex].h != Number(sliders.eq(0).val())) {
|
||||
sliders.eq(0).val(FC.LED_COLORS[colorIndex].h);
|
||||
$('.colorDefineSliderValue.Hvalue').text(FC.LED_COLORS[colorIndex].h);
|
||||
change = true;
|
||||
}
|
||||
|
||||
if (LED_COLORS[colorIndex].s != Number(sliders.eq(1).val())) {
|
||||
sliders.eq(1).val(LED_COLORS[colorIndex].s);
|
||||
$('.colorDefineSliderValue.Svalue').text(LED_COLORS[colorIndex].s);
|
||||
if (FC.LED_COLORS[colorIndex].s != Number(sliders.eq(1).val())) {
|
||||
sliders.eq(1).val(FC.LED_COLORS[colorIndex].s);
|
||||
$('.colorDefineSliderValue.Svalue').text(FC.LED_COLORS[colorIndex].s);
|
||||
change = true;
|
||||
}
|
||||
|
||||
if (LED_COLORS[colorIndex].v != Number(sliders.eq(2).val())) {
|
||||
sliders.eq(2).val(LED_COLORS[colorIndex].v);
|
||||
$('.colorDefineSliderValue.Vvalue').text(LED_COLORS[colorIndex].v);
|
||||
if (FC.LED_COLORS[colorIndex].v != Number(sliders.eq(2).val())) {
|
||||
sliders.eq(2).val(FC.LED_COLORS[colorIndex].v);
|
||||
$('.colorDefineSliderValue.Vvalue').text(FC.LED_COLORS[colorIndex].v);
|
||||
change = true;
|
||||
}
|
||||
|
||||
|
@ -1101,8 +1101,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function getModeColor(mode, dir) {
|
||||
for (var i = 0; i < LED_MODE_COLORS.length; i++) {
|
||||
var mc = LED_MODE_COLORS[i];
|
||||
for (var i = 0; i < FC.LED_MODE_COLORS.length; i++) {
|
||||
var mc = FC.LED_MODE_COLORS[i];
|
||||
if (mc.mode == mode && mc.direction == dir)
|
||||
return mc.color;
|
||||
}
|
||||
|
@ -1110,8 +1110,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function setModeColor(mode, dir, color) {
|
||||
for (var i = 0; i < LED_MODE_COLORS.length; i++) {
|
||||
var mc = LED_MODE_COLORS[i];
|
||||
for (var i = 0; i < FC.LED_MODE_COLORS.length; i++) {
|
||||
var mc = FC.LED_MODE_COLORS[i];
|
||||
if (mc.mode == mode && mc.direction == dir) {
|
||||
mc.color = color;
|
||||
return 1;
|
||||
|
|
|
@ -154,17 +154,17 @@ TABS.logging.initialize = function (callback) {
|
|||
head += ',' + 'rssi';
|
||||
break;
|
||||
case 'MSP_RC':
|
||||
for (var chan = 0; chan < RC.active_channels; chan++) {
|
||||
for (var chan = 0; chan < FC.RC.active_channels; chan++) {
|
||||
head += ',' + 'RC' + chan;
|
||||
}
|
||||
break;
|
||||
case 'MSP_MOTOR':
|
||||
for (var motor = 0; motor < MOTOR_DATA.length; motor++) {
|
||||
for (var motor = 0; motor < FC.MOTOR_DATA.length; motor++) {
|
||||
head += ',' + 'Motor' + motor;
|
||||
}
|
||||
break;
|
||||
case 'MSP_DEBUG':
|
||||
for (var debug = 0; debug < SENSOR_DATA.debug.length; debug++) {
|
||||
for (var debug = 0; debug < FC.SENSOR_DATA.debug.length; debug++) {
|
||||
head += ',' + 'Debug' + debug;
|
||||
}
|
||||
break;
|
||||
|
@ -180,43 +180,43 @@ TABS.logging.initialize = function (callback) {
|
|||
for (var i = 0; i < requested_properties.length; i++) {
|
||||
switch (requested_properties[i]) {
|
||||
case 'MSP_RAW_IMU':
|
||||
sample += ',' + SENSOR_DATA.gyroscope;
|
||||
sample += ',' + SENSOR_DATA.accelerometer;
|
||||
sample += ',' + SENSOR_DATA.magnetometer;
|
||||
sample += ',' + FC.SENSOR_DATA.gyroscope;
|
||||
sample += ',' + FC.SENSOR_DATA.accelerometer;
|
||||
sample += ',' + FC.SENSOR_DATA.magnetometer;
|
||||
break;
|
||||
case 'MSP_ATTITUDE':
|
||||
sample += ',' + SENSOR_DATA.kinematics[0];
|
||||
sample += ',' + SENSOR_DATA.kinematics[1];
|
||||
sample += ',' + SENSOR_DATA.kinematics[2];
|
||||
sample += ',' + FC.SENSOR_DATA.kinematics[0];
|
||||
sample += ',' + FC.SENSOR_DATA.kinematics[1];
|
||||
sample += ',' + FC.SENSOR_DATA.kinematics[2];
|
||||
break;
|
||||
case 'MSP_ALTITUDE':
|
||||
sample += ',' + SENSOR_DATA.altitude;
|
||||
sample += ',' + FC.SENSOR_DATA.altitude;
|
||||
break;
|
||||
case 'MSP_RAW_GPS':
|
||||
sample += ',' + GPS_DATA.fix;
|
||||
sample += ',' + GPS_DATA.numSat;
|
||||
sample += ',' + (GPS_DATA.lat / 10000000);
|
||||
sample += ',' + (GPS_DATA.lon / 10000000);
|
||||
sample += ',' + GPS_DATA.alt;
|
||||
sample += ',' + GPS_DATA.speed;
|
||||
sample += ',' + GPS_DATA.ground_course;
|
||||
sample += ',' + FC.GPS_DATA.fix;
|
||||
sample += ',' + FC.GPS_DATA.numSat;
|
||||
sample += ',' + (FC.GPS_DATA.lat / 10000000);
|
||||
sample += ',' + (FC.GPS_DATA.lon / 10000000);
|
||||
sample += ',' + FC.GPS_DATA.alt;
|
||||
sample += ',' + FC.GPS_DATA.speed;
|
||||
sample += ',' + FC.GPS_DATA.ground_course;
|
||||
break;
|
||||
case 'MSP_ANALOG':
|
||||
sample += ',' + ANALOG.voltage;
|
||||
sample += ',' + ANALOG.amperage;
|
||||
sample += ',' + ANALOG.mAhdrawn;
|
||||
sample += ',' + ANALOG.rssi;
|
||||
sample += ',' + FC.ANALOG.voltage;
|
||||
sample += ',' + FC.ANALOG.amperage;
|
||||
sample += ',' + FC.ANALOG.mAhdrawn;
|
||||
sample += ',' + FC.ANALOG.rssi;
|
||||
break;
|
||||
case 'MSP_RC':
|
||||
for (var chan = 0; chan < RC.active_channels; chan++) {
|
||||
sample += ',' + RC.channels[chan];
|
||||
for (var chan = 0; chan < FC.RC.active_channels; chan++) {
|
||||
sample += ',' + FC.RC.channels[chan];
|
||||
}
|
||||
break;
|
||||
case 'MSP_MOTOR':
|
||||
sample += ',' + MOTOR_DATA;
|
||||
sample += ',' + FC.MOTOR_DATA;
|
||||
break;
|
||||
case 'MSP_DEBUG':
|
||||
sample += ',' + SENSOR_DATA.debug;
|
||||
sample += ',' + FC.SENSOR_DATA.debug;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -65,7 +65,7 @@ TABS.motors.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function load_motor_telemetry_data() {
|
||||
if (MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor) {
|
||||
if (FC.MOTOR_CONFIG.use_dshot_telemetry || FC.MOTOR_CONFIG.use_esc_sensor) {
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR_TELEMETRY, false, false, load_mixer_config);
|
||||
} else {
|
||||
load_mixer_config();
|
||||
|
@ -81,7 +81,7 @@ TABS.motors.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// Get information from Betaflight
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
// BF 3.2.0+
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR_CONFIG, false, false, get_arm_status);
|
||||
} else {
|
||||
|
@ -90,13 +90,13 @@ TABS.motors.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function update_arm_status() {
|
||||
self.armed = bit_check(CONFIG.mode, 0);
|
||||
self.armed = bit_check(FC.CONFIG.mode, 0);
|
||||
}
|
||||
|
||||
function initSensorData() {
|
||||
for (var i = 0; i < 3; i++) {
|
||||
SENSOR_DATA.accelerometer[i] = 0;
|
||||
SENSOR_DATA.gyroscope[i] = 0;
|
||||
FC.SENSOR_DATA.accelerometer[i] = 0;
|
||||
FC.SENSOR_DATA.gyroscope[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -217,8 +217,8 @@ TABS.motors.initialize = function (callback) {
|
|||
function update_model(mixer) {
|
||||
var reverse = "";
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
reverse = MIXER_CONFIG.reverseMotorDir ? "_reversed" : "";
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
reverse = FC.MIXER_CONFIG.reverseMotorDir ? "_reversed" : "";
|
||||
}
|
||||
|
||||
$('.mixerPreview img').attr('src', './resources/motor_order/' + mixerList[mixer - 1].image + reverse + '.svg');
|
||||
|
@ -230,9 +230,9 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
update_arm_status();
|
||||
|
||||
self.feature3DEnabled = FEATURE_CONFIG.features.isEnabled('3D');
|
||||
self.feature3DEnabled = FC.FEATURE_CONFIG.features.isEnabled('3D');
|
||||
|
||||
if (PID_ADVANCED_CONFIG.fast_pwm_protocol >= TABS.configuration.DSHOT_PROTOCOL_MIN_VALUE) {
|
||||
if (FC.PID_ADVANCED_CONFIG.fast_pwm_protocol >= TABS.configuration.DSHOT_PROTOCOL_MIN_VALUE) {
|
||||
self.escProtocolIsDshot = true;
|
||||
} else {
|
||||
self.escProtocolIsDshot = false;
|
||||
|
@ -240,16 +240,16 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
$('#motorsEnableTestMode').prop('checked', false);
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.42.0") || !(MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor)) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.42.0") || !(FC.MOTOR_CONFIG.use_dshot_telemetry || FC.MOTOR_CONFIG.use_esc_sensor)) {
|
||||
$(".motor_testing .telemetry").hide();
|
||||
} else {
|
||||
// Hide telemetry from unused motors (to hide the tooltip in an empty blank space)
|
||||
for (let i = MOTOR_CONFIG.motor_count; i < MOTOR_DATA.length; i++) {
|
||||
for (let i = FC.MOTOR_CONFIG.motor_count; i < FC.MOTOR_DATA.length; i++) {
|
||||
$(".motor_testing .telemetry .motor-" + i).hide();
|
||||
}
|
||||
}
|
||||
|
||||
update_model(MIXER_CONFIG.mixer);
|
||||
update_model(FC.MIXER_CONFIG.mixer);
|
||||
|
||||
// Always start with default/empty sensor data array, clean slate all
|
||||
initSensorData();
|
||||
|
@ -360,16 +360,16 @@ TABS.motors.initialize = function (callback) {
|
|||
function update_accel_graph() {
|
||||
if (!accel_offset_established) {
|
||||
for (var i = 0; i < 3; i++) {
|
||||
accel_offset[i] = SENSOR_DATA.accelerometer[i] * -1;
|
||||
accel_offset[i] = FC.SENSOR_DATA.accelerometer[i] * -1;
|
||||
}
|
||||
|
||||
accel_offset_established = true;
|
||||
}
|
||||
|
||||
var accel_with_offset = [
|
||||
accel_offset[0] + SENSOR_DATA.accelerometer[0],
|
||||
accel_offset[1] + SENSOR_DATA.accelerometer[1],
|
||||
accel_offset[2] + SENSOR_DATA.accelerometer[2]
|
||||
accel_offset[0] + FC.SENSOR_DATA.accelerometer[0],
|
||||
accel_offset[1] + FC.SENSOR_DATA.accelerometer[1],
|
||||
accel_offset[2] + FC.SENSOR_DATA.accelerometer[2]
|
||||
];
|
||||
|
||||
updateGraphHelperSize(accel_helpers);
|
||||
|
@ -384,9 +384,9 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
function update_gyro_graph() {
|
||||
var gyro = [
|
||||
SENSOR_DATA.gyroscope[0],
|
||||
SENSOR_DATA.gyroscope[1],
|
||||
SENSOR_DATA.gyroscope[2]
|
||||
FC.SENSOR_DATA.gyroscope[0],
|
||||
FC.SENSOR_DATA.gyroscope[1],
|
||||
FC.SENSOR_DATA.gyroscope[2]
|
||||
];
|
||||
|
||||
updateGraphHelperSize(gyro_helpers);
|
||||
|
@ -437,9 +437,9 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
// Amperage
|
||||
function power_data_pull() {
|
||||
motor_voltage_e.text(i18n.getMessage('motorsVoltageValue', [ANALOG.voltage]));
|
||||
motor_mah_drawing_e.text(i18n.getMessage('motorsADrawingValue', [ANALOG.amperage.toFixed(2)]));
|
||||
motor_mah_drawn_e.text(i18n.getMessage('motorsmAhDrawnValue', [ANALOG.mAhdrawn]));
|
||||
motor_voltage_e.text(i18n.getMessage('motorsVoltageValue', [FC.ANALOG.voltage]));
|
||||
motor_mah_drawing_e.text(i18n.getMessage('motorsADrawingValue', [FC.ANALOG.amperage.toFixed(2)]));
|
||||
motor_mah_drawn_e.text(i18n.getMessage('motorsmAhDrawnValue', [FC.ANALOG.mAhdrawn]));
|
||||
|
||||
}
|
||||
GUI.interval_add('motors_power_data_pull_slow', power_data_pull, 250, true); // 4 fps
|
||||
|
@ -450,7 +450,7 @@ TABS.motors.initialize = function (callback) {
|
|||
accel_offset_established = false;
|
||||
});
|
||||
|
||||
var number_of_valid_outputs = (MOTOR_DATA.indexOf(0) > -1) ? MOTOR_DATA.indexOf(0) : 8;
|
||||
var number_of_valid_outputs = (FC.MOTOR_DATA.indexOf(0) > -1) ? FC.MOTOR_DATA.indexOf(0) : 8;
|
||||
var rangeMin;
|
||||
var rangeMax;
|
||||
var neutral3d;
|
||||
|
@ -459,11 +459,11 @@ TABS.motors.initialize = function (callback) {
|
|||
rangeMax = self.DSHOT_MAX_VALUE;
|
||||
neutral3d = self.DSHOT_3D_NEUTRAL;
|
||||
} else {
|
||||
rangeMin = MOTOR_CONFIG.mincommand;
|
||||
rangeMax = MOTOR_CONFIG.maxthrottle;
|
||||
rangeMin = FC.MOTOR_CONFIG.mincommand;
|
||||
rangeMax = FC.MOTOR_CONFIG.maxthrottle;
|
||||
//Arbitrary sanity checks
|
||||
//Note: values may need to be revisited
|
||||
neutral3d = (MOTOR_3D_CONFIG.neutral > 1575 || MOTOR_3D_CONFIG.neutral < 1425) ? 1500 : MOTOR_3D_CONFIG.neutral;
|
||||
neutral3d = (FC.MOTOR_3D_CONFIG.neutral > 1575 || FC.MOTOR_3D_CONFIG.neutral < 1425) ? 1500 : FC.MOTOR_3D_CONFIG.neutral;
|
||||
}
|
||||
|
||||
var motors_wrapper = $('.motors .bar-wrapper'),
|
||||
|
@ -579,11 +579,11 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
for (var i = 0; i < number_of_valid_outputs; i++) {
|
||||
if (!self.feature3DEnabled) {
|
||||
if (MOTOR_DATA[i] > rangeMin) {
|
||||
if (FC.MOTOR_DATA[i] > rangeMin) {
|
||||
motors_running = true;
|
||||
}
|
||||
} else {
|
||||
if ((MOTOR_DATA[i] < MOTOR_3D_CONFIG.deadband3d_low) || (MOTOR_DATA[i] > MOTOR_3D_CONFIG.deadband3d_high)) {
|
||||
if ((FC.MOTOR_DATA[i] < FC.MOTOR_3D_CONFIG.deadband3d_low) || (FC.MOTOR_DATA[i] > FC.MOTOR_3D_CONFIG.deadband3d_high)) {
|
||||
motors_running = true;
|
||||
}
|
||||
}
|
||||
|
@ -596,12 +596,12 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
var sliders = $('div.sliders input:not(.master)');
|
||||
|
||||
var master_value = MOTOR_DATA[0];
|
||||
for (var i = 0; i < MOTOR_DATA.length; i++) {
|
||||
if (MOTOR_DATA[i] > 0) {
|
||||
sliders.eq(i).val(MOTOR_DATA[i]);
|
||||
var master_value = FC.MOTOR_DATA[0];
|
||||
for (var i = 0; i < FC.MOTOR_DATA.length; i++) {
|
||||
if (FC.MOTOR_DATA[i] > 0) {
|
||||
sliders.eq(i).val(FC.MOTOR_DATA[i]);
|
||||
|
||||
if (master_value != MOTOR_DATA[i]) {
|
||||
if (master_value != FC.MOTOR_DATA[i]) {
|
||||
master_value = false;
|
||||
}
|
||||
}
|
||||
|
@ -629,7 +629,7 @@ TABS.motors.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function get_motor_telemetry_data() {
|
||||
if (MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor) {
|
||||
if (FC.MOTOR_CONFIG.use_dshot_telemetry || FC.MOTOR_CONFIG.use_esc_sensor) {
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR_TELEMETRY, false, false, get_servo_data);
|
||||
} else {
|
||||
get_servo_data();
|
||||
|
@ -646,8 +646,8 @@ TABS.motors.initialize = function (callback) {
|
|||
var previousArmState = self.armed;
|
||||
var block_height = $('div.m-block:first').height();
|
||||
|
||||
for (var i = 0; i < MOTOR_DATA.length; i++) {
|
||||
var motorValue = MOTOR_DATA[i];
|
||||
for (var i = 0; i < FC.MOTOR_DATA.length; i++) {
|
||||
var motorValue = FC.MOTOR_DATA[i];
|
||||
var barHeight = motorValue - rangeMin,
|
||||
margin_top = block_height - (barHeight * (block_height / full_block_scale)).clamp(0, block_height),
|
||||
height = (barHeight * (block_height / full_block_scale)).clamp(0, block_height),
|
||||
|
@ -660,12 +660,12 @@ TABS.motors.initialize = function (callback) {
|
|||
'background-color' : 'rgba(255,187,0,1.'+ color +')'
|
||||
});
|
||||
|
||||
if (i < MOTOR_CONFIG.motor_count && (MOTOR_CONFIG.use_dshot_telemetry || MOTOR_CONFIG.use_esc_sensor)) {
|
||||
if (i < FC.MOTOR_CONFIG.motor_count && (FC.MOTOR_CONFIG.use_dshot_telemetry || FC.MOTOR_CONFIG.use_esc_sensor)) {
|
||||
|
||||
const MAX_INVALID_PERCENT = 100,
|
||||
MAX_VALUE_SIZE = 6;
|
||||
|
||||
let rpmMotorValue = MOTOR_TELEMETRY_DATA.rpm[i];
|
||||
let rpmMotorValue = FC.MOTOR_TELEMETRY_DATA.rpm[i];
|
||||
|
||||
// Reduce the size of the value if too big
|
||||
if (rpmMotorValue > 999999) {
|
||||
|
@ -676,9 +676,9 @@ TABS.motors.initialize = function (callback) {
|
|||
let telemetryText = i18n.getMessage('motorsRPM', {motorsRpmValue: rpmMotorValue});
|
||||
|
||||
|
||||
if (MOTOR_CONFIG.use_dshot_telemetry) {
|
||||
if (FC.MOTOR_CONFIG.use_dshot_telemetry) {
|
||||
|
||||
let invalidPercent = MOTOR_TELEMETRY_DATA.invalidPercent[i];
|
||||
let invalidPercent = FC.MOTOR_TELEMETRY_DATA.invalidPercent[i];
|
||||
|
||||
let classError = (invalidPercent > MAX_INVALID_PERCENT) ? "warning" : "";
|
||||
invalidPercent = (invalidPercent / 100).toFixed(2).toString().padStart(MAX_VALUE_SIZE);
|
||||
|
@ -688,9 +688,9 @@ TABS.motors.initialize = function (callback) {
|
|||
telemetryText += "</span>";
|
||||
}
|
||||
|
||||
if (MOTOR_CONFIG.use_esc_sensor) {
|
||||
if (FC.MOTOR_CONFIG.use_esc_sensor) {
|
||||
|
||||
let escTemperature = MOTOR_TELEMETRY_DATA.temperature[i];
|
||||
let escTemperature = FC.MOTOR_TELEMETRY_DATA.temperature[i];
|
||||
|
||||
telemetryText += "<br>";
|
||||
escTemperature = escTemperature.toString().padStart(MAX_VALUE_SIZE);
|
||||
|
@ -704,13 +704,13 @@ TABS.motors.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// servo indicators are still using old (not flexible block scale), it will be changed in the future accordingly
|
||||
for (var i = 0; i < SERVO_DATA.length; i++) {
|
||||
var data = SERVO_DATA[i] - 1000,
|
||||
for (var i = 0; i < FC.SERVO_DATA.length; i++) {
|
||||
var data = FC.SERVO_DATA[i] - 1000,
|
||||
margin_top = block_height - (data * (block_height / 1000)).clamp(0, block_height),
|
||||
height = (data * (block_height / 1000)).clamp(0, block_height),
|
||||
color = parseInt(data * 0.009);
|
||||
|
||||
$('.servo-' + i + ' .label', servos_wrapper).text(SERVO_DATA[i]);
|
||||
$('.servo-' + i + ' .label', servos_wrapper).text(FC.SERVO_DATA[i]);
|
||||
$('.servo-' + i + ' .indicator', servos_wrapper).css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgba(255,187,0,1'+ color +')'});
|
||||
}
|
||||
//keep the following here so at least we get a visual cue of our motor setup
|
||||
|
|
|
@ -61,7 +61,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
i18n.localizePage();
|
||||
|
||||
var
|
||||
dataflashPresent = DATAFLASH.totalSize > 0,
|
||||
dataflashPresent = FC.DATAFLASH.totalSize > 0,
|
||||
blackboxSupport;
|
||||
|
||||
/*
|
||||
|
@ -69,7 +69,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
*
|
||||
* The best we can do on those targets is check the BLACKBOX feature bit to identify support for Blackbox instead.
|
||||
*/
|
||||
if ((BLACKBOX.supported || DATAFLASH.supported) && (semver.gte(CONFIG.apiVersion, "1.33.0") || FEATURE_CONFIG.features.isEnabled('BLACKBOX'))) {
|
||||
if ((FC.BLACKBOX.supported || FC.DATAFLASH.supported) && (semver.gte(FC.CONFIG.apiVersion, "1.33.0") || FC.FEATURE_CONFIG.features.isEnabled('BLACKBOX'))) {
|
||||
blackboxSupport = 'yes';
|
||||
} else {
|
||||
blackboxSupport = 'no';
|
||||
|
@ -77,10 +77,10 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
|
||||
$(".tab-onboard_logging")
|
||||
.addClass("serial-supported")
|
||||
.toggleClass("dataflash-supported", DATAFLASH.supported)
|
||||
.toggleClass("dataflash-supported", FC.DATAFLASH.supported)
|
||||
.toggleClass("dataflash-present", dataflashPresent)
|
||||
.toggleClass("sdcard-supported", SDCARD.supported)
|
||||
.toggleClass("blackbox-config-supported", BLACKBOX.supported)
|
||||
.toggleClass("sdcard-supported", FC.SDCARD.supported)
|
||||
.toggleClass("blackbox-config-supported", FC.BLACKBOX.supported)
|
||||
|
||||
.toggleClass("blackbox-supported", blackboxSupport === 'yes')
|
||||
.toggleClass("blackbox-maybe-supported", blackboxSupport === 'maybe')
|
||||
|
@ -102,20 +102,20 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
var loggingRatesSelect = $(".blackboxRate select");
|
||||
var debugModeSelect = $(".blackboxDebugMode select");
|
||||
|
||||
if (BLACKBOX.supported) {
|
||||
if (FC.BLACKBOX.supported) {
|
||||
$(".tab-onboard_logging a.save-settings").click(function() {
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_44)) {
|
||||
BLACKBOX.blackboxSampleRate = parseInt(loggingRatesSelect.val(), 10);
|
||||
} else if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
BLACKBOX.blackboxPDenom = parseInt(loggingRatesSelect.val(), 10);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_44)) {
|
||||
FC.BLACKBOX.blackboxSampleRate = parseInt(loggingRatesSelect.val(), 10);
|
||||
} else if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
FC.BLACKBOX.blackboxPDenom = parseInt(loggingRatesSelect.val(), 10);
|
||||
} else {
|
||||
var rate = loggingRatesSelect.val().split('/');
|
||||
BLACKBOX.blackboxRateNum = parseInt(rate[0], 10);
|
||||
BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10);
|
||||
FC.BLACKBOX.blackboxRateNum = parseInt(rate[0], 10);
|
||||
FC.BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10);
|
||||
}
|
||||
BLACKBOX.blackboxDevice = parseInt(deviceSelect.val(), 10);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
PID_ADVANCED_CONFIG.debugMode = parseInt(debugModeSelect.val());
|
||||
FC.BLACKBOX.blackboxDevice = parseInt(deviceSelect.val(), 10);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
FC.PID_ADVANCED_CONFIG.debugMode = parseInt(debugModeSelect.val());
|
||||
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, save_to_eeprom);
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_SET_BLACKBOX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BLACKBOX_CONFIG), false, save_to_eeprom);
|
||||
|
@ -134,8 +134,8 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
}).change();
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
if ((SDCARD.supported && deviceSelect.val() == 2) || (DATAFLASH.supported && deviceSelect.val() == 1)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
if ((FC.SDCARD.supported && deviceSelect.val() == 2) || (FC.DATAFLASH.supported && deviceSelect.val() == 1)) {
|
||||
|
||||
$(".tab-onboard_logging")
|
||||
.toggleClass("msc-supported", true);
|
||||
|
@ -144,7 +144,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
analytics.sendEvent(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, 'RebootMsc');
|
||||
|
||||
var buffer = [];
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
if (GUI.operating_system === "Linux") {
|
||||
// Reboot into MSC using UTC time offset instead of user timezone
|
||||
// Linux seems to expect that the FAT file system timestamps are UTC based
|
||||
|
@ -169,26 +169,26 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
function populateDevices(deviceSelect) {
|
||||
deviceSelect.empty();
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
deviceSelect.append('<option value="0">' + i18n.getMessage('blackboxLoggingNone') + '</option>');
|
||||
if (DATAFLASH.supported) {
|
||||
if (FC.DATAFLASH.supported) {
|
||||
deviceSelect.append('<option value="1">' + i18n.getMessage('blackboxLoggingFlash') + '</option>');
|
||||
}
|
||||
if (SDCARD.supported) {
|
||||
if (FC.SDCARD.supported) {
|
||||
deviceSelect.append('<option value="2">' + i18n.getMessage('blackboxLoggingSdCard') + '</option>');
|
||||
}
|
||||
deviceSelect.append('<option value="3">' + i18n.getMessage('blackboxLoggingSerial') + '</option>');
|
||||
} else {
|
||||
deviceSelect.append('<option value="0">' + i18n.getMessage('blackboxLoggingSerial') + '</option>');
|
||||
if (DATAFLASH.ready) {
|
||||
if (FC.DATAFLASH.ready) {
|
||||
deviceSelect.append('<option value="1">' + i18n.getMessage('blackboxLoggingFlash') + '</option>');
|
||||
}
|
||||
if (SDCARD.supported) {
|
||||
if (FC.SDCARD.supported) {
|
||||
deviceSelect.append('<option value="2">' + i18n.getMessage('blackboxLoggingSdCard') + '</option>');
|
||||
}
|
||||
}
|
||||
|
||||
deviceSelect.val(BLACKBOX.blackboxDevice);
|
||||
deviceSelect.val(FC.BLACKBOX.blackboxDevice);
|
||||
}
|
||||
|
||||
function populateLoggingRates(loggingRatesSelect) {
|
||||
|
@ -197,20 +197,20 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
let loggingRates = [];
|
||||
|
||||
let pidRate;
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
pidRate = CONFIG.sampleRateHz / PID_ADVANCED_CONFIG.pid_process_denom;
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
pidRate = FC.CONFIG.sampleRateHz / FC.PID_ADVANCED_CONFIG.pid_process_denom;
|
||||
|
||||
} else {
|
||||
|
||||
let pidRateBase = 8000;
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.25.0") && semver.lt(CONFIG.apiVersion, "1.41.0") && PID_ADVANCED_CONFIG.gyroUse32kHz !== 0) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.25.0") && semver.lt(FC.CONFIG.apiVersion, "1.41.0") && FC.PID_ADVANCED_CONFIG.gyroUse32kHz !== 0) {
|
||||
pidRateBase = 32000;
|
||||
}
|
||||
pidRate = pidRateBase / PID_ADVANCED_CONFIG.gyro_sync_denom / PID_ADVANCED_CONFIG.pid_process_denom;
|
||||
pidRate = pidRateBase / FC.PID_ADVANCED_CONFIG.gyro_sync_denom / FC.PID_ADVANCED_CONFIG.pid_process_denom;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_44)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_44)) {
|
||||
const sampleRateNum=5;
|
||||
for (let i = 0; i < sampleRateNum; i++) {
|
||||
let loggingFrequency = Math.round(pidRate / (2**i));
|
||||
|
@ -221,8 +221,8 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
loggingRatesSelect.append(`<option value="${i}">1/${2**i} (${loggingFrequency}${loggingFrequencyUnit})</option>`);
|
||||
}
|
||||
loggingRatesSelect.val(BLACKBOX.blackboxSampleRate);
|
||||
} else if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
loggingRatesSelect.val(FC.BLACKBOX.blackboxSampleRate);
|
||||
} else if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
loggingRates = [
|
||||
{text: "Disabled", hz: 0, p_denom: 0},
|
||||
{text: "500 Hz", hz: 500, p_denom: 16},
|
||||
|
@ -241,7 +241,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
|
||||
loggingRatesSelect.val(BLACKBOX.blackboxPDenom);
|
||||
loggingRatesSelect.val(FC.BLACKBOX.blackboxPDenom);
|
||||
}
|
||||
else {
|
||||
loggingRates = [
|
||||
|
@ -271,14 +271,14 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
+ loggingRate + loggingRateUnit + ' (' + Math.round(loggingRates[i].num / loggingRates[i].denom * 100) + '%)</option>');
|
||||
|
||||
}
|
||||
loggingRatesSelect.val(BLACKBOX.blackboxRateNum + '/' + BLACKBOX.blackboxRateDenom);
|
||||
loggingRatesSelect.val(FC.BLACKBOX.blackboxRateNum + '/' + FC.BLACKBOX.blackboxRateDenom);
|
||||
}
|
||||
}
|
||||
|
||||
function populateDebugModes(debugModeSelect) {
|
||||
var debugModes = [];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
$('.blackboxDebugMode').show();
|
||||
|
||||
debugModes = [
|
||||
|
@ -344,7 +344,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
{text: "FF_INTERPOLATED"},
|
||||
];
|
||||
|
||||
for (let i = 0; i < PID_ADVANCED_CONFIG.debugModeCount; i++) {
|
||||
for (let i = 0; i < FC.PID_ADVANCED_CONFIG.debugModeCount; i++) {
|
||||
if (i < debugModes.length) {
|
||||
debugModeSelect.append(new Option(debugModes[i].text, i));
|
||||
} else {
|
||||
|
@ -352,7 +352,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
}
|
||||
|
||||
debugModeSelect.val(PID_ADVANCED_CONFIG.debugMode);
|
||||
debugModeSelect.val(FC.PID_ADVANCED_CONFIG.debugMode);
|
||||
} else {
|
||||
$('.blackboxDebugMode').hide();
|
||||
}
|
||||
|
@ -399,23 +399,23 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function update_html() {
|
||||
var dataflashPresent = DATAFLASH.totalSize > 0;
|
||||
var dataflashPresent = FC.DATAFLASH.totalSize > 0;
|
||||
|
||||
update_bar_width($(".tab-onboard_logging .dataflash-used"), DATAFLASH.usedSize, DATAFLASH.totalSize, i18n.getMessage('dataflashUsedSpace'), false);
|
||||
update_bar_width($(".tab-onboard_logging .dataflash-free"), DATAFLASH.totalSize - DATAFLASH.usedSize, DATAFLASH.totalSize, i18n.getMessage('dataflashFreeSpace'), false);
|
||||
update_bar_width($(".tab-onboard_logging .dataflash-used"), FC.DATAFLASH.usedSize, FC.DATAFLASH.totalSize, i18n.getMessage('dataflashUsedSpace'), false);
|
||||
update_bar_width($(".tab-onboard_logging .dataflash-free"), FC.DATAFLASH.totalSize - FC.DATAFLASH.usedSize, FC.DATAFLASH.totalSize, i18n.getMessage('dataflashFreeSpace'), false);
|
||||
|
||||
update_bar_width($(".tab-onboard_logging .sdcard-other"), SDCARD.totalSizeKB - SDCARD.freeSizeKB, SDCARD.totalSizeKB, i18n.getMessage('dataflashUnavSpace'), true);
|
||||
update_bar_width($(".tab-onboard_logging .sdcard-free"), SDCARD.freeSizeKB, SDCARD.totalSizeKB, i18n.getMessage('dataflashLogsSpace'), true);
|
||||
update_bar_width($(".tab-onboard_logging .sdcard-other"), FC.SDCARD.totalSizeKB - FC.SDCARD.freeSizeKB, FC.SDCARD.totalSizeKB, i18n.getMessage('dataflashUnavSpace'), true);
|
||||
update_bar_width($(".tab-onboard_logging .sdcard-free"), FC.SDCARD.freeSizeKB, FC.SDCARD.totalSizeKB, i18n.getMessage('dataflashLogsSpace'), true);
|
||||
|
||||
$(".btn a.erase-flash, .btn a.save-flash").toggleClass("disabled", DATAFLASH.usedSize === 0);
|
||||
$(".btn a.erase-flash, .btn a.save-flash").toggleClass("disabled", FC.DATAFLASH.usedSize === 0);
|
||||
|
||||
$(".tab-onboard_logging")
|
||||
.toggleClass("sdcard-error", SDCARD.state === MSP.SDCARD_STATE_FATAL)
|
||||
.toggleClass("sdcard-initializing", SDCARD.state === MSP.SDCARD_STATE_CARD_INIT || SDCARD.state === MSP.SDCARD_STATE_FS_INIT)
|
||||
.toggleClass("sdcard-ready", SDCARD.state === MSP.SDCARD_STATE_READY);
|
||||
.toggleClass("sdcard-error", FC.SDCARD.state === MSP.SDCARD_STATE_FATAL)
|
||||
.toggleClass("sdcard-initializing", FC.SDCARD.state === MSP.SDCARD_STATE_CARD_INIT || FC.SDCARD.state === MSP.SDCARD_STATE_FS_INIT)
|
||||
.toggleClass("sdcard-ready", FC.SDCARD.state === MSP.SDCARD_STATE_READY);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
var mscIsReady = dataflashPresent || (SDCARD.state === MSP.SDCARD_STATE_READY);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
var mscIsReady = dataflashPresent || (FC.SDCARD.state === MSP.SDCARD_STATE_READY);
|
||||
$(".tab-onboard_logging")
|
||||
.toggleClass("msc-not-ready", !mscIsReady);
|
||||
|
||||
|
@ -427,7 +427,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
|
||||
var loggingStatus
|
||||
switch (SDCARD.state) {
|
||||
switch (FC.SDCARD.state) {
|
||||
case MSP.SDCARD_STATE_NOT_PRESENT:
|
||||
$(".sdcard-status").text(i18n.getMessage('sdcardStatusNoCard'));
|
||||
loggingStatus = 'SdCard: NotPresent';
|
||||
|
@ -449,16 +449,16 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
loggingStatus = 'SdCard: FsInit';
|
||||
break;
|
||||
default:
|
||||
$(".sdcard-status").text(i18n.getMessage('sdcardStatusUnknown',[SDCARD.state]));
|
||||
$(".sdcard-status").text(i18n.getMessage('sdcardStatusUnknown',[FC.SDCARD.state]));
|
||||
}
|
||||
|
||||
if (dataflashPresent && SDCARD.state === MSP.SDCARD_STATE_NOT_PRESENT) {
|
||||
if (dataflashPresent && FC.SDCARD.state === MSP.SDCARD_STATE_NOT_PRESENT) {
|
||||
loggingStatus = 'Dataflash';
|
||||
analytics.setFlightControllerData(analytics.DATA.LOG_SIZE, DATAFLASH.usedSize);
|
||||
analytics.setFlightControllerData(analytics.DATA.LOG_SIZE, FC.DATAFLASH.usedSize);
|
||||
}
|
||||
analytics.setFlightControllerData(analytics.DATA.LOGGING_STATUS, loggingStatus);
|
||||
|
||||
if (SDCARD.supported && !sdcardTimer) {
|
||||
if (FC.SDCARD.supported && !sdcardTimer) {
|
||||
// Poll for changes in SD card status
|
||||
sdcardTimer = setTimeout(function() {
|
||||
sdcardTimer = false;
|
||||
|
@ -514,7 +514,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
function flash_save_begin() {
|
||||
if (GUI.connected_to) {
|
||||
if (FC.boardHasVcp()) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) {
|
||||
self.blockSize = self.VCP_BLOCK_SIZE;
|
||||
} else {
|
||||
self.blockSize = self.VCP_BLOCK_SIZE_3_0;
|
||||
|
@ -525,7 +525,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
|
||||
// Begin by refreshing the occupied size in case it changed while the tab was open
|
||||
flash_update_summary(function() {
|
||||
var maxBytes = DATAFLASH.usedSize;
|
||||
var maxBytes = FC.DATAFLASH.usedSize;
|
||||
|
||||
prepare_file(function(fileWriter) {
|
||||
var nextAddress = 0;
|
||||
|
@ -637,7 +637,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
function poll_for_erase_completion() {
|
||||
flash_update_summary(function() {
|
||||
if (CONFIGURATOR.connectionValid && !eraseCancelled) {
|
||||
if (DATAFLASH.ready) {
|
||||
if (FC.DATAFLASH.ready) {
|
||||
$(".dataflash-confirm-erase")[0].close();
|
||||
} else {
|
||||
setTimeout(poll_for_erase_completion, 500);
|
||||
|
|
|
@ -70,7 +70,7 @@ SYM.loadSymbols = function() {
|
|||
* - Symbols used in this versions
|
||||
* - That were moved or didn't exist in the font file
|
||||
*/
|
||||
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
SYM.AH_CENTER_LINE = 0x26;
|
||||
SYM.AH_CENTER = 0x7E;
|
||||
SYM.AH_CENTER_LINE_RIGHT = 0x27;
|
||||
|
@ -347,16 +347,16 @@ OSD.generateTemperaturePreview = function (osd_data, temperature) {
|
|||
|
||||
OSD.generateCraftName = function (osd_data) {
|
||||
var preview = 'CRAFT_NAME';
|
||||
if (CONFIG.name != '') {
|
||||
preview = CONFIG.name.toUpperCase();
|
||||
if (FC.CONFIG.name != '') {
|
||||
preview = FC.CONFIG.name.toUpperCase();
|
||||
}
|
||||
return preview;
|
||||
}
|
||||
|
||||
OSD.generateDisplayName = function(osd_data) {
|
||||
var preview = 'DISPLAY_NAME';
|
||||
if (CONFIG.displayName != '')
|
||||
preview = CONFIG.displayName.toUpperCase();
|
||||
if (FC.CONFIG.displayName != '')
|
||||
preview = FC.CONFIG.displayName.toUpperCase();
|
||||
return preview;
|
||||
}
|
||||
|
||||
|
@ -523,7 +523,7 @@ OSD.loadDisplayFields = function() {
|
|||
},
|
||||
draw_order: 40,
|
||||
positionable: function () {
|
||||
return semver.gte(CONFIG.apiVersion, "1.39.0") ? true : false;
|
||||
return semver.gte(FC.CONFIG.apiVersion, "1.39.0") ? true : false;
|
||||
},
|
||||
preview: function () {
|
||||
return FONT.symbol(SYM.AH_CENTER_LINE) + FONT.symbol(SYM.AH_CENTER) + FONT.symbol(SYM.AH_CENTER_LINE_RIGHT);
|
||||
|
@ -542,7 +542,7 @@ OSD.loadDisplayFields = function() {
|
|||
},
|
||||
draw_order: 10,
|
||||
positionable: function () {
|
||||
return semver.gte(CONFIG.apiVersion, "1.39.0") ? true : false;
|
||||
return semver.gte(FC.CONFIG.apiVersion, "1.39.0") ? true : false;
|
||||
},
|
||||
preview: function () {
|
||||
var artificialHorizon = new Array();
|
||||
|
@ -579,7 +579,7 @@ OSD.loadDisplayFields = function() {
|
|||
},
|
||||
draw_order: 50,
|
||||
positionable: function () {
|
||||
return semver.gte(CONFIG.apiVersion, "1.39.0") ? true : false;
|
||||
return semver.gte(FC.CONFIG.apiVersion, "1.39.0") ? true : false;
|
||||
},
|
||||
preview: function (fieldPosition) {
|
||||
|
||||
|
@ -613,7 +613,7 @@ OSD.loadDisplayFields = function() {
|
|||
draw_order: 130,
|
||||
positionable: true,
|
||||
preview: function () {
|
||||
return semver.gte(CONFIG.apiVersion, "1.36.0") ? ' 42.00' + FONT.symbol(SYM.AMP) : FONT.symbol(SYM.AMP) + '42.0';
|
||||
return semver.gte(FC.CONFIG.apiVersion, "1.36.0") ? ' 42.00' + FONT.symbol(SYM.AMP) : FONT.symbol(SYM.AMP) + '42.0';
|
||||
}
|
||||
},
|
||||
MAH_DRAWN: {
|
||||
|
@ -624,7 +624,7 @@ OSD.loadDisplayFields = function() {
|
|||
draw_order: 140,
|
||||
positionable: true,
|
||||
preview: function () {
|
||||
return semver.gte(CONFIG.apiVersion, "1.36.0") ? ' 690' + FONT.symbol(SYM.MAH) : FONT.symbol(SYM.MAH) + '690';
|
||||
return semver.gte(FC.CONFIG.apiVersion, "1.36.0") ? ' 690' + FONT.symbol(SYM.MAH) : FONT.symbol(SYM.MAH) + '690';
|
||||
}
|
||||
},
|
||||
CRAFT_NAME: {
|
||||
|
@ -754,7 +754,7 @@ OSD.loadDisplayFields = function() {
|
|||
draw_order: 200,
|
||||
positionable: true,
|
||||
preview: function () {
|
||||
return semver.gte(CONFIG.apiVersion, "1.36.0") ? ' 142W' : '142W';
|
||||
return semver.gte(FC.CONFIG.apiVersion, "1.36.0") ? ' 142W' : '142W';
|
||||
}
|
||||
},
|
||||
PID_RATE_PROFILE: {
|
||||
|
@ -1434,7 +1434,7 @@ OSD.searchLimitsElement = function (arrayElements) {
|
|||
OSD.chooseFields = function () {
|
||||
var F = OSD.ALL_DISPLAY_FIELDS;
|
||||
// version 3.0.1
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = [
|
||||
F.RSSI_VALUE,
|
||||
F.MAIN_BATT_VOLTAGE,
|
||||
|
@ -1443,7 +1443,7 @@ OSD.chooseFields = function () {
|
|||
F.HORIZON_SIDEBARS
|
||||
];
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.ONTIME,
|
||||
F.FLYTIME
|
||||
|
@ -1466,31 +1466,31 @@ OSD.chooseFields = function () {
|
|||
F.GPS_SATS,
|
||||
F.ALTITUDE
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.PID_ROLL,
|
||||
F.PID_PITCH,
|
||||
F.PID_YAW,
|
||||
F.POWER
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.32.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.32.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.PID_RATE_PROFILE,
|
||||
semver.gte(CONFIG.apiVersion, "1.36.0") ? F.WARNINGS : F.BATTERY_WARNING,
|
||||
semver.gte(FC.CONFIG.apiVersion, "1.36.0") ? F.WARNINGS : F.BATTERY_WARNING,
|
||||
F.AVG_CELL_VOLTAGE
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.34.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.34.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.GPS_LON,
|
||||
F.GPS_LAT,
|
||||
F.DEBUG
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.35.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.35.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.PITCH_ANGLE,
|
||||
F.ROLL_ANGLE
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.MAIN_BATT_USAGE,
|
||||
F.DISARMED,
|
||||
|
@ -1502,22 +1502,22 @@ OSD.chooseFields = function () {
|
|||
F.ESC_TEMPERATURE,
|
||||
F.ESC_RPM
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.REMAINING_TIME_ESTIMATE,
|
||||
F.RTC_DATE_TIME,
|
||||
F.ADJUSTMENT_RANGE,
|
||||
F.CORE_TEMPERATURE
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.39.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.ANTI_GRAVITY
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.G_FORCE,
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.MOTOR_DIAG,
|
||||
F.LOG_STATUS,
|
||||
|
@ -1529,14 +1529,14 @@ OSD.chooseFields = function () {
|
|||
F.DISPLAY_NAME,
|
||||
F.ESC_RPM_FREQ
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.RATE_PROFILE_NAME,
|
||||
F.PID_PROFILE_NAME,
|
||||
F.OSD_PROFILE_NAME,
|
||||
F.RSSI_DBM_VALUE,
|
||||
]);
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.RC_CHANNELS,
|
||||
F.CAMERA_FRAME,
|
||||
|
@ -1587,7 +1587,7 @@ OSD.chooseFields = function () {
|
|||
// that needs to be implemented here as well. Simply appending new stats does not
|
||||
// require a completely new section for the version - only reordering.
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.39.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
OSD.constants.STATISTIC_FIELDS = [
|
||||
F.MAX_SPEED,
|
||||
F.MIN_BATTERY,
|
||||
|
@ -1602,7 +1602,7 @@ OSD.chooseFields = function () {
|
|||
F.MAX_DISTANCE,
|
||||
F.BLACKBOX_LOG_NUMBER
|
||||
];
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
OSD.constants.STATISTIC_FIELDS = OSD.constants.STATISTIC_FIELDS.concat([
|
||||
F.RTC_DATE_TIME
|
||||
]);
|
||||
|
@ -1624,7 +1624,7 @@ OSD.chooseFields = function () {
|
|||
F.BLACKBOX,
|
||||
F.BLACKBOX_LOG_NUMBER
|
||||
];
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
OSD.constants.STATISTIC_FIELDS = OSD.constants.STATISTIC_FIELDS.concat([
|
||||
F.MAX_G_FORCE,
|
||||
F.MAX_ESC_TEMP,
|
||||
|
@ -1634,7 +1634,7 @@ OSD.chooseFields = function () {
|
|||
F.MAX_FFT
|
||||
]);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
OSD.constants.STATISTIC_FIELDS = OSD.constants.STATISTIC_FIELDS.concat([
|
||||
F.TOTAL_FLIGHTS,
|
||||
F.TOTAL_FLIGHT_TIME,
|
||||
|
@ -1655,14 +1655,14 @@ OSD.chooseFields = function () {
|
|||
F.VISUAL_BEEPER,
|
||||
F.CRASH_FLIP_MODE
|
||||
];
|
||||
if (semver.gte(CONFIG.apiVersion, "1.39.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
OSD.constants.WARNINGS = OSD.constants.WARNINGS.concat([
|
||||
F.ESC_FAIL,
|
||||
F.CORE_TEMPERATURE,
|
||||
F.RC_SMOOTHING_FAILURE
|
||||
]);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
OSD.constants.WARNINGS = OSD.constants.WARNINGS.concat([
|
||||
F.FAILSAFE,
|
||||
F.LAUNCH_CONTROL,
|
||||
|
@ -1676,7 +1676,7 @@ OSD.chooseFields = function () {
|
|||
'TOTAL_ARMED_TIME',
|
||||
'LAST_ARMED_TIME'
|
||||
];
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
OSD.constants.TIMER_TYPES = OSD.constants.TIMER_TYPES.concat([
|
||||
'ON_ARM_TIME'
|
||||
]);
|
||||
|
@ -1686,7 +1686,7 @@ OSD.chooseFields = function () {
|
|||
F.RSSI_DBM,
|
||||
]);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
OSD.constants.WARNINGS = OSD.constants.WARNINGS.concat([
|
||||
F.OVER_CAP,
|
||||
]);
|
||||
|
@ -1744,7 +1744,7 @@ OSD.msp = {
|
|||
var default_position = typeof (c.default_position) === 'function' ? c.default_position() : c.default_position;
|
||||
|
||||
display_item.positionable = positionable;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
// size * y + x
|
||||
display_item.position = positionable ? FONT.constants.SIZES.LINE * ((bits >> 5) & 0x001F) + (bits & 0x001F) : default_position;
|
||||
|
||||
|
@ -1772,7 +1772,7 @@ OSD.msp = {
|
|||
position: function (display_item) {
|
||||
var isVisible = display_item.isVisible;
|
||||
var position = display_item.position;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
|
||||
let packed_visible = 0;
|
||||
for (let osd_profile = 0; osd_profile < OSD.getNumberOfProfiles(); osd_profile++) {
|
||||
|
@ -1790,19 +1790,19 @@ OSD.msp = {
|
|||
},
|
||||
encodeOther: function () {
|
||||
var result = [-1, OSD.data.video_system];
|
||||
if (OSD.data.state.haveOsdFeature && semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (OSD.data.state.haveOsdFeature && semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
result.push8(OSD.data.unit_mode);
|
||||
// watch out, order matters! match the firmware
|
||||
result.push8(OSD.data.alarms.rssi.value);
|
||||
result.push16(OSD.data.alarms.cap.value);
|
||||
if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
result.push16(OSD.data.alarms.time.value);
|
||||
} else {
|
||||
// This value is unused by the firmware with configurable timers
|
||||
result.push16(0);
|
||||
}
|
||||
result.push16(OSD.data.alarms.alt.value);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
var warningFlags = 0;
|
||||
for (var i = 0; i < OSD.data.warnings.length; i++) {
|
||||
if (OSD.data.warnings[i].enabled) {
|
||||
|
@ -1811,7 +1811,7 @@ OSD.msp = {
|
|||
}
|
||||
console.log(warningFlags);
|
||||
result.push16(warningFlags);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
result.push32(warningFlags);
|
||||
|
||||
result.push8(OSD.data.osd_profiles.selected + 1);
|
||||
|
@ -1819,7 +1819,7 @@ OSD.msp = {
|
|||
result.push8(OSD.data.parameters.overlayRadioMode);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
result.push8(OSD.data.parameters.cameraFrameWidth);
|
||||
result.push8(OSD.data.parameters.cameraFrameHeight);
|
||||
}
|
||||
|
@ -1858,18 +1858,18 @@ OSD.msp = {
|
|||
if (d.flags > 0) {
|
||||
if (payload.length > 1) {
|
||||
d.video_system = view.readU8();
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0") && bit_check(d.flags, 0)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0") && bit_check(d.flags, 0)) {
|
||||
d.unit_mode = view.readU8();
|
||||
d.alarms = {};
|
||||
d.alarms['rssi'] = { display_name: i18n.getMessage('osdTimerAlarmOptionRssi'), value: view.readU8() };
|
||||
d.alarms['cap'] = { display_name: i18n.getMessage('osdTimerAlarmOptionCapacity'), value: view.readU16() };
|
||||
if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
d.alarms['time'] = { display_name: 'Minutes', value: view.readU16() };
|
||||
} else {
|
||||
// This value was obsoleted by the introduction of configurable timers, and has been reused to encode the number of display elements sent in this command
|
||||
view.readU8();
|
||||
var tmp = view.readU8();
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
displayItemsCountActual = tmp;
|
||||
}
|
||||
}
|
||||
|
@ -1881,12 +1881,12 @@ OSD.msp = {
|
|||
|
||||
d.state = {};
|
||||
d.state.haveSomeOsd = (d.flags != 0)
|
||||
d.state.haveMax7456Configured = bit_check(d.flags, 4) || (d.flags == 1 && semver.lt(CONFIG.apiVersion, "1.34.0"));
|
||||
d.state.haveFrSkyOSDConfigured = semver.gte(CONFIG.apiVersion, API_VERSION_1_43) && bit_check(d.flags, 3);
|
||||
d.state.haveMax7456Configured = bit_check(d.flags, 4) || (d.flags == 1 && semver.lt(FC.CONFIG.apiVersion, "1.34.0"));
|
||||
d.state.haveFrSkyOSDConfigured = semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43) && bit_check(d.flags, 3);
|
||||
d.state.haveMax7456FontDeviceConfigured = d.state.haveMax7456Configured || d.state.haveFrSkyOSDConfigured;
|
||||
d.state.isMax7456FontDeviceDetected = bit_check(d.flags, 5) || (d.state.haveMax7456FontDeviceConfigured && 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");
|
||||
d.state.isMax7456FontDeviceDetected = bit_check(d.flags, 5) || (d.state.haveMax7456FontDeviceConfigured && semver.lt(FC.CONFIG.apiVersion, API_VERSION_1_43));
|
||||
d.state.haveOsdFeature = bit_check(d.flags, 0) || (d.flags == 1 && semver.lt(FC.CONFIG.apiVersion, "1.34.0"));
|
||||
d.state.isOsdSlave = bit_check(d.flags, 1) && semver.gte(FC.CONFIG.apiVersion, "1.34.0");
|
||||
|
||||
d.display_items = [];
|
||||
d.stat_items = [];
|
||||
|
@ -1902,7 +1902,7 @@ OSD.msp = {
|
|||
var items_positions_read = [];
|
||||
while (view.offset < view.byteLength && items_positions_read.length < displayItemsCountActual) {
|
||||
var v = null;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
v = view.readU16();
|
||||
} else {
|
||||
v = view.read16();
|
||||
|
@ -1910,7 +1910,7 @@ OSD.msp = {
|
|||
items_positions_read.push(v);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
// Parse statistics display enable
|
||||
var expectedStatsCount = view.readU8();
|
||||
if (expectedStatsCount != OSD.constants.STATISTIC_FIELDS.length) {
|
||||
|
@ -1965,7 +1965,7 @@ OSD.msp = {
|
|||
// Parse enabled warnings
|
||||
var warningCount = OSD.constants.WARNINGS.length;
|
||||
var warningFlags = view.readU16();
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
warningCount = view.readU8();
|
||||
// the flags were replaced with a 32bit version
|
||||
warningFlags = view.readU32();
|
||||
|
@ -1992,7 +1992,7 @@ OSD.msp = {
|
|||
}
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
// OSD profiles
|
||||
d.osd_profiles.number = view.readU8();
|
||||
d.osd_profiles.selected = view.readU8() - 1;
|
||||
|
@ -2006,7 +2006,7 @@ OSD.msp = {
|
|||
}
|
||||
|
||||
// Camera frame size
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
d.parameters.cameraFrameWidth = view.readU8();
|
||||
d.parameters.cameraFrameHeight = view.readU8();
|
||||
}
|
||||
|
@ -2153,7 +2153,7 @@ OSD.GUI.preview = {
|
|||
}
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
// unsigned now
|
||||
} else {
|
||||
if (position > OSD.data.display_size.total / 2) {
|
||||
|
@ -2295,7 +2295,7 @@ TABS.osd.initialize = function (callback) {
|
|||
});
|
||||
});
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.21.0")) {
|
||||
// units
|
||||
$('.units-container').show();
|
||||
var $unitMode = $('.units').empty();
|
||||
|
@ -2333,7 +2333,7 @@ TABS.osd.initialize = function (callback) {
|
|||
$alarms.append($input);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
// Timers
|
||||
$('.timers-container').show();
|
||||
var $timers = $('#timer-fields').empty();
|
||||
|
@ -2837,7 +2837,7 @@ TABS.osd.initialize = function (callback) {
|
|||
fontPresetsElement.change(function (e) {
|
||||
var $font = $('.fontpresets option:selected');
|
||||
var fontver = 1;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
fontver = 2;
|
||||
}
|
||||
$('.font-manager-version-info').text(i18n.getMessage('osdDescribeFontVersion' + fontver));
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -19,7 +19,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
{name: 'BLACKBOX', groups: ['peripherals'], sharableWith: ['msp'], notSharableWith: ['telemetry'], maxPorts: 1}
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
var ltmFunctionRule = {name: 'TELEMETRY_LTM', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['peripherals'], maxPorts: 1};
|
||||
functionRules.push(ltmFunctionRule);
|
||||
} else {
|
||||
|
@ -27,33 +27,33 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
functionRules.push(mspFunctionRule);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.18.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.18.0")) {
|
||||
var mavlinkFunctionRule = {name: 'TELEMETRY_MAVLINK', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['peripherals'], maxPorts: 1};
|
||||
functionRules.push(mavlinkFunctionRule);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) {
|
||||
functionRules.push({ name: 'ESC_SENSOR', groups: ['sensors'], maxPorts: 1 });
|
||||
functionRules.push({ name: 'TBS_SMARTAUDIO', groups: ['peripherals'], maxPorts: 1 });
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.27.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.27.0")) {
|
||||
functionRules.push({ name: 'IRC_TRAMP', groups: ['peripherals'], maxPorts: 1 });
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.32.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.32.0")) {
|
||||
functionRules.push({ name: 'TELEMETRY_IBUS', groups: ['telemetry'], maxPorts: 1 });
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
functionRules.push({ name: 'RUNCAM_DEVICE_CONTROL', groups: ['peripherals'], maxPorts: 1 });
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.37.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.37.0")) {
|
||||
functionRules.push({ name: 'LIDAR_TF', groups: ['peripherals'], maxPorts: 1 });
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
functionRules.push({ name: 'FRSKY_OSD', groups: ['peripherals'], maxPorts: 1 });
|
||||
}
|
||||
|
||||
|
@ -71,7 +71,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
'250000'
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.31.0")) {
|
||||
mspBaudRates = mspBaudRates.concat(['500000', '1000000']);
|
||||
}
|
||||
|
||||
|
@ -116,7 +116,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function load_configuration_from_fc() {
|
||||
let promise;
|
||||
if(semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if(semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
promise = MSP.promise(MSPCodes.MSP_VTX_CONFIG);
|
||||
} else {
|
||||
promise = Promise.resolve();
|
||||
|
@ -128,7 +128,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
function on_configuration_loaded_handler() {
|
||||
$('#content').load("./tabs/ports.html", on_tab_loaded_handler);
|
||||
|
||||
board_definition = BOARD.find_board_definition(CONFIG.boardIdentifier);
|
||||
board_definition = BOARD.find_board_definition(FC.CONFIG.boardIdentifier);
|
||||
console.log('Using board definition', board_definition);
|
||||
}
|
||||
}
|
||||
|
@ -136,7 +136,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
function update_ui() {
|
||||
self.analyticsChanges = {};
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.6.0")) {
|
||||
|
||||
$(".tab-ports").removeClass("supported");
|
||||
return;
|
||||
|
@ -187,10 +187,10 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
const portIdentifierTemplateE = $('#tab-ports-templates .portIdentifier');
|
||||
var port_configuration_template_e = $('#tab-ports-templates .portConfiguration');
|
||||
|
||||
for (var portIndex = 0; portIndex < SERIAL_CONFIG.ports.length; portIndex++) {
|
||||
for (var portIndex = 0; portIndex < FC.SERIAL_CONFIG.ports.length; portIndex++) {
|
||||
const portIdentifierE = portIdentifierTemplateE.clone();
|
||||
var port_configuration_e = port_configuration_template_e.clone();
|
||||
var serialPort = SERIAL_CONFIG.ports[portIndex];
|
||||
var serialPort = FC.SERIAL_CONFIG.ports[portIndex];
|
||||
|
||||
port_configuration_e.data('serialPort', serialPort);
|
||||
|
||||
|
@ -296,11 +296,11 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
let vtxTableNotConfigured = true;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
vtxTableNotConfigured = VTX_CONFIG.vtx_table_available &&
|
||||
(VTX_CONFIG.vtx_table_bands == 0 ||
|
||||
VTX_CONFIG.vtx_table_channels == 0 ||
|
||||
VTX_CONFIG.vtx_table_powerlevels == 0);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
vtxTableNotConfigured = FC.VTX_CONFIG.vtx_table_available &&
|
||||
(FC.VTX_CONFIG.vtx_table_bands == 0 ||
|
||||
FC.VTX_CONFIG.vtx_table_channels == 0 ||
|
||||
FC.VTX_CONFIG.vtx_table_powerlevels == 0);
|
||||
} else {
|
||||
$('.vtxTableNotSet').hide();
|
||||
}
|
||||
|
@ -321,7 +321,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
lastVtxControlSelected = vtxControlSelected;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
if (vtxControlSelected && vtxTableNotConfigured) {
|
||||
$('.vtxTableNotSet').show();
|
||||
} else {
|
||||
|
@ -354,7 +354,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
self.analyticsChanges = {};
|
||||
|
||||
// update configuration based on current ui state
|
||||
SERIAL_CONFIG.ports = [];
|
||||
FC.SERIAL_CONFIG.ports = [];
|
||||
|
||||
var ports_e = $('.tab-ports .portConfiguration').each(function (portConfiguration_e) {
|
||||
|
||||
|
@ -399,7 +399,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
blackbox_baudrate: blackboxBaudrate,
|
||||
identifier: oldSerialPort.identifier
|
||||
};
|
||||
SERIAL_CONFIG.ports.push(serialPort);
|
||||
FC.SERIAL_CONFIG.ports.push(serialPort);
|
||||
});
|
||||
|
||||
mspHelper.sendSerialConfig(save_to_eeprom);
|
||||
|
|
|
@ -53,7 +53,7 @@ TABS.power.initialize = function (callback) {
|
|||
$('#content').load("./tabs/power.html", process_html);
|
||||
}
|
||||
|
||||
this.supported = semver.gte(CONFIG.apiVersion, "1.33.0");
|
||||
this.supported = semver.gte(FC.CONFIG.apiVersion, "1.33.0");
|
||||
|
||||
if (!this.supported) {
|
||||
load_html();
|
||||
|
@ -64,7 +64,7 @@ TABS.power.initialize = function (callback) {
|
|||
function updateDisplay(voltageDataSource, currentDataSource) {
|
||||
// voltage meters
|
||||
|
||||
if (BATTERY_CONFIG.voltageMeterSource == 0) {
|
||||
if (FC.BATTERY_CONFIG.voltageMeterSource == 0) {
|
||||
$('.boxVoltageConfiguration').hide();
|
||||
} else {
|
||||
$('.boxVoltageConfiguration').show();
|
||||
|
@ -72,7 +72,7 @@ TABS.power.initialize = function (callback) {
|
|||
|
||||
if (!voltageDataSource) {
|
||||
voltageDataSource = [];
|
||||
for (var index = 0; index < VOLTAGE_METER_CONFIGS.length; index++) {
|
||||
for (var index = 0; index < FC.VOLTAGE_METER_CONFIGS.length; index++) {
|
||||
voltageDataSource[index] = {
|
||||
vbatscale: parseInt($('input[name="vbatscale-' + index + '"]').val()),
|
||||
vbatresdivval: parseInt($('input[name="vbatresdivval-' + index + '"]').val()),
|
||||
|
@ -84,23 +84,23 @@ TABS.power.initialize = function (callback) {
|
|||
var template = $('#tab-power-templates .voltage-meters .voltage-meter');
|
||||
var destination = $('.tab-power .voltage-meters');
|
||||
destination.empty();
|
||||
for (var index = 0; index < VOLTAGE_METERS.length; index++) {
|
||||
for (var index = 0; index < FC.VOLTAGE_METERS.length; index++) {
|
||||
var meterElement = template.clone();
|
||||
$(meterElement).attr('id', 'voltage-meter-' + index);
|
||||
|
||||
var message = i18n.getMessage('powerVoltageId' + VOLTAGE_METERS[index].id);
|
||||
var message = i18n.getMessage('powerVoltageId' + FC.VOLTAGE_METERS[index].id);
|
||||
$(meterElement).find('.label').text(message)
|
||||
destination.append(meterElement);
|
||||
|
||||
meterElement.hide();
|
||||
if ((BATTERY_CONFIG.voltageMeterSource == 1 && VOLTAGE_METERS[index].id == 10) // TODO: replace hardcoded constants
|
||||
|| (BATTERY_CONFIG.voltageMeterSource == 2 && VOLTAGE_METERS[index].id >= 50)) {
|
||||
if ((FC.BATTERY_CONFIG.voltageMeterSource == 1 && FC.VOLTAGE_METERS[index].id == 10) // TODO: replace hardcoded constants
|
||||
|| (FC.BATTERY_CONFIG.voltageMeterSource == 2 && FC.VOLTAGE_METERS[index].id >= 50)) {
|
||||
meterElement.show();
|
||||
}
|
||||
}
|
||||
|
||||
var template = $('#tab-power-templates .voltage-configuration');
|
||||
for (var index = 0; index < VOLTAGE_METER_CONFIGS.length; index++) {
|
||||
for (var index = 0; index < FC.VOLTAGE_METER_CONFIGS.length; index++) {
|
||||
var destination = $('#voltage-meter-' + index + ' .configuration');
|
||||
var element = template.clone();
|
||||
|
||||
|
@ -124,7 +124,7 @@ TABS.power.initialize = function (callback) {
|
|||
});
|
||||
|
||||
// amperage meters
|
||||
if (BATTERY_CONFIG.currentMeterSource == 0) {
|
||||
if (FC.BATTERY_CONFIG.currentMeterSource == 0) {
|
||||
$('.boxAmperageConfiguration').hide();
|
||||
} else {
|
||||
$('.boxAmperageConfiguration').show();
|
||||
|
@ -132,7 +132,7 @@ TABS.power.initialize = function (callback) {
|
|||
|
||||
if (!currentDataSource) {
|
||||
currentDataSource = [];
|
||||
for (var index = 0; index < CURRENT_METER_CONFIGS.length; index++) {
|
||||
for (var index = 0; index < FC.CURRENT_METER_CONFIGS.length; index++) {
|
||||
currentDataSource[index] = {
|
||||
scale: parseInt($('input[name="amperagescale-' + index + '"]').val()),
|
||||
offset: parseInt($('input[name="amperageoffset-' + index + '"]').val())
|
||||
|
@ -142,24 +142,24 @@ TABS.power.initialize = function (callback) {
|
|||
var template = $('#tab-power-templates .amperage-meters .amperage-meter');
|
||||
var destination = $('.tab-power .amperage-meters');
|
||||
destination.empty();
|
||||
for (var index = 0; index < CURRENT_METERS.length; index++) {
|
||||
for (var index = 0; index < FC.CURRENT_METERS.length; index++) {
|
||||
var meterElement = template.clone();
|
||||
$(meterElement).attr('id', 'amperage-meter-' + index);
|
||||
|
||||
var message = i18n.getMessage('powerAmperageId' + CURRENT_METERS[index].id);
|
||||
var message = i18n.getMessage('powerAmperageId' + FC.CURRENT_METERS[index].id);
|
||||
$(meterElement).find('.label').text(message)
|
||||
destination.append(meterElement);
|
||||
|
||||
meterElement.hide();
|
||||
if ((BATTERY_CONFIG.currentMeterSource == 1 && CURRENT_METERS[index].id == 10) // TODO: replace constants
|
||||
|| (BATTERY_CONFIG.currentMeterSource == 2 && CURRENT_METERS[index].id == 80)
|
||||
|| (BATTERY_CONFIG.currentMeterSource == 3 && CURRENT_METERS[index].id >= 50 && CURRENT_METERS[index].id < 80)) {
|
||||
if ((FC.BATTERY_CONFIG.currentMeterSource == 1 && FC.CURRENT_METERS[index].id == 10) // TODO: replace constants
|
||||
|| (FC.BATTERY_CONFIG.currentMeterSource == 2 && FC.CURRENT_METERS[index].id == 80)
|
||||
|| (FC.BATTERY_CONFIG.currentMeterSource == 3 && FC.CURRENT_METERS[index].id >= 50 && FC.CURRENT_METERS[index].id < 80)) {
|
||||
meterElement.show();
|
||||
}
|
||||
}
|
||||
|
||||
var template = $('#tab-power-templates .amperage-configuration');
|
||||
for (var index = 0; index < CURRENT_METER_CONFIGS.length; index++) {
|
||||
for (var index = 0; index < FC.CURRENT_METER_CONFIGS.length; index++) {
|
||||
var destination = $('#amperage-meter-' + index + ' .configuration');
|
||||
var element = template.clone();
|
||||
|
||||
|
@ -174,7 +174,7 @@ TABS.power.initialize = function (callback) {
|
|||
}
|
||||
|
||||
$('input[name="amperagescale-0"]').change(function () {
|
||||
if (BATTERY_CONFIG.currentMeterSource === 1) {
|
||||
if (FC.BATTERY_CONFIG.currentMeterSource === 1) {
|
||||
let value = parseInt($(this).val());
|
||||
|
||||
if (value !== currentDataSource[0].scale) {
|
||||
|
@ -184,7 +184,7 @@ TABS.power.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('input[name="amperagescale-1"]').change(function () {
|
||||
if (BATTERY_CONFIG.currentMeterSource === 2) {
|
||||
if (FC.BATTERY_CONFIG.currentMeterSource === 2) {
|
||||
let value = parseInt($(this).val());
|
||||
|
||||
if (value !== currentDataSource[1].scale) {
|
||||
|
@ -193,7 +193,7 @@ TABS.power.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
|
||||
if(BATTERY_CONFIG.voltageMeterSource == 1 || BATTERY_CONFIG.currentMeterSource == 1 || BATTERY_CONFIG.currentMeterSource == 2) {
|
||||
if(FC.BATTERY_CONFIG.voltageMeterSource == 1 || FC.BATTERY_CONFIG.currentMeterSource == 1 || FC.BATTERY_CONFIG.currentMeterSource == 2) {
|
||||
$('.calibration').show();
|
||||
} else {
|
||||
$('.calibration').hide();
|
||||
|
@ -226,18 +226,18 @@ TABS.power.initialize = function (callback) {
|
|||
var element = template.clone();
|
||||
destination.append(element);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
$('input[name="mincellvoltage"]').prop('step','0.01');
|
||||
$('input[name="maxcellvoltage"]').prop('step','0.01');
|
||||
$('input[name="warningcellvoltage"]').prop('step','0.01');
|
||||
}
|
||||
|
||||
$('input[name="mincellvoltage"]').val(BATTERY_CONFIG.vbatmincellvoltage);
|
||||
$('input[name="maxcellvoltage"]').val(BATTERY_CONFIG.vbatmaxcellvoltage);
|
||||
$('input[name="warningcellvoltage"]').val(BATTERY_CONFIG.vbatwarningcellvoltage);
|
||||
$('input[name="capacity"]').val(BATTERY_CONFIG.capacity);
|
||||
$('input[name="mincellvoltage"]').val(FC.BATTERY_CONFIG.vbatmincellvoltage);
|
||||
$('input[name="maxcellvoltage"]').val(FC.BATTERY_CONFIG.vbatmaxcellvoltage);
|
||||
$('input[name="warningcellvoltage"]').val(FC.BATTERY_CONFIG.vbatwarningcellvoltage);
|
||||
$('input[name="capacity"]').val(FC.BATTERY_CONFIG.capacity);
|
||||
|
||||
var haveFc = (semver.lt(CONFIG.apiVersion, "1.35.0") || (CONFIG.boardType == 0 || CONFIG.boardType == 2));
|
||||
var haveFc = (semver.lt(FC.CONFIG.apiVersion, "1.35.0") || (FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2));
|
||||
|
||||
var batteryMeterTypes = [
|
||||
i18n.getMessage('powerBatteryVoltageMeterTypeNone'),
|
||||
|
@ -264,7 +264,7 @@ TABS.power.initialize = function (callback) {
|
|||
currentMeterTypes.push(i18n.getMessage('powerBatteryCurrentMeterTypeVirtual'));
|
||||
currentMeterTypes.push(i18n.getMessage('powerBatteryCurrentMeterTypeEsc'));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
currentMeterTypes.push(i18n.getMessage('powerBatteryCurrentMeterTypeMsp'));
|
||||
}
|
||||
}
|
||||
|
@ -275,23 +275,23 @@ TABS.power.initialize = function (callback) {
|
|||
currentMeterType_e.append('<option value="' + i + '">' + currentMeterTypes[i] + '</option>');
|
||||
}
|
||||
|
||||
updateDisplay(VOLTAGE_METER_CONFIGS, CURRENT_METER_CONFIGS);
|
||||
updateDisplay(FC.VOLTAGE_METER_CONFIGS, FC.CURRENT_METER_CONFIGS);
|
||||
|
||||
var batteryMeterType_e = $('select.batterymetersource');
|
||||
|
||||
var sourceschanged = false;
|
||||
batteryMeterType_e.val(BATTERY_CONFIG.voltageMeterSource);
|
||||
batteryMeterType_e.val(FC.BATTERY_CONFIG.voltageMeterSource);
|
||||
batteryMeterType_e.change(function () {
|
||||
BATTERY_CONFIG.voltageMeterSource = parseInt($(this).val());
|
||||
FC.BATTERY_CONFIG.voltageMeterSource = parseInt($(this).val());
|
||||
|
||||
updateDisplay();
|
||||
sourceschanged = true;
|
||||
});
|
||||
|
||||
var currentMeterType_e = $('select.currentmetersource');
|
||||
currentMeterType_e.val(BATTERY_CONFIG.currentMeterSource);
|
||||
currentMeterType_e.val(FC.BATTERY_CONFIG.currentMeterSource);
|
||||
currentMeterType_e.change(function () {
|
||||
BATTERY_CONFIG.currentMeterSource = parseInt($(this).val());
|
||||
FC.BATTERY_CONFIG.currentMeterSource = parseInt($(this).val());
|
||||
|
||||
updateDisplay();
|
||||
sourceschanged = true;
|
||||
|
@ -299,18 +299,18 @@ TABS.power.initialize = function (callback) {
|
|||
|
||||
function get_slow_data() {
|
||||
MSP.send_message(MSPCodes.MSP_VOLTAGE_METERS, false, false, function () {
|
||||
for (var i = 0; i < VOLTAGE_METERS.length; i++) {
|
||||
for (var i = 0; i < FC.VOLTAGE_METERS.length; i++) {
|
||||
var elementName = '#voltage-meter-' + i + ' .value';
|
||||
var element = $(elementName);
|
||||
element.text(i18n.getMessage('powerVoltageValue', [VOLTAGE_METERS[i].voltage]));
|
||||
element.text(i18n.getMessage('powerVoltageValue', [FC.VOLTAGE_METERS[i].voltage]));
|
||||
}
|
||||
});
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_CURRENT_METERS, false, false, function () {
|
||||
for (var i = 0; i < CURRENT_METERS.length; i++) {
|
||||
for (var i = 0; i < FC.CURRENT_METERS.length; i++) {
|
||||
var elementName = '#amperage-meter-' + i + ' .value';
|
||||
var element = $(elementName);
|
||||
element.text(i18n.getMessage('powerAmperageValue', [CURRENT_METERS[i].amperage.toFixed(2)]));
|
||||
element.text(i18n.getMessage('powerAmperageValue', [FC.CURRENT_METERS[i].amperage.toFixed(2)]));
|
||||
}
|
||||
});
|
||||
|
||||
|
@ -319,13 +319,13 @@ TABS.power.initialize = function (callback) {
|
|||
var element;
|
||||
|
||||
element = $(elementPrefix + '-connection-state .value');
|
||||
element.text(BATTERY_STATE.cellCount > 0 ? i18n.getMessage('powerBatteryConnectedValueYes', [BATTERY_STATE.cellCount]) : i18n.getMessage('powerBatteryConnectedValueNo'));
|
||||
element.text(FC.BATTERY_STATE.cellCount > 0 ? i18n.getMessage('powerBatteryConnectedValueYes', [FC.BATTERY_STATE.cellCount]) : i18n.getMessage('powerBatteryConnectedValueNo'));
|
||||
element = $(elementPrefix + '-voltage .value');
|
||||
element.text(i18n.getMessage('powerVoltageValue', [BATTERY_STATE.voltage]));
|
||||
element.text(i18n.getMessage('powerVoltageValue', [FC.BATTERY_STATE.voltage]));
|
||||
element = $(elementPrefix + '-mah-drawn .value');
|
||||
element.text(i18n.getMessage('powerMahValue', [BATTERY_STATE.mAhDrawn]));
|
||||
element.text(i18n.getMessage('powerMahValue', [FC.BATTERY_STATE.mAhDrawn]));
|
||||
element = $(elementPrefix + '-amperage .value');
|
||||
element.text(i18n.getMessage('powerAmperageValue', [BATTERY_STATE.amperage]));
|
||||
element.text(i18n.getMessage('powerAmperageValue', [FC.BATTERY_STATE.amperage]));
|
||||
});
|
||||
|
||||
}
|
||||
|
@ -361,17 +361,17 @@ TABS.power.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('a.calibrationmanager').click(function() {
|
||||
if (BATTERY_CONFIG.voltageMeterSource == 1 && BATTERY_STATE.voltage > 0.1){
|
||||
if (FC.BATTERY_CONFIG.voltageMeterSource == 1 && FC.BATTERY_STATE.voltage > 0.1){
|
||||
$('.vbatcalibration').show();
|
||||
} else {
|
||||
$('.vbatcalibration').hide();
|
||||
}
|
||||
if ((BATTERY_CONFIG.currentMeterSource == 1 || BATTERY_CONFIG.currentMeterSource == 2) && BATTERY_STATE.amperage > 0.1) {
|
||||
if ((FC.BATTERY_CONFIG.currentMeterSource == 1 || FC.BATTERY_CONFIG.currentMeterSource == 2) && FC.BATTERY_STATE.amperage > 0.1) {
|
||||
$('.amperagecalibration').show();
|
||||
} else {
|
||||
$('.amperagecalibration').hide();
|
||||
}
|
||||
if (BATTERY_STATE.cellCount == 0) {
|
||||
if (FC.BATTERY_STATE.cellCount == 0) {
|
||||
$('.vbatcalibration').hide();
|
||||
$('.amperagecalibration').hide();
|
||||
$('.calibrate').hide();
|
||||
|
@ -397,26 +397,26 @@ TABS.power.initialize = function (callback) {
|
|||
var vbatscalechanged = false;
|
||||
var amperagescalechanged = false;
|
||||
$('a.calibrate').click(function() {
|
||||
if (BATTERY_CONFIG.voltageMeterSource == 1) {
|
||||
if (FC.BATTERY_CONFIG.voltageMeterSource == 1) {
|
||||
var vbatcalibration = parseFloat($('input[name="vbatcalibration"]').val());
|
||||
if (vbatcalibration != 0) {
|
||||
var vbatnewscale = Math.round(VOLTAGE_METER_CONFIGS[0].vbatscale * (vbatcalibration / VOLTAGE_METERS[0].voltage));
|
||||
var vbatnewscale = Math.round(FC.VOLTAGE_METER_CONFIGS[0].vbatscale * (vbatcalibration / FC.VOLTAGE_METERS[0].voltage));
|
||||
if (vbatnewscale >= 10 && vbatnewscale <= 255) {
|
||||
VOLTAGE_METER_CONFIGS[0].vbatscale = vbatnewscale;
|
||||
FC.VOLTAGE_METER_CONFIGS[0].vbatscale = vbatnewscale;
|
||||
vbatscalechanged = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
var ampsource = BATTERY_CONFIG.currentMeterSource;
|
||||
var ampsource = FC.BATTERY_CONFIG.currentMeterSource;
|
||||
if (ampsource == 1 || ampsource == 2) {
|
||||
var amperagecalibration = parseFloat($('input[name="amperagecalibration"]').val());
|
||||
var amperageoffset = CURRENT_METER_CONFIGS[ampsource - 1].offset / 1000;
|
||||
var amperageoffset = FC.CURRENT_METER_CONFIGS[ampsource - 1].offset / 1000;
|
||||
if (amperagecalibration != 0) {
|
||||
if (CURRENT_METERS[ampsource - 1].amperage != amperageoffset && amperagecalibration != amperageoffset) {
|
||||
var amperagenewscale = Math.round(CURRENT_METER_CONFIGS[ampsource - 1].scale *
|
||||
((CURRENT_METERS[ampsource - 1].amperage - amperageoffset) / (amperagecalibration - amperageoffset)));
|
||||
if (FC.CURRENT_METERS[ampsource - 1].amperage != amperageoffset && amperagecalibration != amperageoffset) {
|
||||
var amperagenewscale = Math.round(FC.CURRENT_METER_CONFIGS[ampsource - 1].scale *
|
||||
((FC.CURRENT_METERS[ampsource - 1].amperage - amperageoffset) / (amperagecalibration - amperageoffset)));
|
||||
if (amperagenewscale > -16000 && amperagenewscale < 16000 && amperagenewscale != 0) {
|
||||
CURRENT_METER_CONFIGS[ampsource - 1].scale = amperagenewscale;
|
||||
FC.CURRENT_METER_CONFIGS[ampsource - 1].scale = amperagenewscale;
|
||||
amperagescalechanged = true;
|
||||
}
|
||||
}
|
||||
|
@ -448,7 +448,7 @@ TABS.power.initialize = function (callback) {
|
|||
|
||||
calibrationconfirmed = true;
|
||||
GUI.calibrationManagerConfirmation.close();
|
||||
updateDisplay(VOLTAGE_METER_CONFIGS, CURRENT_METER_CONFIGS);
|
||||
updateDisplay(FC.VOLTAGE_METER_CONFIGS, FC.CURRENT_METER_CONFIGS);
|
||||
$('.calibration').hide();
|
||||
});
|
||||
|
||||
|
@ -461,21 +461,21 @@ TABS.power.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('a.save').click(function () {
|
||||
for (var index = 0; index < VOLTAGE_METER_CONFIGS.length; index++) {
|
||||
VOLTAGE_METER_CONFIGS[index].vbatscale = parseInt($('input[name="vbatscale-' + index + '"]').val());
|
||||
VOLTAGE_METER_CONFIGS[index].vbatresdivval = parseInt($('input[name="vbatresdivval-' + index + '"]').val());
|
||||
VOLTAGE_METER_CONFIGS[index].vbatresdivmultiplier = parseInt($('input[name="vbatresdivmultiplier-' + index + '"]').val());
|
||||
for (var index = 0; index < FC.VOLTAGE_METER_CONFIGS.length; index++) {
|
||||
FC.VOLTAGE_METER_CONFIGS[index].vbatscale = parseInt($('input[name="vbatscale-' + index + '"]').val());
|
||||
FC.VOLTAGE_METER_CONFIGS[index].vbatresdivval = parseInt($('input[name="vbatresdivval-' + index + '"]').val());
|
||||
FC.VOLTAGE_METER_CONFIGS[index].vbatresdivmultiplier = parseInt($('input[name="vbatresdivmultiplier-' + index + '"]').val());
|
||||
}
|
||||
|
||||
for (var index = 0; index < CURRENT_METER_CONFIGS.length; index++) {
|
||||
CURRENT_METER_CONFIGS[index].scale = parseInt($('input[name="amperagescale-' + index + '"]').val());
|
||||
CURRENT_METER_CONFIGS[index].offset = parseInt($('input[name="amperageoffset-' + index + '"]').val());
|
||||
for (var index = 0; index < FC.CURRENT_METER_CONFIGS.length; index++) {
|
||||
FC.CURRENT_METER_CONFIGS[index].scale = parseInt($('input[name="amperagescale-' + index + '"]').val());
|
||||
FC.CURRENT_METER_CONFIGS[index].offset = parseInt($('input[name="amperageoffset-' + index + '"]').val());
|
||||
}
|
||||
|
||||
BATTERY_CONFIG.vbatmincellvoltage = parseFloat($('input[name="mincellvoltage"]').val());
|
||||
BATTERY_CONFIG.vbatmaxcellvoltage = parseFloat($('input[name="maxcellvoltage"]').val());
|
||||
BATTERY_CONFIG.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
|
||||
BATTERY_CONFIG.capacity = parseInt($('input[name="capacity"]').val());
|
||||
FC.BATTERY_CONFIG.vbatmincellvoltage = parseFloat($('input[name="mincellvoltage"]').val());
|
||||
FC.BATTERY_CONFIG.vbatmaxcellvoltage = parseFloat($('input[name="maxcellvoltage"]').val());
|
||||
FC.BATTERY_CONFIG.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
|
||||
FC.BATTERY_CONFIG.capacity = parseInt($('input[name="capacity"]').val());
|
||||
|
||||
analytics.sendChangeEvents(analytics.EVENT_CATEGORIES.FLIGHT_CONTROLLER, self.analyticsChanges);
|
||||
|
||||
|
@ -491,7 +491,7 @@ TABS.power.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function save_voltage_config() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
mspHelper.sendVoltageConfig(save_amperage_config);
|
||||
} else {
|
||||
MSP.send_message(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG), false, save_amperage_config);
|
||||
|
@ -499,7 +499,7 @@ TABS.power.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function save_amperage_config() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
mspHelper.sendCurrentConfig(save_to_eeprom);
|
||||
} else {
|
||||
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, save_to_eeprom);
|
||||
|
|
|
@ -32,7 +32,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function load_rc_configs() {
|
||||
var next_callback = load_rx_config;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_RC_DEADBAND, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -41,7 +41,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function load_rx_config() {
|
||||
var next_callback = load_mixer_config;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -62,12 +62,12 @@ TABS.receiver.initialize = function (callback) {
|
|||
// translate to user-selected language
|
||||
i18n.localizePage();
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
$('.deadband').hide();
|
||||
} else {
|
||||
$('.deadband input[name="yaw_deadband"]').val(RC_DEADBAND_CONFIG.yaw_deadband);
|
||||
$('.deadband input[name="deadband"]').val(RC_DEADBAND_CONFIG.deadband);
|
||||
$('.deadband input[name="3ddeadbandthrottle"]').val(RC_DEADBAND_CONFIG.deadband3d_throttle);
|
||||
$('.deadband input[name="yaw_deadband"]').val(FC.RC_DEADBAND_CONFIG.yaw_deadband);
|
||||
$('.deadband input[name="deadband"]').val(FC.RC_DEADBAND_CONFIG.deadband);
|
||||
$('.deadband input[name="3ddeadbandthrottle"]').val(FC.RC_DEADBAND_CONFIG.deadband3d_throttle);
|
||||
|
||||
$('.deadband input[name="deadband"]').change(function () {
|
||||
tab.deadband = parseInt($(this).val());
|
||||
|
@ -77,17 +77,17 @@ TABS.receiver.initialize = function (callback) {
|
|||
}).change();
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
$('.sticks').hide();
|
||||
} else {
|
||||
$('.sticks input[name="stick_min"]').val(RX_CONFIG.stick_min);
|
||||
$('.sticks input[name="stick_center"]').val(RX_CONFIG.stick_center);
|
||||
$('.sticks input[name="stick_max"]').val(RX_CONFIG.stick_max);
|
||||
$('.sticks input[name="stick_min"]').val(FC.RX_CONFIG.stick_min);
|
||||
$('.sticks input[name="stick_center"]').val(FC.RX_CONFIG.stick_center);
|
||||
$('.sticks input[name="stick_max"]').val(FC.RX_CONFIG.stick_max);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
$('select[name="rcInterpolation-select"]').val(RX_CONFIG.rcInterpolation);
|
||||
$('input[name="rcInterpolationInterval-number"]').val(RX_CONFIG.rcInterpolationInterval);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
$('select[name="rcInterpolation-select"]').val(FC.RX_CONFIG.rcInterpolation);
|
||||
$('input[name="rcInterpolationInterval-number"]').val(FC.RX_CONFIG.rcInterpolationInterval);
|
||||
|
||||
$('select[name="rcInterpolation-select"]').change(function () {
|
||||
tab.updateRcInterpolationParameters();
|
||||
|
@ -106,7 +106,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
bar_container = $('.tab-receiver .bars'),
|
||||
aux_index = 1;
|
||||
|
||||
var num_bars = (RC.active_channels > 0) ? RC.active_channels : 8;
|
||||
var num_bars = (FC.RC.active_channels > 0) ? FC.RC.active_channels : 8;
|
||||
|
||||
for (var i = 0; i < num_bars; i++) {
|
||||
var name;
|
||||
|
@ -122,7 +122,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
<li class="meter">\
|
||||
<div class="meter-bar">\
|
||||
<div class="label"></div>\
|
||||
<div class="fill' + (RC.active_channels == 0 ? 'disabled' : '') + '">\
|
||||
<div class="fill' + (FC.RC.active_channels == 0 ? 'disabled' : '') + '">\
|
||||
<div class="label"></div>\
|
||||
</div>\
|
||||
</div>\
|
||||
|
@ -164,8 +164,8 @@ TABS.receiver.initialize = function (callback) {
|
|||
var RC_MAP_Letters = ['A', 'E', 'R', 'T', '1', '2', '3', '4'];
|
||||
|
||||
var strBuffer = [];
|
||||
for (var i = 0; i < RC_MAP.length; i++) {
|
||||
strBuffer[RC_MAP[i]] = RC_MAP_Letters[i];
|
||||
for (var i = 0; i < FC.RC_MAP.length; i++) {
|
||||
strBuffer[FC.RC_MAP[i]] = RC_MAP_Letters[i];
|
||||
}
|
||||
|
||||
// reconstruct
|
||||
|
@ -223,11 +223,11 @@ TABS.receiver.initialize = function (callback) {
|
|||
var rssi_channel_e = $('select[name="rssi_channel"]');
|
||||
rssi_channel_e.append('<option value="0">' + i18n.getMessage("receiverRssiChannelDisabledOption") + '</option>');
|
||||
//1-4 reserved for Roll Pitch Yaw & Throttle, starting at 5
|
||||
for (var i = 5; i < RC.active_channels + 1; i++) {
|
||||
for (var i = 5; i < FC.RC.active_channels + 1; i++) {
|
||||
rssi_channel_e.append('<option value="' + i + '">' + i18n.getMessage("controlAxisAux" + (i-4)) + '</option>');
|
||||
}
|
||||
|
||||
$('select[name="rssi_channel"]').val(RSSI_CONFIG.channel);
|
||||
$('select[name="rssi_channel"]').val(FC.RSSI_CONFIG.channel);
|
||||
|
||||
var rateHeight = TABS.receiver.rateChartHeight;
|
||||
|
||||
|
@ -239,42 +239,42 @@ TABS.receiver.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('a.update').click(function () {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
RX_CONFIG.stick_max = parseInt($('.sticks input[name="stick_max"]').val());
|
||||
RX_CONFIG.stick_center = parseInt($('.sticks input[name="stick_center"]').val());
|
||||
RX_CONFIG.stick_min = parseInt($('.sticks input[name="stick_min"]').val());
|
||||
RC_DEADBAND_CONFIG.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
|
||||
RC_DEADBAND_CONFIG.deadband = parseInt($('.deadband input[name="deadband"]').val());
|
||||
RC_DEADBAND_CONFIG.deadband3d_throttle = ($('.deadband input[name="3ddeadbandthrottle"]').val());
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
FC.RX_CONFIG.stick_max = parseInt($('.sticks input[name="stick_max"]').val());
|
||||
FC.RX_CONFIG.stick_center = parseInt($('.sticks input[name="stick_center"]').val());
|
||||
FC.RX_CONFIG.stick_min = parseInt($('.sticks input[name="stick_min"]').val());
|
||||
FC.RC_DEADBAND_CONFIG.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
|
||||
FC.RC_DEADBAND_CONFIG.deadband = parseInt($('.deadband input[name="deadband"]').val());
|
||||
FC.RC_DEADBAND_CONFIG.deadband3d_throttle = ($('.deadband input[name="3ddeadbandthrottle"]').val());
|
||||
}
|
||||
|
||||
// catch rc map
|
||||
var RC_MAP_Letters = ['A', 'E', 'R', 'T', '1', '2', '3', '4'];
|
||||
var strBuffer = $('input[name="rcmap"]').val().split('');
|
||||
|
||||
for (var i = 0; i < RC_MAP.length; i++) {
|
||||
RC_MAP[i] = strBuffer.indexOf(RC_MAP_Letters[i]);
|
||||
for (var i = 0; i < FC.RC_MAP.length; i++) {
|
||||
FC.RC_MAP[i] = strBuffer.indexOf(RC_MAP_Letters[i]);
|
||||
}
|
||||
|
||||
// catch rssi aux
|
||||
RSSI_CONFIG.channel = parseInt($('select[name="rssi_channel"]').val());
|
||||
FC.RSSI_CONFIG.channel = parseInt($('select[name="rssi_channel"]').val());
|
||||
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
RX_CONFIG.rcInterpolation = parseInt($('select[name="rcInterpolation-select"]').val());
|
||||
RX_CONFIG.rcInterpolationInterval = parseInt($('input[name="rcInterpolationInterval-number"]').val());
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
FC.RX_CONFIG.rcInterpolation = parseInt($('select[name="rcInterpolation-select"]').val());
|
||||
FC.RX_CONFIG.rcInterpolationInterval = parseInt($('input[name="rcInterpolationInterval-number"]').val());
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
RX_CONFIG.rcSmoothingInputCutoff = parseInt($('input[name="rcSmoothingInputHz-number"]').val());
|
||||
RX_CONFIG.rcSmoothingDerivativeCutoff = parseInt($('input[name="rcSmoothingDerivativeCutoff-number"]').val());
|
||||
RX_CONFIG.rcSmoothingDerivativeType = parseInt($('select[name="rcSmoothingDerivativeType-select"]').val());
|
||||
RX_CONFIG.rcInterpolationChannels = parseInt($('select[name="rcSmoothingChannels-select"]').val());
|
||||
RX_CONFIG.rcSmoothingInputType = parseInt($('select[name="rcSmoothingInputType-select"]').val());
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
FC.RX_CONFIG.rcSmoothingInputCutoff = parseInt($('input[name="rcSmoothingInputHz-number"]').val());
|
||||
FC.RX_CONFIG.rcSmoothingDerivativeCutoff = parseInt($('input[name="rcSmoothingDerivativeCutoff-number"]').val());
|
||||
FC.RX_CONFIG.rcSmoothingDerivativeType = parseInt($('select[name="rcSmoothingDerivativeType-select"]').val());
|
||||
FC.RX_CONFIG.rcInterpolationChannels = parseInt($('select[name="rcSmoothingChannels-select"]').val());
|
||||
FC.RX_CONFIG.rcSmoothingInputType = parseInt($('select[name="rcSmoothingInputType-select"]').val());
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
RX_CONFIG.rcSmoothingAutoSmoothness = parseInt($('input[name="rcSmoothingAutoSmoothness-number"]').val());
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
FC.RX_CONFIG.rcSmoothingAutoSmoothness = parseInt($('input[name="rcSmoothingAutoSmoothness-number"]').val());
|
||||
}
|
||||
|
||||
function save_rssi_config() {
|
||||
|
@ -283,7 +283,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function save_rc_configs() {
|
||||
var next_callback = save_rx_config;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_RC_DEADBAND, mspHelper.crunch(MSPCodes.MSP_SET_RC_DEADBAND), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -292,7 +292,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function save_rx_config() {
|
||||
var next_callback = save_to_eeprom;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -338,8 +338,8 @@ TABS.receiver.initialize = function (callback) {
|
|||
});
|
||||
|
||||
let showBindButton = false;
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
showBindButton = bit_check(CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.SUPPORTS_RX_BIND);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
showBindButton = bit_check(FC.CONFIG.targetCapabilities, FC.TARGET_CAPABILITIES_FLAGS.SUPPORTS_RX_BIND);
|
||||
|
||||
$("a.bind").click(function() {
|
||||
MSP.send_message(MSPCodes.MSP2_BETAFLIGHT_BIND);
|
||||
|
@ -350,23 +350,23 @@ TABS.receiver.initialize = function (callback) {
|
|||
$(".bind_btn").toggle(showBindButton);
|
||||
|
||||
// RC Smoothing
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
$('.tab-receiver .rcSmoothing').show();
|
||||
|
||||
var rc_smoothing_protocol_e = $('select[name="rcSmoothing-select"]');
|
||||
rc_smoothing_protocol_e.change(function () {
|
||||
RX_CONFIG.rcSmoothingType = $(this).val();
|
||||
FC.RX_CONFIG.rcSmoothingType = $(this).val();
|
||||
updateInterpolationView();
|
||||
});
|
||||
rc_smoothing_protocol_e.val(RX_CONFIG.rcSmoothingType);
|
||||
rc_smoothing_protocol_e.val(FC.RX_CONFIG.rcSmoothingType);
|
||||
|
||||
const rcSmoothingNumberElement = $('input[name="rcSmoothingInputHz-number"]');
|
||||
const rcSmoothingDerivativeNumberElement = $('input[name="rcSmoothingDerivativeCutoff-number"]');
|
||||
rcSmoothingNumberElement.val(RX_CONFIG.rcSmoothingInputCutoff);
|
||||
rcSmoothingDerivativeNumberElement.val(RX_CONFIG.rcSmoothingDerivativeCutoff);
|
||||
rcSmoothingNumberElement.val(FC.RX_CONFIG.rcSmoothingInputCutoff);
|
||||
rcSmoothingDerivativeNumberElement.val(FC.RX_CONFIG.rcSmoothingDerivativeCutoff);
|
||||
$('.tab-receiver .rcSmoothing-input-cutoff').show();
|
||||
$('select[name="rcSmoothing-input-manual-select"]').val("1");
|
||||
if (RX_CONFIG.rcSmoothingInputCutoff == 0) {
|
||||
if (FC.RX_CONFIG.rcSmoothingInputCutoff == 0) {
|
||||
$('.tab-receiver .rcSmoothing-input-cutoff').hide();
|
||||
$('select[name="rcSmoothing-input-manual-select"]').val("0");
|
||||
}
|
||||
|
@ -376,14 +376,14 @@ TABS.receiver.initialize = function (callback) {
|
|||
$('.tab-receiver .rcSmoothing-input-cutoff').hide();
|
||||
}
|
||||
if ($(this).val() == 1) {
|
||||
rcSmoothingNumberElement.val(RX_CONFIG.rcSmoothingInputCutoff);
|
||||
rcSmoothingNumberElement.val(FC.RX_CONFIG.rcSmoothingInputCutoff);
|
||||
$('.tab-receiver .rcSmoothing-input-cutoff').show();
|
||||
}
|
||||
}).change();
|
||||
|
||||
$('.tab-receiver .rcSmoothing-derivative-cutoff').show();
|
||||
$('select[name="rcSmoothing-input-derivative-select"]').val("1");
|
||||
if (RX_CONFIG.rcSmoothingDerivativeCutoff == 0) {
|
||||
if (FC.RX_CONFIG.rcSmoothingDerivativeCutoff == 0) {
|
||||
$('select[name="rcSmoothing-input-derivative-select"]').val("0");
|
||||
$('.tab-receiver .rcSmoothing-derivative-cutoff').hide();
|
||||
}
|
||||
|
@ -394,22 +394,22 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
if ($(this).val() == 1) {
|
||||
$('.tab-receiver .rcSmoothing-derivative-cutoff').show();
|
||||
rcSmoothingDerivativeNumberElement.val(RX_CONFIG.rcSmoothingDerivativeCutoff);
|
||||
rcSmoothingDerivativeNumberElement.val(FC.RX_CONFIG.rcSmoothingDerivativeCutoff);
|
||||
}
|
||||
}).change();
|
||||
|
||||
var rc_smoothing_derivative_type = $('select[name="rcSmoothingDerivativeType-select"]');
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
rc_smoothing_derivative_type.append($(`<option value="3">${i18n.getMessage("receiverRcSmoothingDerivativeTypeAuto")}</option>`));
|
||||
}
|
||||
|
||||
rc_smoothing_derivative_type.val(RX_CONFIG.rcSmoothingDerivativeType);
|
||||
rc_smoothing_derivative_type.val(FC.RX_CONFIG.rcSmoothingDerivativeType);
|
||||
var rc_smoothing_channels = $('select[name="rcSmoothingChannels-select"]');
|
||||
rc_smoothing_channels.val(RX_CONFIG.rcInterpolationChannels);
|
||||
rc_smoothing_channels.val(FC.RX_CONFIG.rcInterpolationChannels);
|
||||
var rc_smoothing_input_type = $('select[name="rcSmoothingInputType-select"]');
|
||||
rc_smoothing_input_type.val(RX_CONFIG.rcSmoothingInputType);
|
||||
rc_smoothing_input_type.val(FC.RX_CONFIG.rcSmoothingInputType);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
$('select[name="rcSmoothing-input-manual-select"], select[name="rcSmoothing-input-derivative-select"]').change(function() {
|
||||
if ($('select[name="rcSmoothing-input-manual-select"]').val() == 0 || $('select[name="rcSmoothing-input-derivative-select"]').val() == 0) {
|
||||
$('.tab-receiver .rcSmoothing-auto-smoothness').show();
|
||||
|
@ -420,7 +420,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
$('select[name="rcSmoothing-input-manual-select"]').change();
|
||||
|
||||
var rc_smoothing_auto_smoothness = $('input[name="rcSmoothingAutoSmoothness-number"]');
|
||||
rc_smoothing_auto_smoothness.val(RX_CONFIG.rcSmoothingAutoSmoothness);
|
||||
rc_smoothing_auto_smoothness.val(FC.RX_CONFIG.rcSmoothingAutoSmoothness);
|
||||
} else {
|
||||
$('.tab-receiver .rcSmoothing-auto-smoothness').hide();
|
||||
}
|
||||
|
@ -439,7 +439,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// Only show the MSP control sticks if the MSP Rx feature is enabled
|
||||
$(".sticks_btn").toggle(FEATURE_CONFIG.features.isEnabled('RX_MSP'));
|
||||
$(".sticks_btn").toggle(FC.FEATURE_CONFIG.features.isEnabled('RX_MSP'));
|
||||
|
||||
$('select[name="rx_refresh_rate"]').change(function () {
|
||||
var plot_update_rate = parseInt($(this).val(), 10);
|
||||
|
@ -452,7 +452,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// setup plot
|
||||
var RX_plot_data = new Array(RC.active_channels);
|
||||
var RX_plot_data = new Array(FC.RC.active_channels);
|
||||
for (var i = 0; i < RX_plot_data.length; i++) {
|
||||
RX_plot_data[i] = [];
|
||||
}
|
||||
|
@ -473,17 +473,17 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function update_ui() {
|
||||
|
||||
if (RC.active_channels > 0) {
|
||||
if (FC.RC.active_channels > 0) {
|
||||
|
||||
// update bars with latest data
|
||||
for (var i = 0; i < RC.active_channels; i++) {
|
||||
meter_fill_array[i].css('width', ((RC.channels[i] - meter_scale.min) / (meter_scale.max - meter_scale.min) * 100).clamp(0, 100) + '%');
|
||||
meter_label_array[i].text(RC.channels[i]);
|
||||
for (var i = 0; i < FC.RC.active_channels; i++) {
|
||||
meter_fill_array[i].css('width', ((FC.RC.channels[i] - meter_scale.min) / (meter_scale.max - meter_scale.min) * 100).clamp(0, 100) + '%');
|
||||
meter_label_array[i].text(FC.RC.channels[i]);
|
||||
}
|
||||
|
||||
// push latest data to the main array
|
||||
for (var i = 0; i < RC.active_channels; i++) {
|
||||
RX_plot_data[i].push([samples, RC.channels[i]]);
|
||||
for (var i = 0; i < FC.RC.active_channels; i++) {
|
||||
RX_plot_data[i].push([samples, FC.RC.channels[i]]);
|
||||
}
|
||||
|
||||
// Remove old data from array
|
||||
|
@ -583,15 +583,15 @@ TABS.receiver.initModelPreview = function () {
|
|||
this.model = new Model($('.model_preview'), $('.model_preview canvas'));
|
||||
|
||||
this.useSuperExpo = false;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0") || (semver.gte(CONFIG.apiVersion, "1.16.0") && FEATURE_CONFIG.features.isEnabled('SUPEREXPO_RATES'))) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0") || (semver.gte(FC.CONFIG.apiVersion, "1.16.0") && FC.FEATURE_CONFIG.features.isEnabled('SUPEREXPO_RATES'))) {
|
||||
this.useSuperExpo = true;
|
||||
}
|
||||
|
||||
var useOldRateCurve = false;
|
||||
if (CONFIG.flightControllerIdentifier == 'CLFL' && semver.lt(CONFIG.apiVersion, '2.0.0')) {
|
||||
if (FC.CONFIG.flightControllerIdentifier == 'CLFL' && semver.lt(FC.CONFIG.apiVersion, '2.0.0')) {
|
||||
useOldRateCurve = true;
|
||||
}
|
||||
if (CONFIG.flightControllerIdentifier == 'BTFL' && semver.lt(CONFIG.flightControllerVersion, '2.8.0')) {
|
||||
if (FC.CONFIG.flightControllerIdentifier == 'BTFL' && semver.lt(FC.CONFIG.flightControllerVersion, '2.8.0')) {
|
||||
useOldRateCurve = true;
|
||||
}
|
||||
|
||||
|
@ -605,12 +605,12 @@ TABS.receiver.renderModel = function () {
|
|||
|
||||
if (!this.clock) { this.clock = new THREE.Clock(); }
|
||||
|
||||
if (RC.channels[0] && RC.channels[1] && RC.channels[2]) {
|
||||
if (FC.RC.channels[0] && FC.RC.channels[1] && FC.RC.channels[2]) {
|
||||
var delta = this.clock.getDelta();
|
||||
|
||||
var roll = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[0], RC_tuning.roll_rate, RC_tuning.RC_RATE, RC_tuning.RC_EXPO, this.useSuperExpo, this.deadband, RC_tuning.roll_rate_limit),
|
||||
pitch = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[1], RC_tuning.pitch_rate, RC_tuning.rcPitchRate, RC_tuning.RC_PITCH_EXPO, this.useSuperExpo, this.deadband, RC_tuning.pitch_rate_limit),
|
||||
yaw = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[2], RC_tuning.yaw_rate, RC_tuning.rcYawRate, RC_tuning.RC_YAW_EXPO, this.useSuperExpo, this.yawDeadband, RC_tuning.yaw_rate_limit);
|
||||
var roll = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(FC.RC.channels[0], FC.RC_TUNING.roll_rate, FC.RC_TUNING.RC_RATE, FC.RC_TUNING.RC_EXPO, this.useSuperExpo, this.deadband, FC.RC_TUNING.roll_rate_limit),
|
||||
pitch = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(FC.RC.channels[1], FC.RC_TUNING.pitch_rate, FC.RC_TUNING.rcPitchRate, FC.RC_TUNING.RC_PITCH_EXPO, this.useSuperExpo, this.deadband, FC.RC_TUNING.pitch_rate_limit),
|
||||
yaw = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(FC.RC.channels[2], FC.RC_TUNING.yaw_rate, FC.RC_TUNING.rcYawRate, FC.RC_TUNING.RC_YAW_EXPO, this.useSuperExpo, this.yawDeadband, FC.RC_TUNING.yaw_rate_limit);
|
||||
|
||||
this.model.rotateBy(-degToRad(pitch), -degToRad(yaw), -degToRad(roll));
|
||||
}
|
||||
|
@ -642,7 +642,7 @@ TABS.receiver.refresh = function (callback) {
|
|||
};
|
||||
|
||||
TABS.receiver.updateRcInterpolationParameters = function () {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
|
||||
if ($('select[name="rcInterpolation-select"]').val() === '3') {
|
||||
$('.tab-receiver .rc-interpolation-manual').show();
|
||||
} else {
|
||||
|
@ -659,13 +659,13 @@ function updateInterpolationView() {
|
|||
$('.tab-receiver .rcSmoothing-input-type').show();
|
||||
$('.tab-receiver .rcSmoothing-derivative-manual').show();
|
||||
$('.tab-receiver .rcSmoothing-input-manual').show();
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (RX_CONFIG.rcSmoothingDerivativeCutoff == 0 || RX_CONFIG.rcSmoothingInputCutoff == 0) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
if (FC.RX_CONFIG.rcSmoothingDerivativeCutoff == 0 || FC.RX_CONFIG.rcSmoothingInputCutoff == 0) {
|
||||
$('.tab-receiver .rcSmoothing-auto-smoothness').show();
|
||||
}
|
||||
}
|
||||
|
||||
if (RX_CONFIG.rcSmoothingType == 0) {
|
||||
if (FC.RX_CONFIG.rcSmoothingType == 0) {
|
||||
$('.tab-receiver .rcInterpolation').show();
|
||||
$('.tab-receiver .rcSmoothing-derivative-cutoff').hide();
|
||||
$('.tab-receiver .rcSmoothing-input-cutoff').hide();
|
||||
|
@ -675,10 +675,10 @@ function updateInterpolationView() {
|
|||
$('.tab-receiver .rcSmoothing-input-manual').hide();
|
||||
$('.tab-receiver .rcSmoothing-auto-smoothness').hide();
|
||||
}
|
||||
if (RX_CONFIG.rcSmoothingDerivativeCutoff == 0) {
|
||||
if (FC.RX_CONFIG.rcSmoothingDerivativeCutoff == 0) {
|
||||
$('.tab-receiver .rcSmoothing-derivative-cutoff').hide();
|
||||
}
|
||||
if (RX_CONFIG.rcSmoothingInputCutoff == 0) {
|
||||
if (FC.RX_CONFIG.rcSmoothingInputCutoff == 0) {
|
||||
$('.tab-receiver .rcSmoothing-input-cutoff').hide();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -10,12 +10,12 @@ TABS.sensors.initialize = function (callback) {
|
|||
|
||||
function initSensorData(){
|
||||
for (var i = 0; i < 3; i++) {
|
||||
SENSOR_DATA.accelerometer[i] = 0;
|
||||
SENSOR_DATA.gyroscope[i] = 0;
|
||||
SENSOR_DATA.magnetometer[i] = 0;
|
||||
SENSOR_DATA.sonar = 0;
|
||||
SENSOR_DATA.altitude = 0;
|
||||
SENSOR_DATA.debug[i] = 0;
|
||||
FC.SENSOR_DATA.accelerometer[i] = 0;
|
||||
FC.SENSOR_DATA.gyroscope[i] = 0;
|
||||
FC.SENSOR_DATA.magnetometer[i] = 0;
|
||||
FC.SENSOR_DATA.sonar = 0;
|
||||
FC.SENSOR_DATA.altitude = 0;
|
||||
FC.SENSOR_DATA.debug[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -187,17 +187,17 @@ TABS.sensors.initialize = function (callback) {
|
|||
var checkboxes = $('.tab-sensors .info .checkboxes input');
|
||||
checkboxes.parent().show();
|
||||
|
||||
if (CONFIG.boardType == 0 || CONFIG.boardType == 2) {
|
||||
if (!have_sensor(CONFIG.activeSensors, 'acc')) {
|
||||
if (FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'acc')) {
|
||||
checkboxes.eq(1).prop('disabled', true);
|
||||
}
|
||||
if (!have_sensor(CONFIG.activeSensors, 'mag')) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'mag')) {
|
||||
checkboxes.eq(2).prop('disabled', true);
|
||||
}
|
||||
if (!(have_sensor(CONFIG.activeSensors, 'baro') || (semver.gte(CONFIG.apiVersion, "1.40.0") && have_sensor(CONFIG.activeSensors, 'gps')))) {
|
||||
if (!(have_sensor(FC.CONFIG.activeSensors, 'baro') || (semver.gte(FC.CONFIG.apiVersion, "1.40.0") && have_sensor(FC.CONFIG.activeSensors, 'gps')))) {
|
||||
checkboxes.eq(3).prop('disabled', true);
|
||||
}
|
||||
if (!have_sensor(CONFIG.activeSensors, 'sonar')) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'sonar')) {
|
||||
checkboxes.eq(4).prop('disabled', true);
|
||||
}
|
||||
} else {
|
||||
|
@ -243,7 +243,7 @@ TABS.sensors.initialize = function (callback) {
|
|||
});
|
||||
|
||||
let altitudeHint_e = $('.tab-sensors #sensorsAltitudeHint');
|
||||
if (semver.lt(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
altitudeHint_e.hide();
|
||||
}
|
||||
|
||||
|
@ -367,57 +367,57 @@ TABS.sensors.initialize = function (callback) {
|
|||
if (checkboxes[0]) {
|
||||
updateGraphHelperSize(gyroHelpers);
|
||||
|
||||
samples_gyro_i = addSampleToData(gyro_data, samples_gyro_i, SENSOR_DATA.gyroscope);
|
||||
samples_gyro_i = addSampleToData(gyro_data, samples_gyro_i, FC.SENSOR_DATA.gyroscope);
|
||||
drawGraph(gyroHelpers, gyro_data, samples_gyro_i);
|
||||
raw_data_text_ements.x[0].text(SENSOR_DATA.gyroscope[0].toFixed(2));
|
||||
raw_data_text_ements.y[0].text(SENSOR_DATA.gyroscope[1].toFixed(2));
|
||||
raw_data_text_ements.z[0].text(SENSOR_DATA.gyroscope[2].toFixed(2));
|
||||
raw_data_text_ements.x[0].text(FC.SENSOR_DATA.gyroscope[0].toFixed(2));
|
||||
raw_data_text_ements.y[0].text(FC.SENSOR_DATA.gyroscope[1].toFixed(2));
|
||||
raw_data_text_ements.z[0].text(FC.SENSOR_DATA.gyroscope[2].toFixed(2));
|
||||
}
|
||||
|
||||
if (checkboxes[1]) {
|
||||
updateGraphHelperSize(accelHelpers);
|
||||
|
||||
samples_accel_i = addSampleToData(accel_data, samples_accel_i, SENSOR_DATA.accelerometer);
|
||||
samples_accel_i = addSampleToData(accel_data, samples_accel_i, FC.SENSOR_DATA.accelerometer);
|
||||
drawGraph(accelHelpers, accel_data, samples_accel_i);
|
||||
raw_data_text_ements.x[1].text(SENSOR_DATA.accelerometer[0].toFixed(2));
|
||||
raw_data_text_ements.y[1].text(SENSOR_DATA.accelerometer[1].toFixed(2));
|
||||
raw_data_text_ements.z[1].text(SENSOR_DATA.accelerometer[2].toFixed(2));
|
||||
raw_data_text_ements.x[1].text(FC.SENSOR_DATA.accelerometer[0].toFixed(2));
|
||||
raw_data_text_ements.y[1].text(FC.SENSOR_DATA.accelerometer[1].toFixed(2));
|
||||
raw_data_text_ements.z[1].text(FC.SENSOR_DATA.accelerometer[2].toFixed(2));
|
||||
}
|
||||
|
||||
if (checkboxes[2]) {
|
||||
updateGraphHelperSize(magHelpers);
|
||||
|
||||
samples_mag_i = addSampleToData(mag_data, samples_mag_i, SENSOR_DATA.magnetometer);
|
||||
samples_mag_i = addSampleToData(mag_data, samples_mag_i, FC.SENSOR_DATA.magnetometer);
|
||||
drawGraph(magHelpers, mag_data, samples_mag_i);
|
||||
raw_data_text_ements.x[2].text(SENSOR_DATA.magnetometer[0].toFixed(2));
|
||||
raw_data_text_ements.y[2].text(SENSOR_DATA.magnetometer[1].toFixed(2));
|
||||
raw_data_text_ements.z[2].text(SENSOR_DATA.magnetometer[2].toFixed(2));
|
||||
raw_data_text_ements.x[2].text(FC.SENSOR_DATA.magnetometer[0].toFixed(2));
|
||||
raw_data_text_ements.y[2].text(FC.SENSOR_DATA.magnetometer[1].toFixed(2));
|
||||
raw_data_text_ements.z[2].text(FC.SENSOR_DATA.magnetometer[2].toFixed(2));
|
||||
}
|
||||
}
|
||||
|
||||
function update_altitude_graph() {
|
||||
updateGraphHelperSize(altitudeHelpers);
|
||||
|
||||
samples_altitude_i = addSampleToData(altitude_data, samples_altitude_i, [SENSOR_DATA.altitude]);
|
||||
samples_altitude_i = addSampleToData(altitude_data, samples_altitude_i, [FC.SENSOR_DATA.altitude]);
|
||||
drawGraph(altitudeHelpers, altitude_data, samples_altitude_i);
|
||||
raw_data_text_ements.x[3].text(SENSOR_DATA.altitude.toFixed(2));
|
||||
raw_data_text_ements.x[3].text(FC.SENSOR_DATA.altitude.toFixed(2));
|
||||
}
|
||||
|
||||
function update_sonar_graphs() {
|
||||
updateGraphHelperSize(sonarHelpers);
|
||||
|
||||
samples_sonar_i = addSampleToData(sonar_data, samples_sonar_i, [SENSOR_DATA.sonar]);
|
||||
samples_sonar_i = addSampleToData(sonar_data, samples_sonar_i, [FC.SENSOR_DATA.sonar]);
|
||||
drawGraph(sonarHelpers, sonar_data, samples_sonar_i);
|
||||
raw_data_text_ements.x[4].text(SENSOR_DATA.sonar.toFixed(2));
|
||||
raw_data_text_ements.x[4].text(FC.SENSOR_DATA.sonar.toFixed(2));
|
||||
}
|
||||
|
||||
function update_debug_graphs() {
|
||||
for (var i = 0; i < 4; i++) {
|
||||
updateGraphHelperSize(debugHelpers[i]);
|
||||
|
||||
addSampleToData(debug_data[i], samples_debug_i, [SENSOR_DATA.debug[i]]);
|
||||
addSampleToData(debug_data[i], samples_debug_i, [FC.SENSOR_DATA.debug[i]]);
|
||||
drawGraph(debugHelpers[i], debug_data[i], samples_debug_i);
|
||||
raw_data_text_ements.x[5 + i].text(SENSOR_DATA.debug[i]);
|
||||
raw_data_text_ements.x[5 + i].text(FC.SENSOR_DATA.debug[i]);
|
||||
}
|
||||
samples_debug_i++;
|
||||
}
|
||||
|
|
|
@ -30,7 +30,7 @@ TABS.servos.initialize = function (callback) {
|
|||
|
||||
function update_ui() {
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0") || SERVO_CONFIG.length === 0) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.12.0") || FC.SERVO_CONFIG.length === 0) {
|
||||
|
||||
$(".tab-servos").removeClass("supported");
|
||||
return;
|
||||
|
@ -40,14 +40,14 @@ TABS.servos.initialize = function (callback) {
|
|||
|
||||
let servoCheckbox = '';
|
||||
let servoHeader = '';
|
||||
for (let i = 0; i < RC.active_channels-4; i++) {
|
||||
for (let i = 0; i < FC.RC.active_channels-4; i++) {
|
||||
servoHeader = servoHeader + '\
|
||||
<th >A' + (i+1) + '</th>\
|
||||
';
|
||||
}
|
||||
servoHeader = servoHeader + '<th style="width: 110px" i18n="servosDirectionAndRate"></th>';
|
||||
|
||||
for (let i = 0; i < RC.active_channels; i++) {
|
||||
for (let i = 0; i < FC.RC.active_channels; i++) {
|
||||
servoCheckbox = servoCheckbox + '\
|
||||
<td class="channel"><input type="checkbox"/></td>\
|
||||
';
|
||||
|
@ -62,17 +62,17 @@ TABS.servos.initialize = function (callback) {
|
|||
$('div.tab-servos table.fields').append('\
|
||||
<tr> \
|
||||
<td style="text-align: center">' + name + '</td>\
|
||||
<td class="middle"><input type="number" min="500" max="2500" value="' + SERVO_CONFIG[obj].middle + '" /></td>\
|
||||
<td class="min"><input type="number" min="500" max="2500" value="' + SERVO_CONFIG[obj].min +'" /></td>\
|
||||
<td class="max"><input type="number" min="500" max="2500" value="' + SERVO_CONFIG[obj].max +'" /></td>\
|
||||
<td class="middle"><input type="number" min="500" max="2500" value="' + FC.SERVO_CONFIG[obj].middle + '" /></td>\
|
||||
<td class="min"><input type="number" min="500" max="2500" value="' + FC.SERVO_CONFIG[obj].min +'" /></td>\
|
||||
<td class="max"><input type="number" min="500" max="2500" value="' + FC.SERVO_CONFIG[obj].max +'" /></td>\
|
||||
' + servoCheckbox + '\
|
||||
<td class="direction">\
|
||||
</td>\
|
||||
</tr> \
|
||||
');
|
||||
|
||||
if (SERVO_CONFIG[obj].indexOfChannelToForward >= 0) {
|
||||
$('div.tab-servos table.fields tr:last td.channel input').eq(SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
if (FC.SERVO_CONFIG[obj].indexOfChannelToForward >= 0) {
|
||||
$('div.tab-servos table.fields tr:last td.channel input').eq(FC.SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
}
|
||||
|
||||
// adding select box and generating options
|
||||
|
@ -87,7 +87,7 @@ TABS.servos.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// select current rate
|
||||
select.val(SERVO_CONFIG[obj].rate);
|
||||
select.val(FC.SERVO_CONFIG[obj].rate);
|
||||
|
||||
$('div.tab-servos table.fields tr:last').data('info', {'obj': obj});
|
||||
|
||||
|
@ -112,15 +112,15 @@ TABS.servos.initialize = function (callback) {
|
|||
channelIndex = undefined;
|
||||
}
|
||||
|
||||
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||
FC.SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||
|
||||
|
||||
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
||||
SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
|
||||
SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
|
||||
FC.SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
||||
FC.SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
|
||||
FC.SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
|
||||
|
||||
const val = parseInt($('.direction select', this).val());
|
||||
SERVO_CONFIG[info.obj].rate = val;
|
||||
FC.SERVO_CONFIG[info.obj].rate = val;
|
||||
});
|
||||
|
||||
//
|
||||
|
|
|
@ -29,11 +29,11 @@ TABS.setup.initialize = function (callback) {
|
|||
// translate to user-selected language
|
||||
i18n.localizePage();
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_BACKUP_RESTORE)) {
|
||||
if (semver.lt(FC.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.API_VERSION_MIN_SUPPORTED_BACKUP_RESTORE]));
|
||||
GUI.log(i18n.getMessage('initialSetupBackupAndRestoreApiVersion', [FC.CONFIG.apiVersion, CONFIGURATOR.API_VERSION_MIN_SUPPORTED_BACKUP_RESTORE]));
|
||||
}
|
||||
|
||||
// initialize 3D Model
|
||||
|
@ -47,12 +47,12 @@ TABS.setup.initialize = function (callback) {
|
|||
$('span.heading').text(i18n.getMessage('initialSetupAttitude', [0]));
|
||||
|
||||
// check if we have accelerometer and magnetometer
|
||||
if (!have_sensor(CONFIG.activeSensors, 'acc')) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'acc')) {
|
||||
$('a.calibrateAccel').addClass('disabled');
|
||||
$('default_btn').addClass('disabled');
|
||||
}
|
||||
|
||||
if (!have_sensor(CONFIG.activeSensors, 'mag')) {
|
||||
if (!have_sensor(FC.CONFIG.activeSensors, 'mag')) {
|
||||
$('a.calibrateMag').addClass('disabled');
|
||||
$('default_btn').addClass('disabled');
|
||||
}
|
||||
|
@ -61,7 +61,7 @@ TABS.setup.initialize = function (callback) {
|
|||
|
||||
$('#arming-disable-flag').attr('title', i18n.getMessage('initialSetupArmingDisableFlagsTooltip'));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.40.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.40.0")) {
|
||||
if (isExpertModeEnabled()) {
|
||||
$('.initialSetupRebootBootloader').show();
|
||||
} else {
|
||||
|
@ -151,7 +151,7 @@ TABS.setup.initialize = function (callback) {
|
|||
|
||||
// reset yaw button hook
|
||||
$('div#interactive_block > a.reset').click(function () {
|
||||
self.yaw_fix = SENSOR_DATA.kinematics[2] * - 1.0;
|
||||
self.yaw_fix = FC.SENSOR_DATA.kinematics[2] * - 1.0;
|
||||
$(this).text(i18n.getMessage('initialSetupButtonResetZaxisValue', [self.yaw_fix]));
|
||||
|
||||
console.log('YAW reset to 0 deg, fix: ' + self.yaw_fix + ' deg');
|
||||
|
@ -194,7 +194,7 @@ TABS.setup.initialize = function (callback) {
|
|||
pitch_e = $('dd.pitch'),
|
||||
heading_e = $('dd.heading');
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.36.0")) {
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
arming_disable_flags_e.hide();
|
||||
}
|
||||
|
||||
|
@ -220,26 +220,26 @@ TABS.setup.initialize = function (callback) {
|
|||
'MSP',
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.38.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.38.0")) {
|
||||
disarmFlagElements.splice(disarmFlagElements.indexOf('THROTTLE'), 0, 'RUNAWAY_TAKEOFF');
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.39.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.39.0")) {
|
||||
disarmFlagElements = disarmFlagElements.concat(['PARALYZE',
|
||||
'GPS']);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
disarmFlagElements.splice(disarmFlagElements.indexOf('OSD_MENU'), 1);
|
||||
disarmFlagElements = disarmFlagElements.concat(['RESC']);
|
||||
disarmFlagElements = disarmFlagElements.concat(['RPMFILTER']);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
disarmFlagElements.splice(disarmFlagElements.indexOf('THROTTLE'), 0, 'CRASH');
|
||||
disarmFlagElements = disarmFlagElements.concat(['REBOOT_REQD',
|
||||
'DSHOT_BBANG']);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_43)) {
|
||||
disarmFlagElements = disarmFlagElements.concat(['NO_ACC_CAL', 'MOTOR_PROTO']);
|
||||
}
|
||||
|
||||
|
@ -250,14 +250,14 @@ TABS.setup.initialize = function (callback) {
|
|||
arming_disable_flags_e.append('<span id="initialSetupArmingAllowed" i18n="initialSetupArmingAllowed" style="display: none;"></span>');
|
||||
|
||||
// Arming disabled flags
|
||||
for (var i = 0; i < CONFIG.armingDisableCount; i++) {
|
||||
for (var i = 0; i < FC.CONFIG.armingDisableCount; i++) {
|
||||
|
||||
// All the known elements but the ARM_SWITCH (it must be always the last element)
|
||||
if (i < disarmFlagElements.length - 1) {
|
||||
arming_disable_flags_e.append('<span id="initialSetupArmingDisableFlags' + i + '" class="cf_tip disarm-flag" title="' + i18n.getMessage('initialSetupArmingDisableFlagsTooltip' + disarmFlagElements[i]) + '" style="display: none;">' + disarmFlagElements[i] + '</span>');
|
||||
|
||||
// The ARM_SWITCH, always the last element
|
||||
} else if (i == CONFIG.armingDisableCount - 1) {
|
||||
} else if (i == FC.CONFIG.armingDisableCount - 1) {
|
||||
arming_disable_flags_e.append('<span id="initialSetupArmingDisableFlags' + i + '" class="cf_tip disarm-flag" title="' + i18n.getMessage('initialSetupArmingDisableFlagsTooltipARM_SWITCH') + '" style="display: none;">ARM_SWITCH</span>');
|
||||
|
||||
// Unknown disarm flags
|
||||
|
@ -273,36 +273,36 @@ TABS.setup.initialize = function (callback) {
|
|||
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
|
||||
$('#initialSetupArmingAllowed').toggle(CONFIG.armingDisableFlags == 0);
|
||||
$('#initialSetupArmingAllowed').toggle(FC.CONFIG.armingDisableFlags == 0);
|
||||
|
||||
for (var i = 0; i < CONFIG.armingDisableCount; i++) {
|
||||
$('#initialSetupArmingDisableFlags'+i).css('display',(CONFIG.armingDisableFlags & (1 << i)) == 0 ? 'none':'inline-block');
|
||||
for (var i = 0; i < FC.CONFIG.armingDisableCount; i++) {
|
||||
$('#initialSetupArmingDisableFlags'+i).css('display',(FC.CONFIG.armingDisableFlags & (1 << i)) == 0 ? 'none':'inline-block');
|
||||
}
|
||||
|
||||
});
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
|
||||
bat_voltage_e.text(i18n.getMessage('initialSetupBatteryValue', [ANALOG.voltage]));
|
||||
bat_mah_drawn_e.text(i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn]));
|
||||
bat_mah_drawing_e.text(i18n.getMessage('initialSetupBatteryAValue', [ANALOG.amperage.toFixed(2)]));
|
||||
rssi_e.text(i18n.getMessage('initialSetupRSSIValue', [((ANALOG.rssi / 1023) * 100).toFixed(0)]));
|
||||
bat_voltage_e.text(i18n.getMessage('initialSetupBatteryValue', [FC.ANALOG.voltage]));
|
||||
bat_mah_drawn_e.text(i18n.getMessage('initialSetupBatteryMahValue', [FC.ANALOG.mAhdrawn]));
|
||||
bat_mah_drawing_e.text(i18n.getMessage('initialSetupBatteryAValue', [FC.ANALOG.amperage.toFixed(2)]));
|
||||
rssi_e.text(i18n.getMessage('initialSetupRSSIValue', [((FC.ANALOG.rssi / 1023) * 100).toFixed(0)]));
|
||||
});
|
||||
|
||||
if (have_sensor(CONFIG.activeSensors, 'gps')) {
|
||||
if (have_sensor(FC.CONFIG.activeSensors, 'gps')) {
|
||||
MSP.send_message(MSPCodes.MSP_RAW_GPS, false, false, function () {
|
||||
gpsFix_e.html((GPS_DATA.fix) ? i18n.getMessage('gpsFixTrue') : i18n.getMessage('gpsFixFalse'));
|
||||
gpsSats_e.text(GPS_DATA.numSat);
|
||||
gpsLat_e.text((GPS_DATA.lat / 10000000).toFixed(4) + ' deg');
|
||||
gpsLon_e.text((GPS_DATA.lon / 10000000).toFixed(4) + ' deg');
|
||||
gpsFix_e.html((FC.GPS_DATA.fix) ? i18n.getMessage('gpsFixTrue') : i18n.getMessage('gpsFixFalse'));
|
||||
gpsSats_e.text(FC.GPS_DATA.numSat);
|
||||
gpsLat_e.text((FC.GPS_DATA.lat / 10000000).toFixed(4) + ' deg');
|
||||
gpsLon_e.text((FC.GPS_DATA.lon / 10000000).toFixed(4) + ' deg');
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
function get_fast_data() {
|
||||
MSP.send_message(MSPCodes.MSP_ATTITUDE, false, false, function () {
|
||||
roll_e.text(i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[0]]));
|
||||
pitch_e.text(i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[1]]));
|
||||
heading_e.text(i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[2]]));
|
||||
roll_e.text(i18n.getMessage('initialSetupAttitude', [FC.SENSOR_DATA.kinematics[0]]));
|
||||
pitch_e.text(i18n.getMessage('initialSetupAttitude', [FC.SENSOR_DATA.kinematics[1]]));
|
||||
heading_e.text(i18n.getMessage('initialSetupAttitude', [FC.SENSOR_DATA.kinematics[2]]));
|
||||
|
||||
self.renderModel();
|
||||
self.updateInstruments();
|
||||
|
@ -322,9 +322,9 @@ TABS.setup.initializeInstruments = function() {
|
|||
var heading = $.flightIndicator('#heading', 'heading', options);
|
||||
|
||||
this.updateInstruments = function() {
|
||||
attitude.setRoll(SENSOR_DATA.kinematics[0]);
|
||||
attitude.setPitch(SENSOR_DATA.kinematics[1]);
|
||||
heading.setHeading(SENSOR_DATA.kinematics[2]);
|
||||
attitude.setRoll(FC.SENSOR_DATA.kinematics[0]);
|
||||
attitude.setPitch(FC.SENSOR_DATA.kinematics[1]);
|
||||
heading.setHeading(FC.SENSOR_DATA.kinematics[2]);
|
||||
};
|
||||
};
|
||||
|
||||
|
@ -335,9 +335,9 @@ TABS.setup.initModel = function () {
|
|||
};
|
||||
|
||||
TABS.setup.renderModel = function () {
|
||||
var x = (SENSOR_DATA.kinematics[1] * -1.0) * 0.017453292519943295,
|
||||
y = ((SENSOR_DATA.kinematics[2] * -1.0) - this.yaw_fix) * 0.017453292519943295,
|
||||
z = (SENSOR_DATA.kinematics[0] * -1.0) * 0.017453292519943295;
|
||||
var x = (FC.SENSOR_DATA.kinematics[1] * -1.0) * 0.017453292519943295,
|
||||
y = ((FC.SENSOR_DATA.kinematics[2] * -1.0) - this.yaw_fix) * 0.017453292519943295,
|
||||
z = (FC.SENSOR_DATA.kinematics[0] * -1.0) * 0.017453292519943295;
|
||||
|
||||
this.model.rotateTo(x, y, z);
|
||||
};
|
||||
|
|
|
@ -115,8 +115,8 @@ TABS.transponder.initialize = function(callback, scrollPosition) {
|
|||
//googleAnalytics.sendAppView('Transponder');
|
||||
}
|
||||
// transponder supported added in MSP API Version 1.16.0
|
||||
if ( CONFIG ) {
|
||||
TABS.transponder.available = semver.gte(CONFIG.apiVersion, "1.16.0");
|
||||
if ( FC.CONFIG ) {
|
||||
TABS.transponder.available = semver.gte(FC.CONFIG.apiVersion, "1.16.0");
|
||||
}
|
||||
//////////////
|
||||
if ( !TABS.transponder.available ) {
|
||||
|
@ -243,9 +243,9 @@ TABS.transponder.initialize = function(callback, scrollPosition) {
|
|||
let hexRegExp = new RegExp('[0-9a-fA-F]{' + (transponderProvider.dataLength * 2) + '}', 'gi');
|
||||
|
||||
if ( !dataString.match(hexRegExp) ) {
|
||||
TRANSPONDER.data = [];
|
||||
FC.TRANSPONDER.data = [];
|
||||
} else {
|
||||
TRANSPONDER.data = hexToBytes(dataString);
|
||||
FC.TRANSPONDER.data = hexToBytes(dataString);
|
||||
}
|
||||
_persistentInputValues[transponderProvider.id] = dataString;
|
||||
};
|
||||
|
@ -260,7 +260,7 @@ TABS.transponder.initialize = function(callback, scrollPosition) {
|
|||
*/
|
||||
function toggleTransponderType() {
|
||||
|
||||
TRANSPONDER.provider = $(this).val();
|
||||
FC.TRANSPONDER.provider = $(this).val();
|
||||
let defaultProvider = $(this).attr('data-defaultValue');
|
||||
if ( defaultProvider == $(this).val() ) {
|
||||
$('.save_reboot').hide();
|
||||
|
@ -271,25 +271,25 @@ TABS.transponder.initialize = function(callback, scrollPosition) {
|
|||
}
|
||||
|
||||
let clearValue = true;
|
||||
buildDataBlockForTransponderProviders(TRANSPONDER.providers.find(function(provider) {
|
||||
return provider.id == TRANSPONDER.provider;
|
||||
}), bytesToHex(TRANSPONDER.data), clearValue);
|
||||
buildDataBlockForTransponderProviders(FC.TRANSPONDER.providers.find(function(provider) {
|
||||
return provider.id == FC.TRANSPONDER.provider;
|
||||
}), bytesToHex(FC.TRANSPONDER.data), clearValue);
|
||||
}
|
||||
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_TRANSPONDER_CONFIG, false, false, load_html);
|
||||
|
||||
function process_html() {
|
||||
$(".tab-transponder").toggleClass("transponder-supported", TABS.transponder.available && TRANSPONDER.supported);
|
||||
$(".tab-transponder").toggleClass("transponder-supported", TABS.transponder.available && FC.TRANSPONDER.supported);
|
||||
|
||||
i18n.localizePage();
|
||||
|
||||
if ( TABS.transponder.available && TRANSPONDER.providers.length > 0 ) {
|
||||
if ( TABS.transponder.available && FC.TRANSPONDER.providers.length > 0 ) {
|
||||
|
||||
fillByTransponderProviders(TRANSPONDER.providers, TRANSPONDER.provider, toggleTransponderType);
|
||||
buildDataBlockForTransponderProviders(TRANSPONDER.providers.find(function(provider) {
|
||||
return provider.id == TRANSPONDER.provider;
|
||||
}), bytesToHex(TRANSPONDER.data));
|
||||
fillByTransponderProviders(FC.TRANSPONDER.providers, FC.TRANSPONDER.provider, toggleTransponderType);
|
||||
buildDataBlockForTransponderProviders(FC.TRANSPONDER.providers.find(function(provider) {
|
||||
return provider.id == FC.TRANSPONDER.provider;
|
||||
}), bytesToHex(FC.TRANSPONDER.data));
|
||||
|
||||
|
||||
$('a.save').click(function() {
|
||||
|
@ -311,8 +311,8 @@ TABS.transponder.initialize = function(callback, scrollPosition) {
|
|||
});
|
||||
}
|
||||
|
||||
if (TRANSPONDER.provider !== "0" && TRANSPONDER.data.length !== TRANSPONDER.providers.find(function(provider) {
|
||||
return provider.id == TRANSPONDER.provider;
|
||||
if (FC.TRANSPONDER.provider !== "0" && FC.TRANSPONDER.data.length !== FC.TRANSPONDER.providers.find(function(provider) {
|
||||
return provider.id == FC.TRANSPONDER.provider;
|
||||
}).dataLength ) {
|
||||
GUI.log(i18n.getMessage('transponderDataInvalid'));
|
||||
} else {
|
||||
|
|
|
@ -23,7 +23,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
|
||||
self.analyticsChanges = {};
|
||||
|
||||
this.supported = semver.gte(CONFIG.apiVersion, "1.42.0");
|
||||
this.supported = semver.gte(FC.CONFIG.apiVersion, "1.42.0");
|
||||
|
||||
if (!this.supported) {
|
||||
load_html();
|
||||
|
@ -65,14 +65,14 @@ TABS.vtx.initialize = function (callback) {
|
|||
TABS.vtx.VTXTABLE_BAND_LIST = [];
|
||||
vtxtable_bands.counter = 1;
|
||||
} else {
|
||||
TABS.vtx.VTXTABLE_BAND_LIST.push(Object.assign({}, VTXTABLE_BAND));
|
||||
TABS.vtx.VTXTABLE_BAND_LIST.push(Object.assign({}, FC.VTXTABLE_BAND));
|
||||
vtxtable_bands.counter++;
|
||||
}
|
||||
|
||||
const buffer = [];
|
||||
buffer.push8(vtxtable_bands.counter);
|
||||
|
||||
if (vtxtable_bands.counter <= VTX_CONFIG.vtx_table_bands) {
|
||||
if (vtxtable_bands.counter <= FC.VTX_CONFIG.vtx_table_bands) {
|
||||
MSP.send_message(MSPCodes.MSP_VTXTABLE_BAND, buffer, false, vtxtable_bands);
|
||||
} else {
|
||||
vtxtable_bands.counter = undefined;
|
||||
|
@ -88,14 +88,14 @@ TABS.vtx.initialize = function (callback) {
|
|||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST = [];
|
||||
vtxtable_powerlevels.counter = 1;
|
||||
} else {
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST.push(Object.assign({}, VTXTABLE_POWERLEVEL));
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST.push(Object.assign({}, FC.VTXTABLE_POWERLEVEL));
|
||||
vtxtable_powerlevels.counter++;
|
||||
}
|
||||
|
||||
const buffer = [];
|
||||
buffer.push8(vtxtable_powerlevels.counter);
|
||||
|
||||
if (vtxtable_powerlevels.counter <= VTX_CONFIG.vtx_table_powerlevels) {
|
||||
if (vtxtable_powerlevels.counter <= FC.VTX_CONFIG.vtx_table_powerlevels) {
|
||||
MSP.send_message(MSPCodes.MSP_VTXTABLE_POWERLEVEL, buffer, false, vtxtable_powerlevels);
|
||||
} else {
|
||||
vtxtable_powerlevels.counter = undefined;
|
||||
|
@ -144,12 +144,12 @@ TABS.vtx.initialize = function (callback) {
|
|||
function read_vtx_config_json(vtxConfig, vtxcallback_after_read) {
|
||||
|
||||
// Bands and channels
|
||||
VTX_CONFIG.vtx_table_bands = vtxConfig.vtx_table.bands_list.length;
|
||||
FC.VTX_CONFIG.vtx_table_bands = vtxConfig.vtx_table.bands_list.length;
|
||||
|
||||
|
||||
let maxChannels = 0;
|
||||
TABS.vtx.VTXTABLE_BAND_LIST = [];
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_bands; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_bands; i++) {
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1] = {};
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_number = i;
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_name = vtxConfig.vtx_table.bands_list[i - 1].name;
|
||||
|
@ -160,13 +160,13 @@ TABS.vtx.initialize = function (callback) {
|
|||
maxChannels = Math.max(maxChannels, TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_frequencies.length);
|
||||
}
|
||||
|
||||
VTX_CONFIG.vtx_table_channels = maxChannels;
|
||||
FC.VTX_CONFIG.vtx_table_channels = maxChannels;
|
||||
|
||||
// Power levels
|
||||
VTX_CONFIG.vtx_table_powerlevels = vtxConfig.vtx_table.powerlevels_list.length;
|
||||
FC.VTX_CONFIG.vtx_table_powerlevels = vtxConfig.vtx_table.powerlevels_list.length;
|
||||
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST = [];
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1] = {};
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_number = i;
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_value = vtxConfig.vtx_table.powerlevels_list[i - 1].value;
|
||||
|
@ -197,15 +197,15 @@ TABS.vtx.initialize = function (callback) {
|
|||
});
|
||||
|
||||
// Supported?
|
||||
const vtxSupported = VTX_CONFIG.vtx_type !== 0 && VTX_CONFIG.vtx_type !== 255;
|
||||
const vtxTableNotConfigured = vtxSupported && VTX_CONFIG.vtx_table_available &&
|
||||
(VTX_CONFIG.vtx_table_bands === 0 || VTX_CONFIG.vtx_table_channels === 0 || VTX_CONFIG.vtx_table_powerlevels === 0);
|
||||
const vtxSupported = FC.VTX_CONFIG.vtx_type !== 0 && FC.VTX_CONFIG.vtx_type !== 255;
|
||||
const vtxTableNotConfigured = vtxSupported && FC.VTX_CONFIG.vtx_table_available &&
|
||||
(FC.VTX_CONFIG.vtx_table_bands === 0 || FC.VTX_CONFIG.vtx_table_channels === 0 || FC.VTX_CONFIG.vtx_table_powerlevels === 0);
|
||||
|
||||
TABS.vtx.vtxTableFactoryBandsSupported = VTX_CONFIG.vtx_type === 3;
|
||||
TABS.vtx.vtxTableFactoryBandsSupported = FC.VTX_CONFIG.vtx_type === 3;
|
||||
|
||||
$(".vtx_supported").toggle(vtxSupported);
|
||||
$(".vtx_not_supported").toggle(!vtxSupported);
|
||||
$(".vtx_table_available").toggle(vtxSupported && VTX_CONFIG.vtx_table_available);
|
||||
$(".vtx_table_available").toggle(vtxSupported && FC.VTX_CONFIG.vtx_table_available);
|
||||
$(".vtx_table_not_configured").toggle(vtxTableNotConfigured);
|
||||
$(".vtx_table_save_pending").toggle(TABS.vtx.vtxTableSavePending);
|
||||
$(".factory_band").toggle(TABS.vtx.vtxTableFactoryBandsSupported);
|
||||
|
@ -215,63 +215,63 @@ TABS.vtx.initialize = function (callback) {
|
|||
|
||||
// Insert actual values in the fields
|
||||
// Values of the selected mode
|
||||
$("#vtx_frequency").val(VTX_CONFIG.vtx_frequency);
|
||||
$("#vtx_band").val(VTX_CONFIG.vtx_band);
|
||||
$("#vtx_frequency").val(FC.VTX_CONFIG.vtx_frequency);
|
||||
$("#vtx_band").val(FC.VTX_CONFIG.vtx_band);
|
||||
|
||||
$("#vtx_band").change(populateChannelSelect).change();
|
||||
|
||||
$("#vtx_channel").val(VTX_CONFIG.vtx_channel);
|
||||
if (VTX_CONFIG.vtx_table_available) {
|
||||
$("#vtx_channel").attr("max", VTX_CONFIG.vtx_table_channels);
|
||||
$("#vtx_channel").val(FC.VTX_CONFIG.vtx_channel);
|
||||
if (FC.VTX_CONFIG.vtx_table_available) {
|
||||
$("#vtx_channel").attr("max", FC.VTX_CONFIG.vtx_table_channels);
|
||||
}
|
||||
|
||||
$("#vtx_power").val(VTX_CONFIG.vtx_power);
|
||||
$("#vtx_pit_mode").prop('checked', VTX_CONFIG.vtx_pit_mode);
|
||||
$("#vtx_pit_mode_frequency").val(VTX_CONFIG.vtx_pit_mode_frequency);
|
||||
$("#vtx_low_power_disarm").val(VTX_CONFIG.vtx_low_power_disarm);
|
||||
$("#vtx_power").val(FC.VTX_CONFIG.vtx_power);
|
||||
$("#vtx_pit_mode").prop('checked', FC.VTX_CONFIG.vtx_pit_mode);
|
||||
$("#vtx_pit_mode_frequency").val(FC.VTX_CONFIG.vtx_pit_mode_frequency);
|
||||
$("#vtx_low_power_disarm").val(FC.VTX_CONFIG.vtx_low_power_disarm);
|
||||
|
||||
// Values of the current values
|
||||
const yesMessage = i18n.getMessage("yes");
|
||||
const noMessage = i18n.getMessage("no");
|
||||
|
||||
$("#vtx_device_ready_description").text(VTX_CONFIG.vtx_device_ready ? yesMessage : noMessage);
|
||||
$("#vtx_type_description").text(i18n.getMessage(`vtxType_${VTX_CONFIG.vtx_type}`));
|
||||
$("#vtx_channel_description").text(VTX_CONFIG.vtx_channel);
|
||||
$("#vtx_frequency_description").text(VTX_CONFIG.vtx_frequency);
|
||||
$("#vtx_pit_mode_description").text(VTX_CONFIG.vtx_pit_mode ? yesMessage : noMessage);
|
||||
$("#vtx_pit_mode_frequency_description").text(VTX_CONFIG.vtx_pit_mode_frequency);
|
||||
$("#vtx_low_power_disarm_description").text(i18n.getMessage(`vtxLowPowerDisarmOption_${VTX_CONFIG.vtx_low_power_disarm}`));
|
||||
$("#vtx_device_ready_description").text(FC.VTX_CONFIG.vtx_device_ready ? yesMessage : noMessage);
|
||||
$("#vtx_type_description").text(i18n.getMessage(`vtxType_${FC.VTX_CONFIG.vtx_type}`));
|
||||
$("#vtx_channel_description").text(FC.VTX_CONFIG.vtx_channel);
|
||||
$("#vtx_frequency_description").text(FC.VTX_CONFIG.vtx_frequency);
|
||||
$("#vtx_pit_mode_description").text(FC.VTX_CONFIG.vtx_pit_mode ? yesMessage : noMessage);
|
||||
$("#vtx_pit_mode_frequency_description").text(FC.VTX_CONFIG.vtx_pit_mode_frequency);
|
||||
$("#vtx_low_power_disarm_description").text(i18n.getMessage(`vtxLowPowerDisarmOption_${FC.VTX_CONFIG.vtx_low_power_disarm}`));
|
||||
|
||||
if (VTX_CONFIG.vtx_band === 0) {
|
||||
if (FC.VTX_CONFIG.vtx_band === 0) {
|
||||
$("#vtx_band_description").text(i18n.getMessage("vtxBand_0"));
|
||||
} else {
|
||||
if (VTX_CONFIG.vtx_table_available && TABS.vtx.VTXTABLE_BAND_LIST[VTX_CONFIG.vtx_band - 1]) {
|
||||
let bandName = TABS.vtx.VTXTABLE_BAND_LIST[VTX_CONFIG.vtx_band - 1].vtxtable_band_name;
|
||||
if (FC.VTX_CONFIG.vtx_table_available && TABS.vtx.VTXTABLE_BAND_LIST[FC.VTX_CONFIG.vtx_band - 1]) {
|
||||
let bandName = TABS.vtx.VTXTABLE_BAND_LIST[FC.VTX_CONFIG.vtx_band - 1].vtxtable_band_name;
|
||||
if (bandName.trim() === '') {
|
||||
bandName = VTX_CONFIG.vtx_band;
|
||||
bandName = FC.VTX_CONFIG.vtx_band;
|
||||
}
|
||||
$("#vtx_band_description").text(bandName);
|
||||
} else {
|
||||
$("#vtx_band_description").text(VTX_CONFIG.vtx_band);
|
||||
$("#vtx_band_description").text(FC.VTX_CONFIG.vtx_band);
|
||||
}
|
||||
}
|
||||
|
||||
if (VTX_CONFIG.vtx_power === 0) {
|
||||
if (FC.VTX_CONFIG.vtx_power === 0) {
|
||||
$("#vtx_power_description").text(i18n.getMessage("vtxPower_0"));
|
||||
} else {
|
||||
if (VTX_CONFIG.vtx_table_available) {
|
||||
let powerLevel = TABS.vtx.VTXTABLE_POWERLEVEL_LIST[VTX_CONFIG.vtx_power - 1].vtxtable_powerlevel_label;
|
||||
if (FC.VTX_CONFIG.vtx_table_available) {
|
||||
let powerLevel = TABS.vtx.VTXTABLE_POWERLEVEL_LIST[FC.VTX_CONFIG.vtx_power - 1].vtxtable_powerlevel_label;
|
||||
if (powerLevel.trim() === '') {
|
||||
powerLevel = VTX_CONFIG.vtx_power;
|
||||
powerLevel = FC.VTX_CONFIG.vtx_power;
|
||||
}
|
||||
$("#vtx_power_description").text(powerLevel);
|
||||
} else {
|
||||
const levelText = i18n.getMessage('vtxPower_X', {powerLevel: VTX_CONFIG.vtx_power});
|
||||
const levelText = i18n.getMessage('vtxPower_X', {powerLevel: FC.VTX_CONFIG.vtx_power});
|
||||
$("#vtx_power_description").text(levelText);
|
||||
}
|
||||
}
|
||||
|
||||
$("#vtx_table_powerlevels").val(VTX_CONFIG.vtx_table_powerlevels);
|
||||
$("#vtx_table_powerlevels").val(FC.VTX_CONFIG.vtx_table_powerlevels);
|
||||
|
||||
// Populate power levels
|
||||
for (let i = 1; i <= TABS.vtx.VTXTABLE_POWERLEVEL_LIST.length; i++) {
|
||||
|
@ -279,8 +279,8 @@ TABS.vtx.initialize = function (callback) {
|
|||
$(`#vtx_table_powerlabels_${i}`).val(TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_label);
|
||||
}
|
||||
|
||||
$("#vtx_table_bands").val(VTX_CONFIG.vtx_table_bands);
|
||||
$("#vtx_table_channels").val(VTX_CONFIG.vtx_table_channels);
|
||||
$("#vtx_table_bands").val(FC.VTX_CONFIG.vtx_table_bands);
|
||||
$("#vtx_table_channels").val(FC.VTX_CONFIG.vtx_table_channels);
|
||||
|
||||
// Populate VTX Table
|
||||
let hasFactoryBands = false;
|
||||
|
@ -317,7 +317,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
}
|
||||
}
|
||||
|
||||
$("#vtx_frequency_channel").prop('checked', VTX_CONFIG.vtx_band === 0 && VTX_CONFIG.vtx_frequency > 0).change(frequencyOrBandChannel);
|
||||
$("#vtx_frequency_channel").prop('checked', FC.VTX_CONFIG.vtx_band === 0 && FC.VTX_CONFIG.vtx_frequency > 0).change(frequencyOrBandChannel);
|
||||
|
||||
if ($("#vtx_frequency_channel").prop('checked')) {
|
||||
$(".field.vtx_channel").hide();
|
||||
|
@ -440,8 +440,8 @@ TABS.vtx.initialize = function (callback) {
|
|||
const selectBand = $(".field #vtx_band");
|
||||
|
||||
selectBand.append(new Option(i18n.getMessage('vtxBand_0'), 0));
|
||||
if (VTX_CONFIG.vtx_table_available) {
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_bands; i++) {
|
||||
if (FC.VTX_CONFIG.vtx_table_available) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_bands; i++) {
|
||||
let bandName = TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_name;
|
||||
if (bandName.trim() === '') {
|
||||
bandName = i18n.getMessage('vtxBand_X', {bandName: i});
|
||||
|
@ -463,7 +463,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
selectChannel.empty();
|
||||
|
||||
selectChannel.append(new Option(i18n.getMessage('vtxChannel_0'), 0));
|
||||
if (VTX_CONFIG.vtx_table_available) {
|
||||
if (FC.VTX_CONFIG.vtx_table_available) {
|
||||
if (TABS.vtx.VTXTABLE_BAND_LIST[selectedBand - 1]) {
|
||||
for (let i = 1; i <= TABS.vtx.VTXTABLE_BAND_LIST[selectedBand - 1].vtxtable_band_frequencies.length; i++) {
|
||||
const channelName = TABS.vtx.VTXTABLE_BAND_LIST[selectedBand - 1].vtxtable_band_frequencies[i - 1];
|
||||
|
@ -482,9 +482,9 @@ TABS.vtx.initialize = function (callback) {
|
|||
function populatePowerSelect() {
|
||||
const selectPower = $(".field #vtx_power");
|
||||
|
||||
if (VTX_CONFIG.vtx_table_available) {
|
||||
if (FC.VTX_CONFIG.vtx_table_available) {
|
||||
selectPower.append(new Option(i18n.getMessage('vtxPower_0'), 0));
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
let powerLevel = TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_label;
|
||||
if (powerLevel.trim() === '') {
|
||||
powerLevel = i18n.getMessage('vtxPower_X', {powerLevel: i});
|
||||
|
@ -492,7 +492,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
selectPower.append(new Option(powerLevel, i));
|
||||
}
|
||||
} else {
|
||||
const powerMaxMinValues = getPowerValues(VTX_CONFIG.vtx_type);
|
||||
const powerMaxMinValues = getPowerValues(FC.VTX_CONFIG.vtx_type);
|
||||
for (let i = powerMaxMinValues.min; i <= powerMaxMinValues.max; i++) {
|
||||
if (i === 0) {
|
||||
selectPower.append(new Option(i18n.getMessage('vtxPower_0'), 0));
|
||||
|
@ -508,8 +508,8 @@ TABS.vtx.initialize = function (callback) {
|
|||
|
||||
let powerMinMax = {};
|
||||
|
||||
if (VTX_CONFIG.vtx_table_available) {
|
||||
powerMinMax = {min: 1, max: VTX_CONFIG.vtx_table_powerlevels};
|
||||
if (FC.VTX_CONFIG.vtx_table_available) {
|
||||
powerMinMax = {min: 1, max: FC.VTX_CONFIG.vtx_table_powerlevels};
|
||||
} else {
|
||||
|
||||
switch (vtxType) {
|
||||
|
@ -568,8 +568,8 @@ TABS.vtx.initialize = function (callback) {
|
|||
const suffix = 'lua';
|
||||
|
||||
let filename;
|
||||
if(CONFIG.name && CONFIG.name.trim() !== '') {
|
||||
filename = CONFIG.name.trim().replace(' ', '_');
|
||||
if(FC.CONFIG.name && FC.CONFIG.name.trim() !== '') {
|
||||
filename = FC.CONFIG.name.trim().replace(' ', '_');
|
||||
}else{
|
||||
filename = suggestedName;
|
||||
}
|
||||
|
@ -819,8 +819,8 @@ TABS.vtx.initialize = function (callback) {
|
|||
}
|
||||
|
||||
|
||||
if (save_vtx_powerlevels.counter < VTX_CONFIG.vtx_table_powerlevels) {
|
||||
VTXTABLE_POWERLEVEL = Object.assign({}, TABS.vtx.VTXTABLE_POWERLEVEL_LIST[save_vtx_powerlevels.counter]);
|
||||
if (save_vtx_powerlevels.counter < FC.VTX_CONFIG.vtx_table_powerlevels) {
|
||||
FC.VTXTABLE_POWERLEVEL = Object.assign({}, TABS.vtx.VTXTABLE_POWERLEVEL_LIST[save_vtx_powerlevels.counter]);
|
||||
MSP.send_message(MSPCodes.MSP_SET_VTXTABLE_POWERLEVEL, mspHelper.crunch(MSPCodes.MSP_SET_VTXTABLE_POWERLEVEL), false, save_vtx_powerlevels);
|
||||
} else {
|
||||
save_vtx_powerlevels.counter = undefined;
|
||||
|
@ -838,8 +838,8 @@ TABS.vtx.initialize = function (callback) {
|
|||
}
|
||||
|
||||
|
||||
if (save_vtx_bands.counter < VTX_CONFIG.vtx_table_bands) {
|
||||
VTXTABLE_BAND = Object.assign({}, TABS.vtx.VTXTABLE_BAND_LIST[save_vtx_bands.counter]);
|
||||
if (save_vtx_bands.counter < FC.VTX_CONFIG.vtx_table_bands) {
|
||||
FC.VTXTABLE_BAND = Object.assign({}, TABS.vtx.VTXTABLE_BAND_LIST[save_vtx_bands.counter]);
|
||||
MSP.send_message(MSPCodes.MSP_SET_VTXTABLE_BAND, mspHelper.crunch(MSPCodes.MSP_SET_VTXTABLE_BAND), false, save_vtx_bands);
|
||||
} else {
|
||||
save_vtx_bands.counter = undefined;
|
||||
|
@ -871,29 +871,29 @@ TABS.vtx.initialize = function (callback) {
|
|||
// General config
|
||||
const frequencyEnabled = $("#vtx_frequency_channel").prop('checked');
|
||||
if (frequencyEnabled) {
|
||||
VTX_CONFIG.vtx_frequency = parseInt($("#vtx_frequency").val());
|
||||
VTX_CONFIG.vtx_band = 0;
|
||||
VTX_CONFIG.vtx_channel = 0;
|
||||
FC.VTX_CONFIG.vtx_frequency = parseInt($("#vtx_frequency").val());
|
||||
FC.VTX_CONFIG.vtx_band = 0;
|
||||
FC.VTX_CONFIG.vtx_channel = 0;
|
||||
} else {
|
||||
VTX_CONFIG.vtx_band = parseInt($("#vtx_band").val());
|
||||
VTX_CONFIG.vtx_channel = parseInt($("#vtx_channel").val());
|
||||
VTX_CONFIG.vtx_frequency = 0;
|
||||
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
||||
if (VTX_CONFIG.vtx_band > 0 || VTX_CONFIG.vtx_channel > 0) {
|
||||
VTX_CONFIG.vtx_frequency = (band - 1) * 8 + (channel - 1);
|
||||
FC.VTX_CONFIG.vtx_band = parseInt($("#vtx_band").val());
|
||||
FC.VTX_CONFIG.vtx_channel = parseInt($("#vtx_channel").val());
|
||||
FC.VTX_CONFIG.vtx_frequency = 0;
|
||||
if (semver.lt(FC.CONFIG.apiVersion, "1.42.0")) {
|
||||
if (FC.VTX_CONFIG.vtx_band > 0 || FC.VTX_CONFIG.vtx_channel > 0) {
|
||||
FC.VTX_CONFIG.vtx_frequency = (band - 1) * 8 + (channel - 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
VTX_CONFIG.vtx_power = parseInt($("#vtx_power").val());
|
||||
VTX_CONFIG.vtx_pit_mode = $("#vtx_pit_mode").prop('checked');
|
||||
VTX_CONFIG.vtx_low_power_disarm = parseInt($("#vtx_low_power_disarm").val());
|
||||
VTX_CONFIG.vtx_table_clear = true;
|
||||
FC.VTX_CONFIG.vtx_power = parseInt($("#vtx_power").val());
|
||||
FC.VTX_CONFIG.vtx_pit_mode = $("#vtx_pit_mode").prop('checked');
|
||||
FC.VTX_CONFIG.vtx_low_power_disarm = parseInt($("#vtx_low_power_disarm").val());
|
||||
FC.VTX_CONFIG.vtx_table_clear = true;
|
||||
|
||||
// Power levels
|
||||
VTX_CONFIG.vtx_table_powerlevels = parseInt($("#vtx_table_powerlevels").val());
|
||||
FC.VTX_CONFIG.vtx_table_powerlevels = parseInt($("#vtx_table_powerlevels").val());
|
||||
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST = [];
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1] = {};
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_number = i;
|
||||
TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_value = parseInt($(`#vtx_table_powerlevels_${i}`).val());
|
||||
|
@ -901,10 +901,10 @@ TABS.vtx.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// Bands and channels
|
||||
VTX_CONFIG.vtx_table_bands = parseInt($("#vtx_table_bands").val());
|
||||
VTX_CONFIG.vtx_table_channels = parseInt($("#vtx_table_channels").val());
|
||||
FC.VTX_CONFIG.vtx_table_bands = parseInt($("#vtx_table_bands").val());
|
||||
FC.VTX_CONFIG.vtx_table_channels = parseInt($("#vtx_table_channels").val());
|
||||
TABS.vtx.VTXTABLE_BAND_LIST = [];
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_bands; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_bands; i++) {
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1] = {};
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_number = i;
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_name = $(`#vtx_table_band_name_${i}`).val();
|
||||
|
@ -912,7 +912,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_is_factory_band = TABS.vtx.vtxTableFactoryBandsSupported ? $(`#vtx_table_band_factory_${i}`).prop('checked') : false;
|
||||
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_frequencies = [];
|
||||
for (let j = 1; j <= VTX_CONFIG.vtx_table_channels; j++) {
|
||||
for (let j = 1; j <= FC.VTX_CONFIG.vtx_table_channels; j++) {
|
||||
TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_frequencies.push(parseInt($(`#vtx_table_band_channel_${i}_${j}`).val()));
|
||||
}
|
||||
}
|
||||
|
@ -930,7 +930,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
vtxConfig.vtx_table = {};
|
||||
|
||||
vtxConfig.vtx_table.bands_list = [];
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_bands; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_bands; i++) {
|
||||
vtxConfig.vtx_table.bands_list[i - 1] = {};
|
||||
vtxConfig.vtx_table.bands_list[i - 1].name = TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_name;
|
||||
vtxConfig.vtx_table.bands_list[i - 1].letter = TABS.vtx.VTXTABLE_BAND_LIST[i - 1].vtxtable_band_letter;
|
||||
|
@ -939,7 +939,7 @@ TABS.vtx.initialize = function (callback) {
|
|||
}
|
||||
|
||||
vtxConfig.vtx_table.powerlevels_list = [];
|
||||
for (let i = 1; i <= VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
for (let i = 1; i <= FC.VTX_CONFIG.vtx_table_powerlevels; i++) {
|
||||
vtxConfig.vtx_table.powerlevels_list[i - 1] = {};
|
||||
vtxConfig.vtx_table.powerlevels_list[i - 1].value = TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_value;
|
||||
vtxConfig.vtx_table.powerlevels_list[i - 1].label = TABS.vtx.VTXTABLE_POWERLEVEL_LIST[i - 1].vtxtable_powerlevel_label;
|
||||
|
|
Loading…
Reference in New Issue