mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-24 00:35:20 +03:00
references to pre 1.15 api version removed
This commit is contained in:
parent
8fdfbca840
commit
7c7b366ca7
5 changed files with 22 additions and 74 deletions
|
@ -577,14 +577,12 @@ var mspHelper = (function (gui) {
|
|||
offset++;
|
||||
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, true);
|
||||
offset += 2;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset);
|
||||
offset++;
|
||||
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, true);
|
||||
offset += 2;
|
||||
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset);
|
||||
offset++;
|
||||
}
|
||||
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset);
|
||||
offset++;
|
||||
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, true);
|
||||
offset += 2;
|
||||
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset);
|
||||
offset++;
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_RXFAIL_CONFIG:
|
||||
|
@ -1003,10 +1001,7 @@ var mspHelper = (function (gui) {
|
|||
case MSPCodes.MSP_SET_RC_TUNING:
|
||||
buffer.push(Math.round(RC_tuning.RC_RATE * 100));
|
||||
buffer.push(Math.round(RC_tuning.RC_EXPO * 100));
|
||||
if (semver.lt(CONFIG.apiVersion, "1.7.0")) {
|
||||
buffer.push(Math.round(RC_tuning.roll_pitch_rate * 100));
|
||||
buffer.push(Math.round(RC_tuning.yaw_rate * 100));
|
||||
} else if (FC.isRatesInDps()) {
|
||||
if (FC.isRatesInDps()) {
|
||||
buffer.push(Math.round(RC_tuning.roll_rate / 10));
|
||||
buffer.push(Math.round(RC_tuning.pitch_rate / 10));
|
||||
buffer.push(Math.round(RC_tuning.yaw_rate / 10));
|
||||
|
@ -1019,13 +1014,9 @@ var mspHelper = (function (gui) {
|
|||
buffer.push(RC_tuning.dynamic_THR_PID);
|
||||
buffer.push(Math.round(RC_tuning.throttle_MID * 100));
|
||||
buffer.push(Math.round(RC_tuning.throttle_EXPO * 100));
|
||||
if (semver.gte(CONFIG.apiVersion, "1.7.0")) {
|
||||
buffer.push(lowByte(RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(highByte(RC_tuning.dynamic_THR_breakpoint));
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
|
||||
buffer.push(Math.round(RC_tuning.RC_YAW_EXPO * 100));
|
||||
}
|
||||
buffer.push(lowByte(RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(highByte(RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(Math.round(RC_tuning.RC_YAW_EXPO * 100));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_RX_MAP:
|
||||
|
@ -1103,12 +1094,10 @@ var mspHelper = (function (gui) {
|
|||
buffer.push(FAILSAFE_CONFIG.failsafe_off_delay);
|
||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle));
|
||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle));
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
|
||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
|
||||
}
|
||||
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
|
||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
|
||||
|
@ -1838,11 +1827,7 @@ var mspHelper = (function (gui) {
|
|||
};
|
||||
|
||||
self.loadRcDeadband = function (callback) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_RC_DEADBAND, false, false, callback);
|
||||
} else {
|
||||
callback();
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_RC_DEADBAND, false, false, callback);
|
||||
};
|
||||
|
||||
self.loadRcMap = function (callback) {
|
||||
|
|
|
@ -96,12 +96,6 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function update_ui() {
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
|
||||
$(".tab-ports").removeClass("supported");
|
||||
return;
|
||||
}
|
||||
|
||||
$(".tab-ports").addClass("supported");
|
||||
|
||||
var portIdentifierToNameMapping = {
|
||||
|
|
|
@ -41,11 +41,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
$('.tunings .rate input[name="rate"]').val(RC_tuning.RC_RATE.toFixed(2));
|
||||
$('.tunings .rate input[name="expo"]').val(RC_tuning.RC_EXPO.toFixed(2));
|
||||
$('.tunings .yaw_rate input[name="yaw_expo"]').val(RC_tuning.RC_YAW_EXPO.toFixed(2));
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.10.0")) {
|
||||
$('.tunings .yaw_rate input[name="yaw_expo"]').hide();
|
||||
}
|
||||
$('.tunings .yaw_rate input[name="yaw_expo"]').val(RC_tuning.RC_YAW_EXPO.toFixed(2));
|
||||
|
||||
chrome.storage.local.get('rx_refresh_rate', function (result) {
|
||||
if (result.rx_refresh_rate) {
|
||||
|
@ -55,12 +51,8 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||
$('.deadband').hide();
|
||||
} else {
|
||||
$('.deadband input[name="yaw_deadband"]').val(RC_deadband.yaw_deadband);
|
||||
$('.deadband input[name="deadband"]').val(RC_deadband.deadband);
|
||||
}
|
||||
$('.deadband input[name="yaw_deadband"]').val(RC_deadband.yaw_deadband);
|
||||
$('.deadband input[name="deadband"]').val(RC_deadband.deadband);
|
||||
|
||||
// generate bars
|
||||
var bar_names = [
|
||||
|
@ -295,10 +287,8 @@ TABS.receiver.initialize = function (callback) {
|
|||
RC_tuning.RC_EXPO = parseFloat($('.tunings .rate input[name="expo"]').val());
|
||||
RC_tuning.RC_YAW_EXPO = parseFloat($('.tunings .yaw_rate input[name="yaw_expo"]').val());
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
RC_deadband.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
|
||||
RC_deadband.deadband = parseInt($('.deadband input[name="deadband"]').val());
|
||||
}
|
||||
RC_deadband.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
|
||||
RC_deadband.deadband = parseInt($('.deadband input[name="deadband"]').val());
|
||||
|
||||
// catch rc map
|
||||
var RC_MAP_Letters = ['A', 'E', 'R', 'T', '1', '2', '3', '4'];
|
||||
|
@ -320,12 +310,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function save_rc_configs() {
|
||||
var next_callback = save_to_eeprom;
|
||||
if (semver.gte(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();
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_SET_RC_DEADBAND, mspHelper.crunch(MSPCodes.MSP_SET_RC_DEADBAND), false, save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
|
|
|
@ -14,17 +14,7 @@ TABS.servos.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function get_servo_mix_rules() {
|
||||
MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding);
|
||||
}
|
||||
|
||||
function get_channel_forwarding() {
|
||||
var nextFunction = get_rc_data;
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_CHANNEL_FORWARDING, false, false, nextFunction);
|
||||
} else {
|
||||
nextFunction();
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, get_rc_data);
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
|
|
|
@ -34,12 +34,6 @@ TABS.setup.initialize = function (callback) {
|
|||
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("logPwmOutputDisabled") + "</strong></span>");
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, CONFIGURATOR.backupRestoreMinApiVersionAccepted)) {
|
||||
$('#content .backup').addClass('disabled');
|
||||
$('#content .restore').addClass('disabled');
|
||||
|
||||
GUI.log(chrome.i18n.getMessage('initialSetupBackupAndRestoreApiVersion', [CONFIG.apiVersion, CONFIGURATOR.backupRestoreMinApiVersionAccepted]));
|
||||
}
|
||||
// initialize 3D
|
||||
self.initialize3D();
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue