CF/BF - fix some usages of flightControllerVersion which should have
used MSP API version. FYI: 3.1.0 = api 1.31 - https://github.com/betaflight/betaflight/blob/v3.1.6/src/main/msp/msp_protocol.h 3.0.1 = api 1.21 - https://github.com/betaflight/betaflight/blob/v3.0.1/src/main/io/msp_protocol.h 3.0.0 = api 1.20 - https://github.com/betaflight/betaflight/blob/v3.0.0/src/main/io/msp_protocol.h 2.9.1 = api 1.16 - https://github.com/betaflight/betaflight/blob/v2.9.1/src/main/io/serial_msp.h 2.8.0 = api 1.16 - https://github.com/betaflight/betaflight/blob/v.2.8.0/src/main/io/serial_msp.h 2.4.0 = api 1.16 - https://github.com/betaflight/betaflight/blob/v2.4.0/src/main/io/serial_msp.h10.3.x-maintenance
parent
6fb4a089e5
commit
b4936958f8
|
@ -35,7 +35,7 @@ var Features = function (config) {
|
|||
);
|
||||
}
|
||||
|
||||
if (semver.gte(config.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
features.push(
|
||||
{bit: 8, group: 'rxFailsafe', name: 'FAILSAFE', haveTip: true}
|
||||
);
|
||||
|
@ -45,21 +45,21 @@ var Features = function (config) {
|
|||
);
|
||||
}
|
||||
|
||||
if (semver.gte(config.apiVersion, "1.16.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
features.push(
|
||||
{bit: 21, group: 'other', name: 'TRANSPONDER', haveTip: true}
|
||||
);
|
||||
}
|
||||
|
||||
if (config.flightControllerVersion !== '') {
|
||||
if (semver.gte(config.flightControllerVersion, "2.8.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
features.push(
|
||||
{bit: 22, group: 'other', name: 'AIRMODE'}
|
||||
);
|
||||
}
|
||||
|
||||
if (semver.gte(config.flightControllerVersion, "2.8.0")) {
|
||||
if (!semver.gte(config.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
features.push(
|
||||
{bit: 23, group: 'pidTuning', name: 'SUPEREXPO_RATES'}
|
||||
);
|
||||
|
@ -70,13 +70,13 @@ var Features = function (config) {
|
|||
}
|
||||
}
|
||||
|
||||
if (semver.gte(config.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
features.push(
|
||||
{bit: 18, group: 'other', name: 'OSD'}
|
||||
);
|
||||
}
|
||||
|
||||
if (semver.gte(config.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
features.push(
|
||||
{bit: 27, group: 'other', name: 'ESC_SENSOR'}
|
||||
)
|
||||
|
|
|
@ -92,7 +92,7 @@ RateCurve.prototype.rcCommandRawToDegreesPerSecond = function (rcData, rate, rcR
|
|||
|
||||
var expoPower;
|
||||
var rcRateConstant;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
expoPower = 3;
|
||||
rcRateConstant = 200;
|
||||
} else {
|
||||
|
|
|
@ -75,7 +75,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
CONFIG.mode = data.readU32();
|
||||
CONFIG.profile = data.readU8();
|
||||
CONFIG.cpuload = data.readU16();
|
||||
if (semver.gt(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
CONFIG.numProfiles = data.readU8();
|
||||
CONFIG.rateProfile = data.readU8();
|
||||
|
||||
|
@ -178,7 +178,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
|
||||
RC_tuning.RC_YAW_EXPO = parseFloat((data.readU8() / 100).toFixed(2));
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
RC_tuning.rcYawRate = parseFloat((data.readU8() / 100).toFixed(2));
|
||||
} else {
|
||||
RC_tuning.rcYawRate = 0;
|
||||
|
@ -685,7 +685,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
ADVANCED_TUNING.yaw_p_limit = data.readU16();
|
||||
ADVANCED_TUNING.deltaMethod = data.readU8();
|
||||
ADVANCED_TUNING.vbatPidCompensation = data.readU8();
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
ADVANCED_TUNING.ptermSetpointWeight = data.readU8();
|
||||
ADVANCED_TUNING.dtermSetpointWeight = data.readU8();
|
||||
ADVANCED_TUNING.toleranceBand = data.readU8();
|
||||
|
@ -1024,7 +1024,7 @@ MspHelper.prototype.crunch = function(code) {
|
|||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
|
||||
buffer.push8(Math.round(RC_tuning.RC_YAW_EXPO * 100));
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
buffer.push8(Math.round(RC_tuning.rcYawRate * 100));
|
||||
}
|
||||
}
|
||||
|
@ -1209,7 +1209,7 @@ MspHelper.prototype.crunch = function(code) {
|
|||
}
|
||||
break;
|
||||
case MSPCodes.MSP_SET_PID_ADVANCED:
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
buffer.push16(ADVANCED_TUNING.rollPitchItermIgnoreRate)
|
||||
.push16(ADVANCED_TUNING.yawItermIgnoreRate)
|
||||
.push16(ADVANCED_TUNING.yaw_p_limit)
|
||||
|
@ -1284,7 +1284,7 @@ MspHelper.prototype.setRawRx = function(channels) {
|
|||
MspHelper.prototype.dataflashRead = function(address, blockSize, onDataCallback) {
|
||||
var outData = [address & 0xFF, (address >> 8) & 0xFF, (address >> 16) & 0xFF, (address >> 24) & 0xFF];
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
outData = outData.concat([blockSize & 0xFF, (blockSize >> 8) & 0xFF]);
|
||||
}
|
||||
|
||||
|
@ -1295,7 +1295,7 @@ MspHelper.prototype.dataflashRead = function(address, blockSize, onDataCallback)
|
|||
var headerSize = 4;
|
||||
var dataSize = response.data.buffer.byteLength - headerSize;
|
||||
var dataCompressionType = 0;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
headerSize = headerSize + 3;
|
||||
dataSize = response.data.readU16();
|
||||
dataCompressionType = response.data.readU8();
|
||||
|
|
|
@ -74,7 +74,7 @@ $(document).ready(function () {
|
|||
// Reset various UI elements
|
||||
$('span.i2c-error').text(0);
|
||||
$('span.cycle-time').text(0);
|
||||
if (CONFIG.flightControllerVersion !== '' && semver.gte(CONFIG.flightControllerVersion, "3.0.0"))
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0"))
|
||||
$('span.cpu-load').text('');
|
||||
|
||||
// unlock port select & baud
|
||||
|
@ -271,12 +271,12 @@ function onConnect() {
|
|||
|
||||
$('#tabs ul.mode-connected').show();
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
} else {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
|
||||
if (CONFIG.flightControllerIdentifier === 'BTFL' && semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
|
||||
CONFIG.numProfiles = 2;
|
||||
$('.tab-pid_tuning select[name="profile"] .profile3').hide();
|
||||
} else {
|
||||
|
@ -460,10 +460,10 @@ function update_live_status() {
|
|||
|
||||
if (GUI.active_tab != 'cli') {
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false);
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1"))
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.32.0"))
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
else
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false);
|
||||
}
|
||||
|
||||
|
|
|
@ -273,7 +273,7 @@ TABS.adjustments.cleanup = function (callback) {
|
|||
|
||||
TABS.adjustments.adjust_template = function () {
|
||||
var availableFunctionCount;
|
||||
if (semver.lt(CONFIG.flightControllerVersion, '3.1.0')) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.31.0")) {
|
||||
availableFunctionCount = 21; // Available in betaflight 2.9
|
||||
} else {
|
||||
availableFunctionCount = 24; // RC rate Yaw / D setpoint / D setpoint transition added to 3.1.0
|
||||
|
|
|
@ -74,7 +74,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function esc_protocol() {
|
||||
var next_callback = sensor_config;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -83,7 +83,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function sensor_config() {
|
||||
var next_callback = load_sensor_alignment;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SENSOR_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -101,7 +101,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function load_name() {
|
||||
var next_callback = load_battery;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_NAME, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -110,7 +110,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function load_battery() {
|
||||
var next_callback = load_current;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_VOLTAGE_METER_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -119,7 +119,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function load_current() {
|
||||
var next_callback = load_rx_config;
|
||||
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, next_callback);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function load_rx_config() {
|
||||
|
@ -209,11 +213,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
'MULTISHOT'
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
escprotocols.push('BRUSHED');
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
escprotocols.push('DSHOT150');
|
||||
escprotocols.push('DSHOT300');
|
||||
escprotocols.push('DSHOT600');
|
||||
|
@ -343,13 +347,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$('input[id="magHardwareSwitch"]').prop('checked', SENSOR_CONFIG.mag_hardware !== 1);
|
||||
|
||||
// Only show these sections for supported FW
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('.selectProtocol').hide();
|
||||
$('.checkboxPwm').hide();
|
||||
$('.selectPidProcessDenom').hide();
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('.hardwareSelection').hide();
|
||||
}
|
||||
|
||||
|
@ -362,7 +366,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$('div.fpvCamAngleDegrees').hide();
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
$('.miscSettings').hide();
|
||||
}
|
||||
|
||||
|
@ -444,11 +448,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
serialRXtypes.push('IBUS');
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
|
||||
if ((CONFIG.flightControllerIdentifier === 'BTFL' && semver.gte(CONFIG.flightControllerVersion, "2.6.0")) ||
|
||||
(CONFIG.flightControllerIdentifier === 'CLFL' && semver.gte(CONFIG.apiVersion, "1.31.0"))) {
|
||||
serialRXtypes.push('JETIEXBUS');
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
serialRXtypes.push('CRSF');
|
||||
}
|
||||
|
||||
|
@ -504,7 +509,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$('input[name="mincommand"]').val(MISC.mincommand);
|
||||
|
||||
// fill battery
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
var batteryMeterTypes = [
|
||||
'Onboard ADC',
|
||||
'ESC Sensor'
|
||||
|
@ -536,7 +541,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
'Virtual'
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
currentMeterTypes.push('ESC Sensor');
|
||||
}
|
||||
|
||||
|
@ -586,7 +591,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
if (BF_CONFIG.features.isEnabled('VBAT')) {
|
||||
$('.vbatmonitoring').show();
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
$('select.batterymetertype').show();
|
||||
|
||||
if (MISC.batterymetertype !== 0) {
|
||||
|
@ -795,7 +800,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
function save_esc_protocol() {
|
||||
var next_callback = save_acc_trim;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -813,7 +818,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function save_looptime_config() {
|
||||
var next_callback = save_sensor_config;
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.16.0")) {
|
||||
FC_CONFIG.loopTime = PID_ADVANCED_CONFIG.gyro_sync_denom * 125;
|
||||
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, next_callback);
|
||||
} else {
|
||||
|
@ -823,7 +828,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function save_sensor_config() {
|
||||
var next_callback = save_name;
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
SENSOR_CONFIG.acc_hardware = $('input[id="accHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||
SENSOR_CONFIG.baro_hardware = $('input[id="baroHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||
SENSOR_CONFIG.mag_hardware = $('input[id="magHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||
|
@ -836,7 +841,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function save_name() {
|
||||
var next_callback = save_battery;
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
CONFIG.name = $.trim($('input[name="vesselName"]').val());
|
||||
MSP.send_message(MSPCodes.MSP_SET_NAME, mspHelper.crunch(MSPCodes.MSP_SET_NAME), false, next_callback);
|
||||
} else {
|
||||
|
@ -846,7 +851,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function save_battery() {
|
||||
var next_callback = save_current;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -855,7 +860,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function save_current() {
|
||||
var next_callback = save_rx_config;
|
||||
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, next_callback);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function save_rx_config() {
|
||||
|
|
|
@ -37,7 +37,7 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
function esc_protocol() {
|
||||
var next_callback = get_motor_data;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
|
|
@ -31,7 +31,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
|
||||
var load_name = function () {
|
||||
var next_callback = load_html;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_NAME, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -348,7 +348,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
function flash_save_begin() {
|
||||
if (GUI.connected_to) {
|
||||
if (BOARD.find_board_definition(CONFIG.boardIdentifier).vcp) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
self.blockSize = self.VCP_BLOCK_SIZE;
|
||||
} else {
|
||||
self.blockSize = self.VCP_BLOCK_SIZE_3_0;
|
||||
|
|
18
tabs/osd.js
18
tabs/osd.js
|
@ -434,7 +434,7 @@ OSD.constants = {
|
|||
OSD.chooseFields = function () {
|
||||
var F = OSD.constants.ALL_DISPLAY_FIELDS;
|
||||
// version 3.0.1
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = [
|
||||
F.RSSI_VALUE,
|
||||
F.MAIN_BATT_VOLTAGE,
|
||||
|
@ -453,7 +453,7 @@ OSD.chooseFields = function () {
|
|||
F.GPS_SATS,
|
||||
F.ALTITUDE
|
||||
];
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
OSD.constants.DISPLAY_FIELDS = OSD.constants.DISPLAY_FIELDS.concat([
|
||||
F.PID_ROLL,
|
||||
F.PID_PITCH,
|
||||
|
@ -530,7 +530,7 @@ OSD.msp = {
|
|||
unpack: {
|
||||
position: function(bits, c) {
|
||||
var display_item = {};
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
// size * y + x
|
||||
display_item.position = FONT.constants.SIZES.LINE * ((bits >> 5) & 0x001F) + (bits & 0x001F);
|
||||
display_item.isVisible = (bits & OSD.constants.VISIBLE) != 0;
|
||||
|
@ -545,7 +545,7 @@ OSD.msp = {
|
|||
position: function(display_item) {
|
||||
var isVisible = display_item.isVisible;
|
||||
var position = display_item.position;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
return (isVisible ? 0x0800 : 0) | (((position / FONT.constants.SIZES.LINE) & 0x001F) << 5) | (position % FONT.constants.SIZES.LINE);
|
||||
} else {
|
||||
return isVisible ? (position == -1 ? 0 : position): -1;
|
||||
|
@ -555,7 +555,7 @@ OSD.msp = {
|
|||
},
|
||||
encodeOther: function() {
|
||||
var result = [-1, OSD.data.video_system];
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(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);
|
||||
|
@ -578,7 +578,7 @@ OSD.msp = {
|
|||
d.compiled_in = view.readU8();
|
||||
d.video_system = view.readU8();
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
d.unit_mode = view.readU8();
|
||||
d.alarms = {};
|
||||
d.alarms['rssi'] = { display_name: 'Rssi', value: view.readU8() };
|
||||
|
@ -590,7 +590,7 @@ OSD.msp = {
|
|||
// start at the offset from the other fields
|
||||
while (view.offset < view.byteLength && d.display_items.length < OSD.constants.DISPLAY_FIELDS.length) {
|
||||
var v = null;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
v = view.readU16();
|
||||
} else {
|
||||
v = view.read16();
|
||||
|
@ -644,7 +644,7 @@ OSD.GUI.preview = {
|
|||
if (overflows_line < 0) {
|
||||
position += overflows_line;
|
||||
}
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
// unsigned now
|
||||
} else {
|
||||
if (position > OSD.data.display_size.total/2) {
|
||||
|
@ -723,7 +723,7 @@ TABS.osd.initialize = function (callback) {
|
|||
});
|
||||
});
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
// units
|
||||
$('.units-container').show();
|
||||
var $unitMode = $('.units').empty();
|
||||
|
|
|
@ -26,7 +26,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}).then(function() {
|
||||
return MSP.promise(MSPCodes.MSP_PID);
|
||||
}).then(function() {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
return MSP.promise(MSPCodes.MSP_PID_ADVANCED);
|
||||
}
|
||||
}).then(function() {
|
||||
|
@ -35,7 +35,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
return MSP.promise(MSPCodes.MSP_FILTER_CONFIG);
|
||||
}).then(function() {
|
||||
var promise = true;
|
||||
if (CONFIG.flightControllerIdentifier === "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||
if (CONFIG.flightControllerIdentifier === "BTFL" && semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
promise = MSP.promise(MSPCodes.MSP_BF_CONFIG);
|
||||
}
|
||||
|
||||
|
@ -53,7 +53,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
|
||||
function pid_and_rc_to_form() {
|
||||
self.setProfile();
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
self.setRateProfile();
|
||||
}
|
||||
|
||||
|
@ -216,15 +216,15 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('.pid_tuning input[name="rc_expo"]').attr("rowspan", "3");
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('input[id="vbatpidcompensation"]').prop('checked', ADVANCED_TUNING.vbatPidCompensation !== 0);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('#pid-tuning .delta select').val(ADVANCED_TUNING.deltaMethod);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, '2.9.0')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('.pid_tuning input[name="rc_rate_yaw"]').val(RC_tuning.rcYawRate.toFixed(2));
|
||||
$('.pid_filter input[name="gyroLowpassFrequency"]').val(FILTER_CONFIG.gyro_soft_lpf_hz);
|
||||
$('.pid_filter input[name="dtermLowpassFrequency"]').val(FILTER_CONFIG.dterm_lpf_hz);
|
||||
|
@ -235,14 +235,14 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('.pid_tuning input[name="rc_rate_yaw"]').hide();
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")
|
||||
|| semver.gte(CONFIG.flightControllerVersion, "2.8.0") && BF_CONFIG.features.isEnabled('SUPEREXPO_RATES')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")
|
||||
|| semver.gte(CONFIG.apiVersion, "1.16.0") && BF_CONFIG.features.isEnabled('SUPEREXPO_RATES')) {
|
||||
$('#pid-tuning .rate').text(chrome.i18n.getMessage("pidTuningSuperRate"));
|
||||
} else {
|
||||
$('#pid-tuning .rate').text(chrome.i18n.getMessage("pidTuningRate"));
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, '3.0.0')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
$('.pid_filter input[name="gyroNotch1Frequency"]').val(FILTER_CONFIG.gyro_soft_notch_hz_1);
|
||||
$('.pid_filter input[name="gyroNotch1Cutoff"]').val(FILTER_CONFIG.gyro_soft_notch_cutoff_1);
|
||||
$('.pid_filter input[name="dTermNotchFrequency"]').val(FILTER_CONFIG.dterm_notch_hz);
|
||||
|
@ -257,7 +257,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('.pid_filter .newFilter').hide();
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, '3.0.1')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
$('.pid_filter input[name="gyroNotch2Frequency"]').val(FILTER_CONFIG.gyro_soft_notch_hz_2);
|
||||
$('.pid_filter input[name="gyroNotch2Cutoff"]').val(FILTER_CONFIG.gyro_soft_notch_cutoff_2);
|
||||
} else {
|
||||
|
@ -350,19 +350,19 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
FILTER_CONFIG.dterm_lpf_hz = parseInt($('.pid_filter input[name="dtermLowpassFrequency"]').val());
|
||||
FILTER_CONFIG.yaw_lpf_hz = parseInt($('.pid_filter input[name="yawLowpassFrequency"]').val());
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.0") && !semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0") && !semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
BF_CONFIG.features.updateData($('input[name="SUPEREXPO_RATES"]'));
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
ADVANCED_TUNING.vbatPidCompensation = $('input[id="vbatpidcompensation"]').is(':checked') ? 1 : 0;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
ADVANCED_TUNING.deltaMethod = $('#pid-tuning .delta select').val();
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, '3.0.0')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
ADVANCED_TUNING.ptermSetpointWeight = parseInt($('input[name="ptermSetpoint-number"]').val() * 100);
|
||||
ADVANCED_TUNING.dtermSetpointWeight = parseInt($('input[name="dtermSetpoint-number"]').val() * 100);
|
||||
|
||||
|
@ -370,7 +370,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
FILTER_CONFIG.gyro_soft_notch_cutoff_1 = parseInt($('.pid_filter input[name="gyroNotch1Cutoff"]').val());
|
||||
FILTER_CONFIG.dterm_notch_hz = parseInt($('.pid_filter input[name="dTermNotchFrequency"]').val());
|
||||
FILTER_CONFIG.dterm_notch_cutoff = parseInt($('.pid_filter input[name="dTermNotchCutoff"]').val());
|
||||
if (semver.gte(CONFIG.flightControllerVersion, '3.0.1')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||
FILTER_CONFIG.gyro_soft_notch_hz_2 = parseInt($('.pid_filter input[name="gyroNotch2Frequency"]').val());
|
||||
FILTER_CONFIG.gyro_soft_notch_cutoff_2 = parseInt($('.pid_filter input[name="gyroNotch2Cutoff"]').val());
|
||||
}
|
||||
|
@ -447,7 +447,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}
|
||||
|
||||
var useLegacyCurve = false;
|
||||
if (!semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||
if (!semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
useLegacyCurve = true;
|
||||
}
|
||||
|
||||
|
@ -469,7 +469,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function process_html() {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.0") && !semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0") && !semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
BF_CONFIG.features.generateElements($('.tab-pid_tuning .features'));
|
||||
} else {
|
||||
$('.tab-pid_tuning .pidTuningFeatures').hide();
|
||||
|
@ -497,11 +497,11 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
self.currentRates.pitch_rate = RC_tuning.roll_pitch_rate;
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.16.0")) {
|
||||
self.currentRates.rc_rate_yaw = self.currentRates.rc_rate;
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
self.currentRates.superexpo = true;
|
||||
}
|
||||
|
||||
|
@ -566,7 +566,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
});
|
||||
});
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
$('.tab-pid_tuning select[name="rate_profile"]').change(function () {
|
||||
self.currentRateProfile = parseInt($(this).val());
|
||||
self.updating = true;
|
||||
|
@ -603,7 +603,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('#pid-tuning .dtermSetpoint').hide();
|
||||
}
|
||||
|
||||
if (!semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (!semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('#pid-tuning .delta').hide();
|
||||
$('.tab-pid_tuning .note').hide();
|
||||
}
|
||||
|
@ -620,7 +620,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
|
||||
var pidController_e = $('select[name="controller"]');
|
||||
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.31.0")) {
|
||||
var pidControllerList;
|
||||
|
||||
|
||||
|
@ -633,7 +633,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
{name: "MultiWii (2.3 - hybrid)"},
|
||||
{name: "Harakiri"}
|
||||
]
|
||||
} else if (semver.lt(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
} else if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||
pidControllerList = [
|
||||
{name: ""},
|
||||
{name: "Integer"},
|
||||
|
@ -707,7 +707,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
updateNeeded = true;
|
||||
}
|
||||
|
||||
if (targetElement.attr('name') === 'rc_rate' && semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (targetElement.attr('name') === 'rc_rate' && semver.lt(CONFIG.apiVersion, "1.16.0")) {
|
||||
self.currentRates.rc_rate_yaw = targetValue;
|
||||
}
|
||||
|
||||
|
@ -823,13 +823,13 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
$('#pid-tuning .delta select').change(function() {
|
||||
self.setDirty(true);
|
||||
});
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.31.0")) {
|
||||
pidController_e.change(function () {
|
||||
self.setDirty(true);
|
||||
|
||||
|
@ -845,7 +845,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
Promise.resolve(true)
|
||||
.then(function () {
|
||||
var promise;
|
||||
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion) && semver.lt(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion) && semver.lt(CONFIG.apiVersion, "1.31.0")) {
|
||||
PID.controller = pidController_e.val();
|
||||
promise = MSP.promise(MSPCodes.MSP_SET_PID_CONTROLLER, mspHelper.crunch(MSPCodes.MSP_SET_PID_CONTROLLER));
|
||||
}
|
||||
|
@ -853,17 +853,17 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}).then(function () {
|
||||
return MSP.promise(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID));
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
return MSP.promise(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED));
|
||||
}
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
return MSP.promise(MSPCodes.MSP_SET_FILTER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FILTER_CONFIG));
|
||||
}
|
||||
}).then(function () {
|
||||
return MSP.promise(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING));
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
return MSP.promise(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG));
|
||||
}
|
||||
}).then(function () {
|
||||
|
@ -973,7 +973,7 @@ TABS.pid_tuning.setDirty = function (isDirty) {
|
|||
|
||||
self.dirty = isDirty;
|
||||
$('.tab-pid_tuning select[name="profile"]').prop('disabled', isDirty);
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
$('.tab-pid_tuning select[name="rate_profile"]').prop('disabled', isDirty);
|
||||
}
|
||||
};
|
||||
|
@ -982,7 +982,7 @@ TABS.pid_tuning.checkUpdateProfile = function (updateRateProfile) {
|
|||
var self = this;
|
||||
|
||||
if (GUI.active_tab === 'pid_tuning') {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")
|
||||
&& CONFIG.numProfiles === 2) {
|
||||
$('.tab-pid_tuning select[name="profile"] .profile3').hide();
|
||||
}
|
||||
|
@ -996,7 +996,7 @@ TABS.pid_tuning.checkUpdateProfile = function (updateRateProfile) {
|
|||
}
|
||||
|
||||
var changedRateProfile = false;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")
|
||||
&& updateRateProfile
|
||||
&& self.currentRateProfile !== CONFIG.rateProfile) {
|
||||
self.setRateProfile();
|
||||
|
@ -1036,7 +1036,7 @@ TABS.pid_tuning.checkRC = function() {
|
|||
};
|
||||
|
||||
TABS.pid_tuning.updatePidControllerParameters = function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0") && semver.lt(CONFIG.flightControllerVersion, "3.1.0") && $('.tab-pid_tuning select[name="controller"]').val() === '0') {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0") && semver.lt(CONFIG.apiVersion, "1.31.0") && $('.tab-pid_tuning select[name="controller"]').val() === '0') {
|
||||
$('.pid_tuning .YAW_JUMP_PREVENTION').show();
|
||||
|
||||
$('#pid-tuning .delta').show();
|
||||
|
|
|
@ -30,7 +30,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
functionRules.push(mavlinkFunctionRule);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
functionRules.push({ name: 'ESC_SENSOR', groups: ['sensors'], maxPorts: 1 });
|
||||
functionRules.push({ name: 'TBS_SMARTAUDIO', groups: ['peripherals'], maxPorts: 1 });
|
||||
}
|
||||
|
@ -57,7 +57,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
'250000'
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||
mspBaudRates = mspBaudRates.concat(['500000', '1000000']);
|
||||
}
|
||||
|
||||
|
|
|
@ -46,7 +46,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function load_rx_config() {
|
||||
var next_callback = load_html;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
|
@ -87,7 +87,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
$('select[name="rcInterpolation-select"]').val(RX_CONFIG.rcInterpolation);
|
||||
$('input[name="rcInterpolationInterval-number"]').val(RX_CONFIG.rcInterpolationInterval);
|
||||
|
||||
|
@ -253,7 +253,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
// catch rssi aux
|
||||
MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val());
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
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());
|
||||
}
|
||||
|
@ -273,7 +273,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
function save_rx_config() {
|
||||
var next_callback = save_to_eeprom;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(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();
|
||||
|
@ -447,11 +447,19 @@ TABS.receiver.initModelPreview = function () {
|
|||
this.model = new Model($('.model_preview'), $('.model_preview canvas'));
|
||||
|
||||
this.useSuperExpo = false;
|
||||
if (semver.gte(CONFIG.flightControllerVersion, '2.8.0')) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||
this.useSuperExpo = BF_CONFIG.features.isEnabled('SUPEREXPO_RATES');
|
||||
}
|
||||
|
||||
this.rateCurve = new RateCurve(CONFIG.flightControllerIdentifier !== 'BTFL' || semver.lt(CONFIG.flightControllerVersion, '2.8.0'));
|
||||
var useOldRateCurve = false;
|
||||
if (CONFIG.flightControllerIdentifier == 'CLFL' && semver.lt(CONFIG.apiVersion, '2.0.0') {
|
||||
useOldRateCurve = true;
|
||||
}
|
||||
if (CONFIG.flightControllerIdentifier == 'BTFL' && semver.lt(CONFIG.flightControllerVersionn, '2.8.0') {
|
||||
useOldRateCurve = true;
|
||||
}
|
||||
|
||||
this.rateCurve = new RateCurve(useOldRateCurve);
|
||||
|
||||
$(window).on('resize', $.proxy(this.model.resize, this.model));
|
||||
};
|
||||
|
@ -485,7 +493,7 @@ TABS.receiver.cleanup = function (callback) {
|
|||
};
|
||||
|
||||
TABS.receiver.updateRcInterpolationParameters = function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||
if ($('select[name="rcInterpolation-select"]').val() === '3') {
|
||||
$('.tab-receiver .rcInterpolationInterval').show();
|
||||
} else {
|
||||
|
|
Loading…
Reference in New Issue