1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-23 16:25:19 +03:00

Merge remote-tracking branch 'origin/master' into release-2-3-0

This commit is contained in:
Pawel Spychalski (DzikuVx) 2019-11-20 23:56:16 +01:00
commit 22335fa99e
25 changed files with 1532 additions and 3610 deletions

View file

@ -3222,6 +3222,9 @@
"antigravityCutoff": { "antigravityCutoff": {
"message": "Antigravity Cutoff Frequency" "message": "Antigravity Cutoff Frequency"
}, },
"ouptputsConfiguration": {
"message": "Configuration"
},
"vtxDisclaimer": { "vtxDisclaimer": {
"message": "Use only bands, channels and power levels that are legal in a place you fly! Always refer to VTX user manual and local regulations!" "message": "Use only bands, channels and power levels that are legal in a place you fly! Always refer to VTX user manual and local regulations!"
}, },

100
js/fc.js
View file

@ -62,9 +62,6 @@ var CONFIG,
var FC = { var FC = {
MAX_SERVO_RATE: 125, MAX_SERVO_RATE: 125,
MIN_SERVO_RATE: 0, MIN_SERVO_RATE: 0,
isNewMixer: function () {
return !!(typeof CONFIG != "undefined" && semver.gte(CONFIG.flightControllerVersion, "2.0.0"));
},
isRpyFfComponentUsed: function () { isRpyFfComponentUsed: function () {
return MIXER_CONFIG.platformType == PLATFORM_AIRPLANE; return MIXER_CONFIG.platformType == PLATFORM_AIRPLANE;
}, },
@ -560,49 +557,17 @@ var FC = {
{bit: 15, group: 'other', name: 'RSSI_ADC', haveTip: true, showNameInTip: true}, {bit: 15, group: 'other', name: 'RSSI_ADC', haveTip: true, showNameInTip: true},
{bit: 16, group: 'other', name: 'LED_STRIP', showNameInTip: true}, {bit: 16, group: 'other', name: 'LED_STRIP', showNameInTip: true},
{bit: 17, group: 'other', name: 'DASHBOARD', showNameInTip: true}, {bit: 17, group: 'other', name: 'DASHBOARD', showNameInTip: true},
{bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true} {bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true},
]; {bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true},
{bit: 26, group: 'other', name: 'SOFTSPI'},
if (semver.lt(CONFIG.flightControllerVersion, "2.0.0")) { {bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true},
features.push( {bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false},
{bit: 20, group: 'other', name: 'CHANNEL_FORWARDING', showNameInTip: true}, {bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false},
{bit: 5, group: 'other', name: 'SERVO_TILT', showNameInTip: true}
);
}
features.push(
{bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true}
);
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
features.push(
{bit: 26, group: 'other', name: 'SOFTSPI'}
);
}
features.push(
{bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true}
);
features.push(
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false}
);
features.push(
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false}
);
features.push(
{bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false}, {bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false},
{bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false} {bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false},
); {bit: 0, group: 'other', name: 'THR_VBAT_COMP', haveTip: true, showNameInTip: true},
{bit: 3, group: 'other', name: 'BAT_PROFILE_AUTOSWITCH', haveTip: true, showNameInTip: true}
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) { ];
features.push(
{bit: 0, group: 'other', name: 'THR_VBAT_COMP', haveTip: true, showNameInTip: true},
{bit: 3, group: 'other', name: 'BAT_PROFILE_AUTOSWITCH', haveTip: true, showNameInTip: true}
);
}
return features.reverse(); return features.reverse();
}, },
@ -802,13 +767,10 @@ var FC = {
'XBUS_MODE_B_RJ01', 'XBUS_MODE_B_RJ01',
'IBUS', 'IBUS',
'JETI EXBUS', 'JETI EXBUS',
'TBS Crossfire' 'TBS Crossfire',
'FPort'
]; ];
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) {
data.push('FPort');
}
return data; return data;
}, },
getSPIProtocolTypes: function () { getSPIProtocolTypes: function () {
@ -909,7 +871,7 @@ var FC = {
}, },
7: { 7: {
name: "DSHOT600", name: "DSHOT600",
message: "escProtocolNotAdvised", message: null,
defaultRate: 16000, defaultRate: 16000,
rates: { rates: {
16000: "16kHz" 16000: "16kHz"
@ -973,15 +935,7 @@ var FC = {
return []; return [];
}, },
getAccelerometerNames: function () { getAccelerometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
}
else if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"];
}
else {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "FAKE"];
}
}, },
getMagnetometerNames: function () { getMagnetometerNames: function () {
return ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "FAKE"]; return ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "FAKE"];
@ -989,30 +943,15 @@ var FC = {
getBarometerNames: function () { getBarometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.3.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.3.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "FAKE"]; return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "FAKE"];
} else if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "FAKE"];
} else if (semver.gte(CONFIG.flightControllerVersion, "1.6.2")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "FAKE"];
} else { } else {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "FAKE"]; return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "FAKE"];
} }
}, },
getPitotNames: function () { getPitotNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) { return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
}
else {
return ["NONE", "AUTO", "MS4525", "FAKE"];
}
}, },
getRangefinderNames: function () { getRangefinderNames: function () {
let data = [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"]; return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
data.push("Benewake TFmini")
}
return data;
}, },
getOpticalFlowNames: function () { getOpticalFlowNames: function () {
return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ]; return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
@ -1084,10 +1023,7 @@ var FC = {
} }
}, },
getRcMapLetters: function () { getRcMapLetters: function () {
if (semver.gte(CONFIG.flightControllerVersion, '1.9.1')) return ['A', 'E', 'R', 'T'];
return ['A', 'E', 'R', 'T'];
else
return ['A', 'E', 'R', 'T', '5', '6', '7', '8'];
}, },
isRcMapValid: function (val) { isRcMapValid: function (val) {
var strBuffer = val.split(''), var strBuffer = val.split(''),

View file

@ -231,49 +231,26 @@ var mspHelper = (function (gui) {
ANALOG.amperage = data.getInt16(5, true) / 100; // A ANALOG.amperage = data.getInt16(5, true) / 100; // A
break; break;
case MSPCodes.MSPV2_INAV_ANALOG: case MSPCodes.MSPV2_INAV_ANALOG:
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { let tmp = data.getUint8(offset++);
var tmp = data.getUint8(offset++); ANALOG.battery_full_when_plugged_in = (tmp & 1 ? true : false);
ANALOG.battery_full_when_plugged_in = (tmp & 1 ? true : false); ANALOG.use_capacity_thresholds = ((tmp & 2) >> 1 ? true : false);
ANALOG.use_capacity_thresholds = ((tmp & 2) >> 1 ? true : false); ANALOG.battery_state = (tmp & 12) >> 2;
ANALOG.battery_state = (tmp & 12) >> 2; ANALOG.cell_count = (tmp & 0xF0) >> 4;
ANALOG.cell_count = (tmp & 0xF0) >> 4; ANALOG.voltage = data.getUint16(offset, true) / 100.0;
ANALOG.voltage = data.getUint16(offset, true) / 100.0; offset += 2;
offset += 2; ANALOG.amperage = data.getInt16(offset, true) / 100; // A
ANALOG.amperage = data.getInt16(offset, true) / 100; // A offset += 2;
offset += 2; ANALOG.power = data.getInt32(offset, true) / 100.0;
ANALOG.power = data.getInt32(offset, true) / 100.0; offset += 4;
offset += 4; ANALOG.mAhdrawn = data.getInt32(offset, true);
ANALOG.mAhdrawn = data.getInt32(offset, true); offset += 4;
offset += 4; ANALOG.mWhdrawn = data.getInt32(offset, true);
ANALOG.mWhdrawn = data.getInt32(offset, true); offset += 4;
offset += 4; ANALOG.battery_remaining_capacity = data.getUint32(offset, true);
ANALOG.battery_remaining_capacity = data.getUint32(offset, true); offset += 4;
offset += 4; ANALOG.battery_percentage = data.getUint8(offset++);
ANALOG.battery_percentage = data.getUint8(offset++); ANALOG.rssi = data.getUint16(offset, true); // 0-1023
ANALOG.rssi = data.getUint16(offset, true); // 0-1023 offset += 2;
offset += 2;
} else {
ANALOG.voltage = data.getUint16(offset, true) / 100.0;
offset += 2;
ANALOG.cell_count = data.getUint8(offset++);
ANALOG.battery_percentage = data.getUint8(offset++);
ANALOG.power = data.getUint16(offset, true);
offset += 2;
ANALOG.mAhdrawn = data.getUint16(offset, true);
offset += 2;
ANALOG.mWhdrawn = data.getUint16(offset, true);
offset += 2;
ANALOG.rssi = data.getUint16(offset, true); // 0-1023
offset += 2;
ANALOG.amperage = data.getInt16(offset, true) / 100; // A
offset += 2;
var battery_flags = data.getUint8(offset++);
ANALOG.battery_full_when_plugged_in = (battery_flags & 1 ? true : false);
ANALOG.use_capacity_thresholds = ((battery_flags & 2) >> 1 ? true : false);
ANALOG.battery_state = (battery_flags & 12) >> 2;
ANALOG.battery_remaining_capacity = data.getUint32(offset, true);
offset += 4;
}
//noinspection JSValidateTypes //noinspection JSValidateTypes
dataHandler.analog_last_received_timestamp = Date.now(); dataHandler.analog_last_received_timestamp = Date.now();
break; break;
@ -385,12 +362,10 @@ var mspHelper = (function (gui) {
offset += 2; offset += 2;
MISC.vbatscale = data.getUint16(offset, true); MISC.vbatscale = data.getUint16(offset, true);
offset += 2; offset += 2;
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { MISC.voltage_source = data.getUint8(offset++);
MISC.voltage_source = data.getUint8(offset++); MISC.battery_cells = data.getUint8(offset++);
MISC.battery_cells = data.getUint8(offset++); MISC.vbatdetectcellvoltage = data.getUint16(offset, true) / 100;
MISC.vbatdetectcellvoltage = data.getUint16(offset, true) / 100; offset += 2;
offset += 2;
}
MISC.vbatmincellvoltage = data.getUint16(offset, true) / 100; MISC.vbatmincellvoltage = data.getUint16(offset, true) / 100;
offset += 2; offset += 2;
MISC.vbatmaxcellvoltage = data.getUint16(offset, true) / 100; MISC.vbatmaxcellvoltage = data.getUint16(offset, true) / 100;
@ -411,12 +386,10 @@ var mspHelper = (function (gui) {
case MSPCodes.MSPV2_INAV_BATTERY_CONFIG: case MSPCodes.MSPV2_INAV_BATTERY_CONFIG:
BATTERY_CONFIG.vbatscale = data.getUint16(offset, true); BATTERY_CONFIG.vbatscale = data.getUint16(offset, true);
offset += 2; offset += 2;
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { BATTERY_CONFIG.voltage_source = data.getUint8(offset++);
BATTERY_CONFIG.voltage_source = data.getUint8(offset++); BATTERY_CONFIG.battery_cells = data.getUint8(offset++);
BATTERY_CONFIG.battery_cells = data.getUint8(offset++); BATTERY_CONFIG.vbatdetectcellvoltage = data.getUint16(offset, true) / 100;
BATTERY_CONFIG.vbatdetectcellvoltage = data.getUint16(offset, true) / 100; offset += 2;
offset += 2;
}
BATTERY_CONFIG.vbatmincellvoltage = data.getUint16(offset, true) / 100; BATTERY_CONFIG.vbatmincellvoltage = data.getUint16(offset, true) / 100;
offset += 2; offset += 2;
BATTERY_CONFIG.vbatmaxcellvoltage = data.getUint16(offset, true) / 100; BATTERY_CONFIG.vbatmaxcellvoltage = data.getUint16(offset, true) / 100;
@ -499,28 +472,14 @@ var mspHelper = (function (gui) {
break; break;
case MSPCodes.MSP_SERVO_MIX_RULES: case MSPCodes.MSP_SERVO_MIX_RULES:
SERVO_RULES.flush(); SERVO_RULES.flush();
if (data.byteLength % 8 === 0) {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { for (i = 0; i < data.byteLength; i += 8) {
if (data.byteLength % 8 === 0) { SERVO_RULES.put(new ServoMixRule(
for (i = 0; i < data.byteLength; i += 8) { data.getInt8(i),
SERVO_RULES.put(new ServoMixRule( data.getInt8(i + 1),
data.getInt8(i), data.getInt16(i + 2, true),
data.getInt8(i + 1), data.getInt8(i + 4)
data.getInt16(i + 2, true), ));
data.getInt8(i + 4)
));
}
}
} else {
if (data.byteLength % 7 === 0) {
for (i = 0; i < data.byteLength; i += 7) {
SERVO_RULES.put(new ServoMixRule(
data.getInt8(i),
data.getInt8(i + 1),
data.getInt8(i + 2),
data.getInt8(i + 3)
));
}
} }
} }
SERVO_RULES.cleanup(); SERVO_RULES.cleanup();
@ -634,9 +593,7 @@ var mspHelper = (function (gui) {
SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++); SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_acc = data.getUint8(offset++); SENSOR_ALIGNMENT.align_acc = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_mag = data.getUint8(offset++); SENSOR_ALIGNMENT.align_mag = data.getUint8(offset++);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { SENSOR_ALIGNMENT.align_opflow = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_opflow = data.getUint8(offset++);
}
break; break;
case MSPCodes.MSP_SET_RAW_RC: case MSPCodes.MSP_SET_RAW_RC:
break; break;
@ -1224,11 +1181,9 @@ var mspHelper = (function (gui) {
FILTER_CONFIG.gyroNotchHz2 = data.getUint16(13, true); FILTER_CONFIG.gyroNotchHz2 = data.getUint16(13, true);
FILTER_CONFIG.gyroNotchCutoff2 = data.getUint16(15, true); FILTER_CONFIG.gyroNotchCutoff2 = data.getUint16(15, true);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { FILTER_CONFIG.accNotchHz = data.getUint16(17, true);
FILTER_CONFIG.accNotchHz = data.getUint16(17, true); FILTER_CONFIG.accNotchCutoff = data.getUint16(19, true);
FILTER_CONFIG.accNotchCutoff = data.getUint16(19, true); FILTER_CONFIG.gyroStage2LowpassHz = data.getUint16(21, true);
FILTER_CONFIG.gyroStage2LowpassHz = data.getUint16(21, true);
}
break; break;
@ -1693,12 +1648,10 @@ var mspHelper = (function (gui) {
buffer.push(highByte(Math.round(MISC.mag_declination * 10))); buffer.push(highByte(Math.round(MISC.mag_declination * 10)));
buffer.push(lowByte(MISC.vbatscale)); buffer.push(lowByte(MISC.vbatscale));
buffer.push(highByte(MISC.vbatscale)); buffer.push(highByte(MISC.vbatscale));
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { buffer.push(MISC.voltage_source);
buffer.push(MISC.voltage_source); buffer.push(MISC.battery_cells);
buffer.push(MISC.battery_cells); buffer.push(lowByte(Math.round(MISC.vbatdetectcellvoltage * 100)));
buffer.push(lowByte(Math.round(MISC.vbatdetectcellvoltage * 100))); buffer.push(highByte(Math.round(MISC.vbatdetectcellvoltage * 100)));
buffer.push(highByte(Math.round(MISC.vbatdetectcellvoltage * 100)));
}
buffer.push(lowByte(Math.round(MISC.vbatmincellvoltage * 100))); buffer.push(lowByte(Math.round(MISC.vbatmincellvoltage * 100)));
buffer.push(highByte(Math.round(MISC.vbatmincellvoltage * 100))); buffer.push(highByte(Math.round(MISC.vbatmincellvoltage * 100)));
buffer.push(lowByte(Math.round(MISC.vbatmaxcellvoltage * 100))); buffer.push(lowByte(Math.round(MISC.vbatmaxcellvoltage * 100)));
@ -1716,12 +1669,10 @@ var mspHelper = (function (gui) {
case MSPCodes.MSPV2_INAV_SET_BATTERY_CONFIG: case MSPCodes.MSPV2_INAV_SET_BATTERY_CONFIG:
buffer.push(lowByte(BATTERY_CONFIG.vbatscale)); buffer.push(lowByte(BATTERY_CONFIG.vbatscale));
buffer.push(highByte(BATTERY_CONFIG.vbatscale)); buffer.push(highByte(BATTERY_CONFIG.vbatscale));
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { buffer.push(BATTERY_CONFIG.voltage_source);
buffer.push(BATTERY_CONFIG.voltage_source); buffer.push(BATTERY_CONFIG.battery_cells);
buffer.push(BATTERY_CONFIG.battery_cells); buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatdetectcellvoltage * 100))); buffer.push(highByte(Math.round(BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
buffer.push(highByte(Math.round(BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
}
buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 100))); buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 100)));
buffer.push(highByte(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 100))); buffer.push(highByte(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 100)));
buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatmaxcellvoltage * 100))); buffer.push(lowByte(Math.round(BATTERY_CONFIG.vbatmaxcellvoltage * 100)));
@ -1874,9 +1825,7 @@ var mspHelper = (function (gui) {
buffer.push(SENSOR_ALIGNMENT.align_gyro); buffer.push(SENSOR_ALIGNMENT.align_gyro);
buffer.push(SENSOR_ALIGNMENT.align_acc); buffer.push(SENSOR_ALIGNMENT.align_acc);
buffer.push(SENSOR_ALIGNMENT.align_mag); buffer.push(SENSOR_ALIGNMENT.align_mag);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { buffer.push(SENSOR_ALIGNMENT.align_opflow);
buffer.push(SENSOR_ALIGNMENT.align_opflow);
}
break; break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG: case MSPCodes.MSP_SET_ADVANCED_CONFIG:
@ -2072,16 +2021,14 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(FILTER_CONFIG.gyroNotchCutoff2)); buffer.push(lowByte(FILTER_CONFIG.gyroNotchCutoff2));
buffer.push(highByte(FILTER_CONFIG.gyroNotchCutoff2)); buffer.push(highByte(FILTER_CONFIG.gyroNotchCutoff2));
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { buffer.push(lowByte(FILTER_CONFIG.accNotchHz));
buffer.push(lowByte(FILTER_CONFIG.accNotchHz)); buffer.push(highByte(FILTER_CONFIG.accNotchHz));
buffer.push(highByte(FILTER_CONFIG.accNotchHz));
buffer.push(lowByte(FILTER_CONFIG.accNotchCutoff)); buffer.push(lowByte(FILTER_CONFIG.accNotchCutoff));
buffer.push(highByte(FILTER_CONFIG.accNotchCutoff)); buffer.push(highByte(FILTER_CONFIG.accNotchCutoff));
buffer.push(lowByte(FILTER_CONFIG.gyroStage2LowpassHz)); buffer.push(lowByte(FILTER_CONFIG.gyroStage2LowpassHz));
buffer.push(highByte(FILTER_CONFIG.gyroStage2LowpassHz)); buffer.push(highByte(FILTER_CONFIG.gyroStage2LowpassHz));
}
break; break;
@ -2311,12 +2258,8 @@ var mspHelper = (function (gui) {
buffer.push(servoIndex); buffer.push(servoIndex);
buffer.push(servoRule.getTarget()); buffer.push(servoRule.getTarget());
buffer.push(servoRule.getInput()); buffer.push(servoRule.getInput());
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { buffer.push(lowByte(servoRule.getRate()));
buffer.push(lowByte(servoRule.getRate())); buffer.push(highByte(servoRule.getRate()));
buffer.push(highByte(servoRule.getRate()));
} else {
buffer.push(servoRule.getRate());
}
buffer.push(servoRule.getSpeed()); buffer.push(servoRule.getSpeed());
buffer.push(0); buffer.push(0);
buffer.push(0); buffer.push(0);
@ -2838,10 +2781,7 @@ var mspHelper = (function (gui) {
}; };
self.queryFcStatus = function (callback) { self.queryFcStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, callback);
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, callback);
else
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false, callback);
}; };
self.loadMisc = function (callback) { self.loadMisc = function (callback) {
@ -2853,12 +2793,7 @@ var mspHelper = (function (gui) {
}; };
self.loadOutputMapping = function (callback) { self.loadOutputMapping = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) MSP.send_message(MSPCodes.MSPV2_INAV_OUTPUT_MAPPING, false, false, callback);
MSP.send_message(MSPCodes.MSPV2_INAV_OUTPUT_MAPPING, false, false, callback);
else {
OUTPUT_MAPPING.flush();
callback();
}
}; };
self.loadBatteryConfig = function (callback) { self.loadBatteryConfig = function (callback) {
@ -3042,9 +2977,6 @@ var mspHelper = (function (gui) {
}; };
self._getSetting = function (name) { self._getSetting = function (name) {
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) {
return self._getLegacySetting(name);
}
if (SETTINGS[name]) { if (SETTINGS[name]) {
return Promise.resolve(SETTINGS[name]); return Promise.resolve(SETTINGS[name]);
} }
@ -3101,31 +3033,6 @@ var mspHelper = (function (gui) {
}); });
} }
self._getLegacySetting = function (name) {
var promise;
if (SETTINGS) {
promise = Promise.resolve(SETTINGS);
} else {
promise = new Promise(function (resolve, reject) {
$.ajax({
url: chrome.runtime.getURL('/resources/settings.json'),
dataType: 'json',
error: function (jqXHR, text, error) {
reject(error);
},
success: function (data) {
SETTINGS = data;
resolve(data);
}
});
});
}
return promise.then(function (data) {
return data[name];
});
};
self._encodeSettingReference = function (name, index, data) { self._encodeSettingReference = function (name, index, data) {
if (Number.isInteger(index)) { if (Number.isInteger(index)) {
data.push8(0); data.push8(0);
@ -3286,78 +3193,46 @@ var mspHelper = (function (gui) {
}; };
self.loadMixerConfig = function (callback) { self.loadMixerConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) { MSP.send_message(MSPCodes.MSP2_INAV_MIXER, false, false, callback);
MSP.send_message(MSPCodes.MSP2_INAV_MIXER, false, false, callback);
} else {
callback();
}
}; };
self.saveMixerConfig = function (callback) { self.saveMixerConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) { MSP.send_message(MSPCodes.MSP2_INAV_SET_MIXER, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MIXER), false, callback);
MSP.send_message(MSPCodes.MSP2_INAV_SET_MIXER, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MIXER), false, callback);
} else {
callback();
}
}; };
self.loadVTXConfig = function (callback) { self.loadVTXConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
} else {
callback();
}
}; };
self.saveVTXConfig = function(callback) { self.saveVTXConfig = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
} else {
callback();
}
}; };
self.loadBrakingConfig = function(callback) { self.loadBrakingConfig = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
} else {
callback();
}
} }
self.saveBrakingConfig = function(callback) { self.saveBrakingConfig = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
} else {
callback();
}
}; };
self.loadParameterGroups = function(callback) { self.loadParameterGroups = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) { var groups = [];
var groups = []; while (resp.data.offset < resp.data.byteLength) {
while (resp.data.offset < resp.data.byteLength) { var id = resp.data.readU16();
var id = resp.data.readU16(); var start = resp.data.readU16();
var start = resp.data.readU16(); var end = resp.data.readU16();
var end = resp.data.readU16(); groups.push({id: id, start: start, end: end});
groups.push({id: id, start: start, end: end}); }
} if (callback) {
if (callback) { callback(groups);
callback(groups); }
} });
});
} else if (callback) {
callback();
}
}; };
self.loadBrakingConfig = function(callback) { self.loadBrakingConfig = function(callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
} else {
callback();
}
} }
self.loadSensorStatus = function (callback) { self.loadSensorStatus = function (callback) {

View file

@ -102,13 +102,7 @@ helper.periodicStatusUpdater = (function () {
} }
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS, false, false); MSP.send_message(MSPCodes.MSP_SENSOR_STATUS, false, false);
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false);
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false);
} else {
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
}
MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false); MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false);
MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false); MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false);

View file

@ -340,6 +340,7 @@ function onConnect() {
}, 100); }, 100);
helper.interval.add('global_data_refresh', helper.periodicStatusUpdater.run, helper.periodicStatusUpdater.getUpdateInterval(serial.bitrate), false); helper.interval.add('global_data_refresh', helper.periodicStatusUpdater.run, helper.periodicStatusUpdater.getUpdateInterval(serial.bitrate), false);
helper.defaultsDialog.init();
} }
function onClosed(result) { function onClosed(result) {

View file

@ -145,12 +145,6 @@ $(document).ready(function () {
var tab = tabClass.substring(4); var tab = tabClass.substring(4);
var tabName = $(self).text(); var tabName = $(self).text();
if (CONFIGURATOR.connectionValid && semver.lt(CONFIG.flightControllerVersion, "2.0.0")) {
$('#battery_profile_change').hide();
$('#profile_change').css('width', '125px');
$('#dataflash_wrapper_global').css('width', '125px');
}
if (tabRequiresConnection && !CONFIGURATOR.connectionValid) { if (tabRequiresConnection && !CONFIGURATOR.connectionValid) {
GUI.log(chrome.i18n.getMessage('tabSwitchConnectionRequired')); GUI.log(chrome.i18n.getMessage('tabSwitchConnectionRequired'));
return; return;

2290
package-lock.json generated

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -75,6 +75,7 @@
.config-section .number, .config-section .number,
.config-section .select, .config-section .select,
.config-section .checkbox,
.tab-configuration .number, .tab-configuration .number,
.tab-configuration .select, .tab-configuration .select,
.tab-configuration .radio, .tab-configuration .radio,
@ -90,6 +91,7 @@ hr {
.config-section .number:last-child, .config-section .number:last-child,
.config-section .select:last-child, .config-section .select:last-child,
.config-section .checkbox:last-child,
.tab-configuration .number:last-child, .tab-configuration .number:last-child,
.tab-configuration .select:last-child, .tab-configuration .select:last-child,
.tab-configuration .radio:last-child, .tab-configuration .radio:last-child,

View file

@ -284,7 +284,7 @@
</div> </div>
</div> </div>
<div class="config-section gui_box grey requires-v2_1"> <div class="config-section gui_box grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="multirotorBrakingConfiguration"></div> <div class="spacer_box_title" data-i18n="multirotorBrakingConfiguration"></div>
</div> </div>

View file

@ -61,13 +61,6 @@ TABS.advanced_tuning.initialize = function (callback) {
$rthAllowLanding = $('#rthAllowLanding'), $rthAllowLanding = $('#rthAllowLanding'),
$rthAltControlMode = $('#rthAltControlMode'); $rthAltControlMode = $('#rthAltControlMode');
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
$('.requires-v2_1').show();
} else {
$('.requires-v2_1').hide();
}
$rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst); $rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst);
$rthClimbFirst.change(function () { $rthClimbFirst.change(function () {
if ($(this).is(":checked")) { if ($(this).is(":checked")) {

View file

@ -10,21 +10,6 @@
</div> </div>
</div> </div>
<div class="leftWrapper"> <div class="leftWrapper">
<div class="mixer gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationMixer"></div>
</div>
<div class="spacer_box">
<div class="mixerPreview half">
<img src="./resources/motor_order/custom.svg" />
</div>
<div class="half" style="width: calc(50% - 10px); margin-left: 10px;">
<select class="mixerList">
<!-- list generated here -->
</select>
</div>
</div>
</div>
<div class="config-section sensors gui_box grey"> <div class="config-section sensors gui_box grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationSensors"></div> <div class="spacer_box_title" data-i18n="configurationSensors"></div>
@ -56,7 +41,7 @@
<label for="sensor-rangefinder"> <span data-i18n="sensorRangefinder"></span></label> <label for="sensor-rangefinder"> <span data-i18n="sensorRangefinder"></span></label>
</div> </div>
<div class="select requires-v2_0_0"> <div class="select">
<select id="sensor-opflow"></select> <select id="sensor-opflow"></select>
<label for="sensor-opflow"> <span data-i18n="sensorOpflow"></span></label> <label for="sensor-opflow"> <span data-i18n="sensorOpflow"></span></label>
</div> </div>
@ -276,81 +261,6 @@
<!--Right column begins here--> <!--Right column begins here-->
<div class="rightWrapper"> <div class="rightWrapper">
<div class="config-section gui_box grey">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationEscFeatures"></div>
</div>
<div class="spacer_box">
<div class="features esc-priority"></div>
<!--list of generated features goes here-->
<div id="esc-protocols">
<div id="esc-protocol-warning" class="warning-box"></div>
<div class="select">
<select name="esc-protocol" id="esc-protocol"></select>
<label for="esc-protocol">
<span data-i18n="escProtocol"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="escProtocolHelp"></div>
</div>
<div class="select hide-for-shot">
<select name="esc-rate" id="esc-rate"></select>
<label for="esc-rate">
<span data-i18n="escRefreshRate"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="escRefreshRatelHelp"></div>
</div>
<div class="clear-both"></div>
</div>
<div id="servo-rate-container">
<div class="select">
<select name="servo-rate" id="servo-rate"></select>
<label for="servo-rate">
<span data-i18n="servoRefreshRate"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="servoRefreshRatelHelp"></div>
</div>
<div class="clear-both"></div>
</div>
<div class="features esc"></div>
<!--list of generated features goes here-->
<div class="number disarmdelay" style="display: none; margin-bottom: 5px;">
<input type="number" id="autodisarmdelay" name="autodisarmdelay" min="0" max="60" />
<label for="autodisarmdelay">
<span data-i18n="configurationAutoDisarmDelay"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationAutoDisarmDelayHelp"></div>
</div>
<!-- -->
<div class="number hide-for-shot">
<input type="number" id="minthrottle" name="minthrottle" min="0" max="2000" />
<label for="minthrottle">
<span data-i18n="configurationThrottleMinimum"></span>
</label>
</div>
<div class="number midthrottle_wrapper hide-for-shot">
<input type="number" id="midthrottle" name="midthrottle" min="1200" max="1700" />
<label for="midthrottle">
<span data-i18n="configurationThrottleMid"></span>
</label>
</div>
<div class="number hide-for-shot">
<input type="number" id="maxthrottle" name="maxthrottle" min="0" max="2000" />
<label for="maxthrottle">
<span data-i18n="configurationThrottleMaximum"></span>
</label>
</div>
<div class="number hide-for-shot">
<input type="number" id="mincommand" name="mincommand" min="0" max="2000" />
<label for="mincommand">
<span data-i18n="configurationThrottleMinimumCommand"></span>
</label>
</div>
</div>
</div>
<div class="config-section gui_box grey"> <div class="config-section gui_box grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="configurationSystem"></div> <div class="spacer_box_title" data-i18n="configurationSystem"></div>
@ -363,12 +273,6 @@
<div class="helpicon cf_tip" data-i18n_title="configurationGyroLpfHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationGyroLpfHelp"></div>
</div> </div>
<div class="select removed-v2_1_0">
<select id="async-mode"></select>
<label for="async-mode"> <span data-i18n="configurationAsyncMode"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationAsyncModeHelp"></div>
</div>
<div id="gyro-sync-wrapper" class="checkbox"> <div id="gyro-sync-wrapper" class="checkbox">
<input type="checkbox" id="gyro-sync-checkbox" class="toggle" /> <input type="checkbox" id="gyro-sync-checkbox" class="toggle" />
<label for="gyro-sync-checkbox"> <label for="gyro-sync-checkbox">
@ -384,21 +288,6 @@
<div class="helpicon cf_tip" data-i18n_title="configurationGyroFrequencyHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationGyroFrequencyHelp"></div>
</div> </div>
<div id="accelerometer-frequency-wrapper" class="checkbox removed-v2_1_0">
<select id="accelerometer-frequency"></select>
<label for="accelerometer-frequency">
<span data-i18n="configurationAccelerometerFrequencyTitle"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationAccelerometerFrequencyHelp"></div>
</div>
<div id="attitude-frequency-wrapper" class="checkbox removed-v2_1_0">
<select id="attitude-frequency"></select>
<label for="attitude-frequency">
<span data-i18n="configurationAttitudeFrequencyTitle"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationAttitudeFrequencyHelp"></div>
</div>
<div id="looptime-warning" class="info-box" data-i18n="looptimeNotAdvised"></div> <div id="looptime-warning" class="info-box" data-i18n="looptimeNotAdvised"></div>
<div class="select"> <div class="select">
<select id="looptime"></select> <select id="looptime"></select>
@ -418,7 +307,7 @@
<div class="features batteryVoltage"></div> <div class="features batteryVoltage"></div>
<!--list of generated features goes here--> <!--list of generated features goes here-->
<div class="select requires-v2_0_0"> <div class="select">
<select id="voltagesource" class="voltagesource"> <select id="voltagesource" class="voltagesource">
<option value="0">Raw</option> <option value="0">Raw</option>
<option value="1">Sag compensated</option> <option value="1">Sag compensated</option>
@ -428,12 +317,12 @@
</label> </label>
<div class="helpicon cf_tip" data-i18n_title="configurationVoltageSourceHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationVoltageSourceHelp"></div>
</div> </div>
<div class="number requires-v2_0_0"> <div class="number">
<input type="number" id="cells" name="cells" step="1" min="0" max="8" /> <input type="number" id="cells" name="cells" step="1" min="0" max="8" />
<label for="cells"><span data-i18n="configurationBatteryCells"></span></label> <label for="cells"><span data-i18n="configurationBatteryCells"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellsHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellsHelp"></div>
</div> </div>
<div class="number requires-v2_0_0"> <div class="number">
<input type="number" id="celldetectvoltage" name="celldetectvoltage" step="0.01" min="1" max="5" /> <input type="number" id="celldetectvoltage" name="celldetectvoltage" step="0.01" min="1" max="5" />
<label for="celldetectvoltage"><span data-i18n="configurationBatteryCellDetectVoltage"></span></label> <label for="celldetectvoltage"><span data-i18n="configurationBatteryCellDetectVoltage"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellDetectVoltageHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationBatteryCellDetectVoltageHelp"></div>

View file

@ -41,10 +41,10 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
mspHelper.loadSensorConfig, mspHelper.loadSensorConfig,
mspHelper.loadVTXConfig, mspHelper.loadVTXConfig,
mspHelper.loadMixerConfig, mspHelper.loadMixerConfig,
loadCraftName loadCraftName,
mspHelper.loadMiscV2
]; ];
loadChain.push(mspHelper.loadMiscV2);
loadChainer.setChain(loadChain); loadChainer.setChain(loadChain);
loadChainer.setExitPoint(load_html); loadChainer.setExitPoint(load_html);
loadChainer.execute(); loadChainer.execute();
@ -64,11 +64,10 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
mspHelper.saveSensorConfig, mspHelper.saveSensorConfig,
mspHelper.saveVTXConfig, mspHelper.saveVTXConfig,
saveCraftName, saveCraftName,
mspHelper.saveMiscV2,
mspHelper.saveToEeprom
]; ];
saveChain.push(mspHelper.saveMiscV2);
saveChain.push(mspHelper.saveToEeprom);
saveChainer.setChain(saveChain); saveChainer.setChain(saveChain);
saveChainer.setExitPoint(reboot); saveChainer.setExitPoint(reboot);
@ -383,30 +382,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// fill magnetometer // fill magnetometer
$('#mag_declination').val(MISC.mag_declination); $('#mag_declination').val(MISC.mag_declination);
//fill motor disarm params and FC loop time
$('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay);
$('div.disarm').show();
if (bit_check(BF_CONFIG.features, 4)) { //MOTOR_STOP
$('div.disarmdelay').show();
} else {
$('div.disarmdelay').hide();
}
// fill throttle
$('#minthrottle').val(MISC.minthrottle);
// midrc was removed in 2.0, but the firmware still excepts
// the MSP frame with it for backwards compatibility, so we
// just hide it from the UI.
var midThrottleWrapper = $('.midthrottle_wrapper');
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) {
$('#midthrottle').val(MISC.midrc);
midThrottleWrapper.show();
} else {
midThrottleWrapper.hide();
}
$('#maxthrottle').val(MISC.maxthrottle);
$('#mincommand').val(MISC.mincommand);
// fill battery voltage // fill battery voltage
$('#voltagesource').val(MISC.voltage_source); $('#voltagesource').val(MISC.voltage_source);
$('#cells').val(MISC.battery_cells); $('#cells').val(MISC.battery_cells);
@ -416,20 +391,9 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#warningcellvoltage').val(MISC.vbatwarningcellvoltage); $('#warningcellvoltage').val(MISC.vbatwarningcellvoltage);
$('#voltagescale').val(MISC.vbatscale); $('#voltagescale').val(MISC.vbatscale);
// adjust current offset input attributes
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) {
var current_offset_input = $('#currentoffset');
current_offset_input.attr('step', '1');
current_offset_input.attr('min', '-3300');
current_offset_input.attr('max', '3300');
}
// fill current // fill current
$('#currentscale').val(BF_CONFIG.currentscale); $('#currentscale').val(BF_CONFIG.currentscale);
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0')) $('#currentoffset').val(BF_CONFIG.currentoffset / 10);
$('#currentoffset').val(BF_CONFIG.currentoffset);
else
$('#currentoffset').val(BF_CONFIG.currentoffset / 10);
// fill battery capacity // fill battery capacity
$('#battery_capacity').val(MISC.battery_capacity); $('#battery_capacity').val(MISC.battery_capacity);
@ -437,90 +401,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#battery_capacity_critical').val(MISC.battery_capacity_critical * 100 / MISC.battery_capacity); $('#battery_capacity_critical').val(MISC.battery_capacity_critical * 100 / MISC.battery_capacity);
$('#battery_capacity_unit').val(MISC.battery_capacity_unit); $('#battery_capacity_unit').val(MISC.battery_capacity_unit);
var escProtocols = FC.getEscProtocols();
var servoRates = FC.getServoRates();
function buildMotorRates() {
var protocolData = escProtocols[ADVANCED_CONFIG.motorPwmProtocol];
$escRate.find('option').remove();
for (var i in protocolData.rates) {
if (protocolData.rates.hasOwnProperty(i)) {
$escRate.append('<option value="' + i + '">' + protocolData.rates[i] + '</option>');
}
}
/*
* If rate from FC is not on the list, add a new entry
*/
if ($escRate.find('[value="' + ADVANCED_CONFIG.motorPwmRate + '"]').length == 0) {
$escRate.append('<option value="' + ADVANCED_CONFIG.motorPwmRate + '">' + ADVANCED_CONFIG.motorPwmRate + 'Hz</option>');
}
if (ADVANCED_CONFIG.motorPwmProtocol >= 5) {
//DSHOT/SERIALSHOT protocols, simplify UI
$('.hide-for-shot').addClass('is-hidden');
} else {
$('.hide-for-shot').removeClass('is-hidden');
}
if (protocolData.message !== null) {
$('#esc-protocol-warning').html(chrome.i18n.getMessage(protocolData.message));
$('#esc-protocol-warning').show();
} else {
$('#esc-protocol-warning').hide();
}
}
var $escProtocol = $('#esc-protocol');
var $escRate = $('#esc-rate');
for (i in escProtocols) {
if (escProtocols.hasOwnProperty(i)) {
var protocolData = escProtocols[i];
$escProtocol.append('<option value="' + i + '">' + protocolData.name + '</option>');
}
}
$escProtocol.val(ADVANCED_CONFIG.motorPwmProtocol);
buildMotorRates();
$escRate.val(ADVANCED_CONFIG.motorPwmRate);
$escProtocol.change(function () {
ADVANCED_CONFIG.motorPwmProtocol = $(this).val();
buildMotorRates();
ADVANCED_CONFIG.motorPwmRate = escProtocols[ADVANCED_CONFIG.motorPwmProtocol].defaultRate;
$escRate.val(ADVANCED_CONFIG.motorPwmRate);
});
$escRate.change(function () {
ADVANCED_CONFIG.motorPwmRate = $(this).val();
});
$("#esc-protocols").show();
var $servoRate = $('#servo-rate');
for (i in servoRates) {
if (servoRates.hasOwnProperty(i)) {
$servoRate.append('<option value="' + i + '">' + servoRates[i] + '</option>');
}
}
/*
* If rate from FC is not on the list, add a new entry
*/
if ($servoRate.find('[value="' + ADVANCED_CONFIG.servoPwmRate + '"]').length == 0) {
$servoRate.append('<option value="' + ADVANCED_CONFIG.servoPwmRate + '">' + ADVANCED_CONFIG.servoPwmRate + 'Hz</option>');
}
$servoRate.val(ADVANCED_CONFIG.servoPwmRate);
$servoRate.change(function () {
ADVANCED_CONFIG.servoPwmRate = $(this).val();
});
$('#servo-rate-container').show();
var $looptime = $("#looptime"); var $looptime = $("#looptime");
var $gyroLpf = $("#gyro-lpf"), var $gyroLpf = $("#gyro-lpf"),
@ -717,20 +597,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
SENSOR_CONFIG.opflow = $sensorOpflow.val(); SENSOR_CONFIG.opflow = $sensorOpflow.val();
}); });
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
$(".requires-v2_0_0").show();
} else {
$(".requires-v2_0_0").hide();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
$(".removed-v2_1_0").hide();
$(".requires-v2_1_0").show();
} else {
$(".removed-v2_1_0").show();
$(".requires-v2_1_0").hide();
}
$('#3ddeadbandlow').val(_3D.deadband3d_low); $('#3ddeadbandlow').val(_3D.deadband3d_low);
$('#3ddeadbandhigh').val(_3D.deadband3d_high); $('#3ddeadbandhigh').val(_3D.deadband3d_high);
$('#3dneutral').val(_3D.neutral3d); $('#3dneutral').val(_3D.neutral3d);
@ -816,11 +682,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
MISC.battery_capacity_unit = $('#battery_capacity_unit').val(); MISC.battery_capacity_unit = $('#battery_capacity_unit').val();
BF_CONFIG.currentscale = parseInt($('#currentscale').val()); BF_CONFIG.currentscale = parseInt($('#currentscale').val());
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
if (semver.lt(CONFIG.flightControllerVersion, '2.0.0'))
BF_CONFIG.currentoffset = parseInt($('#currentoffset').val());
else
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
_3D.deadband3d_low = parseInt($('#3ddeadbandlow').val()); _3D.deadband3d_low = parseInt($('#3ddeadbandlow').val());
_3D.deadband3d_high = parseInt($('#3ddeadbandhigh').val()); _3D.deadband3d_high = parseInt($('#3ddeadbandhigh').val());
@ -850,9 +712,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]); googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]); googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
} }
if (!FC.isNewMixer()) {
googleAnalytics.sendEvent('Setting', 'Mixer', helper.mixer.getById(BF_CONFIG.mixerConfiguration).name);
}
googleAnalytics.sendEvent('Setting', 'ReceiverMode', $('#rxType').val()); googleAnalytics.sendEvent('Setting', 'ReceiverMode', $('#rxType').val());
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime); googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
@ -882,13 +742,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#batterycurrent').val([ANALOG.amperage.toFixed(2)]); $('#batterycurrent').val([ANALOG.amperage.toFixed(2)]);
}, 100, true); // 10 fps }, 100, true); // 10 fps
/*
* Hide mixer section
*/
if (FC.isNewMixer()) {
$('.mixer').addClass("is-hidden");
}
GUI.content_ready(callback); GUI.content_ready(callback);
} }
}; };

View file

@ -1,5 +1,4 @@
<div class="tab-configuration tab-mixer toolbar_fixed_bottom"> <div class="tab-configuration tab-mixer toolbar_fixed_bottom">
<div class="content_wrapper is-hidden" id="mixer-hidden-content"><p data-i18n="fcFirmwareUpdateRequired"></p></div>
<div class="content_wrapper" id="mixer-main-content"> <div class="content_wrapper" id="mixer-main-content">
<div class="tab_title" data-i18n="tabMixer">Mixer</div> <div class="tab_title" data-i18n="tabMixer">Mixer</div>
<!-- Top row --> <!-- Top row -->

View file

@ -141,11 +141,9 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
} }
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { let rate_inputs = $('.mix-rule-rate');
rate_inputs = $('.mix-rule-rate'); rate_inputs.attr("min", -1000);
rate_inputs.attr("min", -1000); rate_inputs.attr("max", 1000);
rate_inputs.attr("max", 1000);
}
localize(); localize();
} }
@ -216,11 +214,6 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
function processHtml() { function processHtml() {
if (!FC.isNewMixer()) {
$('#mixer-hidden-content').removeClass("is-hidden");
$('#mixer-main-content').remove();
}
$servoMixTable = $('#servo-mix-table'); $servoMixTable = $('#servo-mix-table');
$servoMixTableBody = $servoMixTable.find('tbody'); $servoMixTableBody = $servoMixTable.find('tbody');
$motorMixTable = $('#motor-mix-table'); $motorMixTable = $('#motor-mix-table');

View file

@ -1,6 +1,79 @@
<div class="tab-motors toolbar_fixed_bottom"> <div class="tab-motors toolbar_fixed_bottom">
<div class="content_wrapper"> <div class="content_wrapper">
<div class="tab_title" i18n="tabMotorTesting">Motors</div> <div class="tab_title" i18n="tabMotorTesting"></div>
<div class="gui_box grey config-section">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="ouptputsConfiguration"></div>
</div>
<div class="spacer">
<div class="checkbox">
<input type="checkbox" data-bit="28" class="feature toggle" name="PWM_OUTPUT_ENABLE" title="PWM_OUTPUT_ENABLE" id="feature-28">
<label for="feature-28">
<span data-i18n="featurePWM_OUTPUT_ENABLE"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="featurePWM_OUTPUT_ENABLETip"></div>
</div>
<!--list of generated features goes here-->
<div id="esc-protocols">
<div id="esc-protocol-warning" class="warning-box"></div>
<div class="select">
<select name="esc-protocol" id="esc-protocol"></select>
<label for="esc-protocol">
<span data-i18n="escProtocol"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="escProtocolHelp"></div>
</div>
<div class="select hide-for-shot">
<select name="esc-rate" id="esc-rate"></select>
<label for="esc-rate">
<span data-i18n="escRefreshRate"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="escRefreshRatelHelp"></div>
</div>
<div class="clear-both"></div>
</div>
<div id="servo-rate-container">
<div class="select">
<select name="servo-rate" id="servo-rate"></select>
<label for="servo-rate">
<span data-i18n="servoRefreshRate"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="servoRefreshRatelHelp"></div>
</div>
<div class="clear-both"></div>
</div>
<div class="checkbox">
<input type="checkbox" data-bit="4" class="feature toggle" name="MOTOR_STOP" title="MOTOR_STOP" id="feature-4">
<label for="feature-4">
<span data-i18n="featureMOTOR_STOP"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="featureMOTOR_STOPTip"></div>
</div>
<!-- -->
<div class="number hide-for-shot">
<input type="number" data-simple-bind="MISC.minthrottle" id="minthrottle" name="minthrottle" min="0" max="2000" />
<label for="minthrottle">
<span data-i18n="configurationThrottleMinimum"></span>
</label>
</div>
<div class="number hide-for-shot">
<input type="number" data-simple-bind="MISC.maxthrottle" id="maxthrottle" name="maxthrottle" min="0" max="2000" />
<label for="maxthrottle">
<span data-i18n="configurationThrottleMaximum"></span>
</label>
</div>
<div class="number hide-for-shot">
<input type="number" data-simple-bind="MISC.mincommand" id="mincommand" name="mincommand" min="0" max="2000" />
<label for="mincommand">
<span data-i18n="configurationThrottleMinimumCommand"></span>
</label>
</div>
</div>
</div>
<div class="gui_box grey"> <div class="gui_box grey">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="motors"></div> <div class="spacer_box_title" data-i18n="motors"></div>
@ -101,6 +174,7 @@
<div class="content_toolbar"> <div class="content_toolbar">
<div class="btn save_btn"> <div class="btn save_btn">
<a class="update" href="#" data-i18n="servosButtonSave"></a> <a class="update" href="#" data-i18n="servosButtonSave"></a>
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
</div> </div>
</div> </div>
</div> </div>

View file

@ -23,7 +23,7 @@ TABS.motors.initialize = function (callback) {
var loadChainer = new MSPChainerClass(); var loadChainer = new MSPChainerClass();
loadChainer.setChain([ loadChainer.setChain([
mspHelper.loadMisc, mspHelper.loadMiscV2,
mspHelper.loadBfConfig, mspHelper.loadBfConfig,
mspHelper.load3dConfig, mspHelper.load3dConfig,
mspHelper.loadMotors, mspHelper.loadMotors,
@ -34,6 +34,7 @@ TABS.motors.initialize = function (callback) {
mspHelper.loadServoConfiguration, mspHelper.loadServoConfiguration,
mspHelper.loadOutputMapping, mspHelper.loadOutputMapping,
mspHelper.loadRcData, mspHelper.loadRcData,
mspHelper.loadAdvancedConfig,
]); ]);
loadChainer.setExitPoint(load_html); loadChainer.setExitPoint(load_html);
loadChainer.execute(); loadChainer.execute();
@ -43,6 +44,9 @@ TABS.motors.initialize = function (callback) {
saveChainer.setChain([ saveChainer.setChain([
mspHelper.sendServoConfigurations, mspHelper.sendServoConfigurations,
mspHelper.saveAdvancedConfig,
mspHelper.saveBfConfig,
mspHelper.saveMiscV2,
mspHelper.saveToEeprom mspHelper.saveToEeprom
]); ]);
saveChainer.setExitPoint(function () { saveChainer.setExitPoint(function () {
@ -57,9 +61,124 @@ TABS.motors.initialize = function (callback) {
function onLoad() { function onLoad() {
process_motors(); process_motors();
process_servos(); process_servos();
processConfiguration();
finalize(); finalize();
} }
function processConfiguration() {
let escProtocols = FC.getEscProtocols();
let servoRates = FC.getServoRates();
function buildMotorRates() {
var protocolData = escProtocols[ADVANCED_CONFIG.motorPwmProtocol];
$escRate.find('option').remove();
for (var i in protocolData.rates) {
if (protocolData.rates.hasOwnProperty(i)) {
$escRate.append('<option value="' + i + '">' + protocolData.rates[i] + '</option>');
}
}
/*
* If rate from FC is not on the list, add a new entry
*/
if ($escRate.find('[value="' + ADVANCED_CONFIG.motorPwmRate + '"]').length == 0) {
$escRate.append('<option value="' + ADVANCED_CONFIG.motorPwmRate + '">' + ADVANCED_CONFIG.motorPwmRate + 'Hz</option>');
}
if (ADVANCED_CONFIG.motorPwmProtocol >= 5) {
//DSHOT/SERIALSHOT protocols, simplify UI
$('.hide-for-shot').addClass('is-hidden');
} else {
$('.hide-for-shot').removeClass('is-hidden');
}
if (protocolData.message !== null) {
$('#esc-protocol-warning').html(chrome.i18n.getMessage(protocolData.message));
$('#esc-protocol-warning').show();
} else {
$('#esc-protocol-warning').hide();
}
}
let $escProtocol = $('#esc-protocol');
let $escRate = $('#esc-rate');
for (i in escProtocols) {
if (escProtocols.hasOwnProperty(i)) {
var protocolData = escProtocols[i];
$escProtocol.append('<option value="' + i + '">' + protocolData.name + '</option>');
}
}
$escProtocol.val(ADVANCED_CONFIG.motorPwmProtocol);
buildMotorRates();
$escRate.val(ADVANCED_CONFIG.motorPwmRate);
$escProtocol.change(function () {
ADVANCED_CONFIG.motorPwmProtocol = $(this).val();
buildMotorRates();
ADVANCED_CONFIG.motorPwmRate = escProtocols[ADVANCED_CONFIG.motorPwmProtocol].defaultRate;
$escRate.val(ADVANCED_CONFIG.motorPwmRate);
});
$escRate.change(function () {
ADVANCED_CONFIG.motorPwmRate = $(this).val();
});
$("#esc-protocols").show();
let $servoRate = $('#servo-rate');
for (i in servoRates) {
if (servoRates.hasOwnProperty(i)) {
$servoRate.append('<option value="' + i + '">' + servoRates[i] + '</option>');
}
}
/*
* If rate from FC is not on the list, add a new entry
*/
if ($servoRate.find('[value="' + ADVANCED_CONFIG.servoPwmRate + '"]').length == 0) {
$servoRate.append('<option value="' + ADVANCED_CONFIG.servoPwmRate + '">' + ADVANCED_CONFIG.servoPwmRate + 'Hz</option>');
}
$servoRate.val(ADVANCED_CONFIG.servoPwmRate);
$servoRate.change(function () {
ADVANCED_CONFIG.servoPwmRate = $(this).val();
});
$('#servo-rate-container').show();
/*
* Set all features ON/OFF
*/
let features = FC.getFeatures();
for (let i in features) {
if (features.hasOwnProperty(i)) {
let $html = $(".feature[data-bit='" +features[i].bit + "']");
if ($html.length) {
$html.prop('checked', bit_check(BF_CONFIG.features, features[i].bit));
}
}
}
$('input[type="checkbox"].feature').change(function () {
let element = $(this),
index = element.data('bit'),
state = element.is(':checked');
if (state) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, index);
} else {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, index);
}
});
GUI.simpleBind();
}
function update_arm_status() { function update_arm_status() {
self.armed = FC.isModeEnabled('ARM'); self.armed = FC.isModeEnabled('ARM');
} }
@ -230,6 +349,20 @@ TABS.motors.initialize = function (callback) {
$('a.update').click(function () { $('a.update').click(function () {
servos_update(); servos_update();
}); });
$('a.save').click(function () {
saveChainer.setExitPoint(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect($('.tab_motors a'));
});
});
});
servos_update();
});
} }
@ -245,11 +378,7 @@ TABS.motors.initialize = function (callback) {
$motorsEnableTestMode.prop('checked', false); $motorsEnableTestMode.prop('checked', false);
$motorsEnableTestMode.prop('disabled', true); $motorsEnableTestMode.prop('disabled', true);
if (FC.isNewMixer()) { update_model(MIXER_CONFIG.appliedMixerPreset);
update_model(MIXER_CONFIG.appliedMixerPreset);
} else {
update_model(BF_CONFIG.mixerConfiguration);
}
// Always start with default/empty sensor data array, clean slate all // Always start with default/empty sensor data array, clean slate all
initSensorData(); initSensorData();

View file

@ -583,7 +583,6 @@ OSD.constants = {
{ {
name: 'IMU_TEMPERATURE_MIN', name: 'IMU_TEMPERATURE_MIN',
field: 'imu_temp_alarm_min', field: 'imu_temp_alarm_min',
min_version: '2.1.0',
unit: '°C', unit: '°C',
step: 0.5, step: 0.5,
to_display: function(osd_data, value) { return value / 10 }, to_display: function(osd_data, value) { return value / 10 },
@ -594,7 +593,6 @@ OSD.constants = {
{ {
name: 'IMU_TEMPERATURE_MAX', name: 'IMU_TEMPERATURE_MAX',
field: 'imu_temp_alarm_max', field: 'imu_temp_alarm_max',
min_version: '2.1.0',
step: 0.5, step: 0.5,
unit: '°C', unit: '°C',
to_display: function(osd_data, value) { return value / 10 }, to_display: function(osd_data, value) { return value / 10 },
@ -605,7 +603,6 @@ OSD.constants = {
{ {
name: 'BARO_TEMPERATURE_MIN', name: 'BARO_TEMPERATURE_MIN',
field: 'baro_temp_alarm_min', field: 'baro_temp_alarm_min',
min_version: '2.1.0',
step: 0.5, step: 0.5,
unit: '°C', unit: '°C',
to_display: function(osd_data, value) { return value / 10 }, to_display: function(osd_data, value) { return value / 10 },
@ -616,7 +613,6 @@ OSD.constants = {
{ {
name: 'BARO_TEMPERATURE_MAX', name: 'BARO_TEMPERATURE_MAX',
field: 'baro_temp_alarm_max', field: 'baro_temp_alarm_max',
min_version: '2.1.0',
step: 0.5, step: 0.5,
unit: '°C', unit: '°C',
to_display: function(osd_data, value) { return value / 10 }, to_display: function(osd_data, value) { return value / 10 },
@ -644,7 +640,6 @@ OSD.constants = {
{ {
name: 'SAG_COMP_MAIN_BATT_VOLTAGE', name: 'SAG_COMP_MAIN_BATT_VOLTAGE',
id: 53, id: 53,
min_version: '2.0.0',
preview: osdMainBatteryPreview, preview: osdMainBatteryPreview,
}, },
{ {
@ -655,13 +650,11 @@ OSD.constants = {
{ {
name: 'SAG_COMP_MAIN_BATT_CELL_VOLTAGE', name: 'SAG_COMP_MAIN_BATT_CELL_VOLTAGE',
id: 54, id: 54,
min_version: '2.0.0',
preview: FONT.symbol(SYM.BATT) + FONT.embed_dot('4.18') + FONT.symbol(SYM.VOLT) preview: FONT.symbol(SYM.BATT) + FONT.embed_dot('4.18') + FONT.symbol(SYM.VOLT)
}, },
{ {
name: 'POWER_SUPPLY_IMPEDANCE', name: 'POWER_SUPPLY_IMPEDANCE',
id: 55, id: 55,
min_version: '2.0.0',
preview: ' 23' + FONT.symbol(SYM.MILLIOHM) preview: ' 23' + FONT.symbol(SYM.MILLIOHM)
}, },
{ {
@ -672,13 +665,11 @@ OSD.constants = {
{ {
name: 'REMAINING_FLIGHT_TIME', name: 'REMAINING_FLIGHT_TIME',
id: 48, id: 48,
min_version: '2.0.0',
preview: FONT.symbol(SYM.FLY_M) + '10:35' preview: FONT.symbol(SYM.FLY_M) + '10:35'
}, },
{ {
name: 'REMAINING_FLIGHT_DISTANCE', name: 'REMAINING_FLIGHT_DISTANCE',
id: 49, id: 49,
min_version: '2.0.0',
preview: function(osd_data) { preview: function(osd_data) {
if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) { if (semver.lt(CONFIG.flightControllerVersion, '2.2.0')) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
@ -779,7 +770,6 @@ OSD.constants = {
{ {
name: 'IMU_TEMPERATURE', name: 'IMU_TEMPERATURE',
id: 86, id: 86,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -792,7 +782,6 @@ OSD.constants = {
{ {
name: 'BARO_TEMPERATURE', name: 'BARO_TEMPERATURE',
id: 87, id: 87,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -805,7 +794,6 @@ OSD.constants = {
{ {
name: 'SENSOR1_TEMPERATURE', name: 'SENSOR1_TEMPERATURE',
id: 88, id: 88,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -818,7 +806,6 @@ OSD.constants = {
{ {
name: 'SENSOR2_TEMPERATURE', name: 'SENSOR2_TEMPERATURE',
id: 89, id: 89,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -831,7 +818,6 @@ OSD.constants = {
{ {
name: 'SENSOR3_TEMPERATURE', name: 'SENSOR3_TEMPERATURE',
id: 90, id: 90,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -844,7 +830,6 @@ OSD.constants = {
{ {
name: 'SENSOR4_TEMPERATURE', name: 'SENSOR4_TEMPERATURE',
id: 91, id: 91,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -857,7 +842,6 @@ OSD.constants = {
{ {
name: 'SENSOR5_TEMPERATURE', name: 'SENSOR5_TEMPERATURE',
id: 92, id: 92,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -870,7 +854,6 @@ OSD.constants = {
{ {
name: 'SENSOR6_TEMPERATURE', name: 'SENSOR6_TEMPERATURE',
id: 93, id: 93,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -883,7 +866,6 @@ OSD.constants = {
{ {
name: 'SENSOR7_TEMPERATURE', name: 'SENSOR7_TEMPERATURE',
id: 94, id: 94,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -896,7 +878,6 @@ OSD.constants = {
{ {
name: 'SENSOR8_TEMPERATURE', name: 'SENSOR8_TEMPERATURE',
id: 95, id: 95,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -1026,7 +1007,6 @@ OSD.constants = {
{ {
name: 'PITCH_ANGLE', name: 'PITCH_ANGLE',
id: 41, id: 41,
min_version: '2.0.0',
preview: function () { preview: function () {
return FONT.symbol(SYM.PITCH_UP) + FONT.embed_dot(' 1.5'); return FONT.symbol(SYM.PITCH_UP) + FONT.embed_dot(' 1.5');
}, },
@ -1034,7 +1014,6 @@ OSD.constants = {
{ {
name: 'ROLL_ANGLE', name: 'ROLL_ANGLE',
id: 42, id: 42,
min_version: '2.0.0',
preview: function () { preview: function () {
return FONT.symbol(SYM.ROLL_LEFT) + FONT.embed_dot('31.4'); return FONT.symbol(SYM.ROLL_LEFT) + FONT.embed_dot('31.4');
}, },
@ -1154,7 +1133,6 @@ OSD.constants = {
{ {
name: '3D_SPEED', name: '3D_SPEED',
id: 85, id: 85,
min_version: '2.1.0',
preview: function(osd_data) { preview: function(osd_data) {
// 3 chars // 3 chars
if (OSD.data.preferences.units === 0 || OSD.data.preferences.units === 2) { if (OSD.data.preferences.units === 0 || OSD.data.preferences.units === 2) {
@ -1182,7 +1160,6 @@ OSD.constants = {
{ {
name: 'PLUS_CODE', name: 'PLUS_CODE',
id: 97, id: 97,
min_version: '2.1.0',
preview: function() { preview: function() {
let digits = parseInt(Settings.getInputValue('osd_plus_code_digits')) + 1; let digits = parseInt(Settings.getInputValue('osd_plus_code_digits')) + 1;
console.log("DITIS", digits); console.log("DITIS", digits);
@ -1197,7 +1174,6 @@ OSD.constants = {
{ {
name: 'HOME_HEADING_ERROR', name: 'HOME_HEADING_ERROR',
id: 50, id: 50,
min_version: '2.0.0',
preview: FONT.symbol(SYM.HOME) + FONT.symbol(SYM.HEADING) + ' -10' + FONT.symbol(SYM.DEGREES) preview: FONT.symbol(SYM.HOME) + FONT.symbol(SYM.HEADING) + ' -10' + FONT.symbol(SYM.DEGREES)
}, },
{ {
@ -1247,7 +1223,6 @@ OSD.constants = {
{ {
name: 'WIND_SPEED_HORIZONTAL', name: 'WIND_SPEED_HORIZONTAL',
id: 46, id: 46,
min_version: '2.0.0',
preview: function(osd_data) { preview: function(osd_data) {
// 6 chars // 6 chars
var p = FONT.symbol(SYM.WIND_SPEED_HORIZONTAL) + FONT.symbol(SYM.DIRECTION + 1); var p = FONT.symbol(SYM.WIND_SPEED_HORIZONTAL) + FONT.symbol(SYM.DIRECTION + 1);
@ -1263,7 +1238,6 @@ OSD.constants = {
{ {
name: 'WIND_SPEED_VERTICAL', name: 'WIND_SPEED_VERTICAL',
id: 47, id: 47,
min_version: '2.0.0',
preview: function(osd_data) { preview: function(osd_data) {
// 6 chars // 6 chars
var p = FONT.symbol(SYM.WIND_SPEED_VERTICAL) + FONT.symbol(SYM.AH_DECORATION_UP); var p = FONT.symbol(SYM.WIND_SPEED_VERTICAL) + FONT.symbol(SYM.AH_DECORATION_UP);
@ -1279,13 +1253,11 @@ OSD.constants = {
{ {
name: 'CRUISE_HEADING_ERROR', name: 'CRUISE_HEADING_ERROR',
id: 51, id: 51,
min_version: '2.0.0',
preview: FONT.symbol(SYM.HEADING) + ' 5' + FONT.symbol(SYM.DEGREES) preview: FONT.symbol(SYM.HEADING) + ' 5' + FONT.symbol(SYM.DEGREES)
}, },
{ {
name: 'CRUISE_HEADING_ADJUSTMENT', name: 'CRUISE_HEADING_ADJUSTMENT',
id: 52, id: 52,
min_version: '2.0.0',
preview: FONT.symbol(SYM.HEADING) + ' -90' + FONT.symbol(SYM.DEGREES) preview: FONT.symbol(SYM.HEADING) + ' -90' + FONT.symbol(SYM.DEGREES)
}, },
] ]
@ -1296,25 +1268,21 @@ OSD.constants = {
{ {
name: 'MAP_NORTH', name: 'MAP_NORTH',
id: 43, id: 43,
min_version: '2.0.0',
positionable: false, positionable: false,
}, },
{ {
name: 'MAP_TAKEOFF', name: 'MAP_TAKEOFF',
id: 44, id: 44,
min_version: '2.0.0',
positionable: false, positionable: false,
}, },
{ {
name: 'RADAR', name: 'RADAR',
id: 45, id: 45,
min_version: '2.0.0',
positionable: false, positionable: false,
}, },
{ {
name: 'MAP_SCALE', name: 'MAP_SCALE',
id: 98, id: 98,
min_version: '2.1.1',
preview: function(osd_data) { preview: function(osd_data) {
var scale; var scale;
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
@ -1328,7 +1296,6 @@ OSD.constants = {
{ {
name: 'MAP_REFERENCE', name: 'MAP_REFERENCE',
id: 99, id: 99,
min_version: '2.1.1',
preview: FONT.symbol(SYM.DIRECTION) + '\nN', preview: FONT.symbol(SYM.DIRECTION) + '\nN',
}, },
], ],
@ -1341,11 +1308,7 @@ OSD.constants = {
id: 10, id: 10,
positionable: true, positionable: true,
preview: function(osd_data) { preview: function(osd_data) {
var preview = 'CH:F7'; return 'CH:F7:1';
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) {
preview += ':1';
}
return preview;
}, },
}, },
{ {
@ -1376,140 +1339,117 @@ OSD.constants = {
{ {
name: 'LEVEL_PIDS', name: 'LEVEL_PIDS',
id: 56, id: 56,
min_version: '2.0.0',
preview: 'LEV 20 15 80' preview: 'LEV 20 15 80'
}, },
{ {
name: 'POS_XY_PIDS', name: 'POS_XY_PIDS',
id: 57, id: 57,
min_version: '2.0.0',
preview: 'PXY 20 15 80' preview: 'PXY 20 15 80'
}, },
{ {
name: 'POS_Z_PIDS', name: 'POS_Z_PIDS',
id: 58, id: 58,
min_version: '2.0.0',
preview: 'PZ 20 15 80' preview: 'PZ 20 15 80'
}, },
{ {
name: 'VEL_XY_PIDS', name: 'VEL_XY_PIDS',
id: 59, id: 59,
min_version: '2.0.0',
preview: 'VXY 20 15 80' preview: 'VXY 20 15 80'
}, },
{ {
name: 'VEL_Z_PIDS', name: 'VEL_Z_PIDS',
id: 60, id: 60,
min_version: '2.0.0',
preview: 'VZ 20 15 80' preview: 'VZ 20 15 80'
}, },
{ {
name: 'HEADING_P', name: 'HEADING_P',
id: 61, id: 61,
min_version: '2.0.0',
preview: 'HP 20' preview: 'HP 20'
}, },
{ {
name: 'BOARD_ALIGNMENT_ROLL', name: 'BOARD_ALIGNMENT_ROLL',
id: 62, id: 62,
min_version: '2.0.0',
preview: 'AR 0' preview: 'AR 0'
}, },
{ {
name: 'BOARD_ALIGNMENT_PITCH', name: 'BOARD_ALIGNMENT_PITCH',
id: 63, id: 63,
min_version: '2.0.0',
preview: 'AP ' + FONT.embed_dot('1.0') preview: 'AP ' + FONT.embed_dot('1.0')
}, },
{ {
name: 'THROTTLE_EXPO', name: 'THROTTLE_EXPO',
id: 66, id: 66,
min_version: '2.0.0',
preview: 'TEX 0' preview: 'TEX 0'
}, },
{ {
name: 'STABILIZED_RC_EXPO', name: 'STABILIZED_RC_EXPO',
id: 64, id: 64,
min_version: '2.0.0',
preview: 'EXP 20' preview: 'EXP 20'
}, },
{ {
name: 'STABILIZED_RC_YAW_EXPO', name: 'STABILIZED_RC_YAW_EXPO',
id: 65, id: 65,
min_version: '2.0.0',
preview: 'YEX 20' preview: 'YEX 20'
}, },
{ {
name: 'STABILIZED_PITCH_RATE', name: 'STABILIZED_PITCH_RATE',
id: 67, id: 67,
min_version: '2.0.0',
preview: 'SPR 20' preview: 'SPR 20'
}, },
{ {
name: 'STABILIZED_ROLL_RATE', name: 'STABILIZED_ROLL_RATE',
id: 68, id: 68,
min_version: '2.0.0',
preview: 'SRR 20' preview: 'SRR 20'
}, },
{ {
name: 'STABILIZED_YAW_RATE', name: 'STABILIZED_YAW_RATE',
id: 69, id: 69,
min_version: '2.0.0',
preview: 'SYR 20' preview: 'SYR 20'
}, },
{ {
name: 'MANUAL_RC_EXPO', name: 'MANUAL_RC_EXPO',
id: 70, id: 70,
min_version: '2.0.0',
preview: 'MEX 20' preview: 'MEX 20'
}, },
{ {
name: 'MANUAL_RC_YAW_EXPO', name: 'MANUAL_RC_YAW_EXPO',
id: 71, id: 71,
min_version: '2.0.0',
preview: 'MYX 20' preview: 'MYX 20'
}, },
{ {
name: 'MANUAL_PITCH_RATE', name: 'MANUAL_PITCH_RATE',
id: 72, id: 72,
min_version: '2.0.0',
preview: 'MPR 20' preview: 'MPR 20'
}, },
{ {
name: 'MANUAL_ROLL_RATE', name: 'MANUAL_ROLL_RATE',
id: 73, id: 73,
min_version: '2.0.0',
preview: 'MRR 20' preview: 'MRR 20'
}, },
{ {
name: 'MANUAL_YAW_RATE', name: 'MANUAL_YAW_RATE',
id: 74, id: 74,
min_version: '2.0.0',
preview: 'MYR 20' preview: 'MYR 20'
}, },
{ {
name: 'NAV_FW_CRUISE_THROTTLE', name: 'NAV_FW_CRUISE_THROTTLE',
id: 75, id: 75,
min_version: '2.0.0',
preview: 'CRS 1500' preview: 'CRS 1500'
}, },
{ {
name: 'NAV_FW_PITCH_TO_THROTTLE', name: 'NAV_FW_PITCH_TO_THROTTLE',
id: 76, id: 76,
min_version: '2.0.0',
preview: 'P2T 10' preview: 'P2T 10'
}, },
{ {
name: 'FW_MIN_THROTTLE_DOWN_PITCH_ANGLE', name: 'FW_MIN_THROTTLE_DOWN_PITCH_ANGLE',
id: 77, id: 77,
min_version: '2.0.0',
preview: '0TP ' + FONT.embed_dot('4.5') preview: '0TP ' + FONT.embed_dot('4.5')
}, },
] ]
}, },
{ {
name: 'osdGroupPIDOutputs', name: 'osdGroupPIDOutputs',
min_version: '2.0.0',
items: [ items: [
{ {
name: 'FW_ALT_PID_OUTPUTS', name: 'FW_ALT_PID_OUTPUTS',
@ -1590,10 +1530,6 @@ OSD.get_item_preview = function(item) {
return preview; return preview;
} }
OSD.use_layouts_api = function() {
return semver.gte(CONFIG.flightControllerVersion, '2.0.0');
};
OSD.reload = function(callback) { OSD.reload = function(callback) {
OSD.initData(); OSD.initData();
var done = function() { var done = function() {
@ -1602,39 +1538,32 @@ OSD.reload = function(callback) {
callback(); callback();
} }
}; };
if (OSD.use_layouts_api()) { MSP.promise(MSPCodes.MSP2_INAV_OSD_LAYOUTS).then(function (resp) {
MSP.promise(MSPCodes.MSP2_INAV_OSD_LAYOUTS).then(function (resp) {
OSD.msp.decodeLayoutCounts(resp); OSD.msp.decodeLayoutCounts(resp);
// Get data for all layouts // Get data for all layouts
var ids = Array.apply(null, {length: OSD.data.layout_count}).map(Number.call, Number); var ids = Array.apply(null, {length: OSD.data.layout_count}).map(Number.call, Number);
var layouts = Promise.mapSeries(ids, function (layoutIndex, ii) { var layouts = Promise.mapSeries(ids, function (layoutIndex, ii) {
var data = []; var data = [];
data.push8(layoutIndex); data.push8(layoutIndex);
return MSP.promise(MSPCodes.MSP2_INAV_OSD_LAYOUTS, data).then(function (resp) { return MSP.promise(MSPCodes.MSP2_INAV_OSD_LAYOUTS, data).then(function (resp) {
OSD.msp.decodeLayout(layoutIndex, resp); OSD.msp.decodeLayout(layoutIndex, resp);
});
}); });
layouts.then(function () { });
OSD.updateSelectedLayout(OSD.data.selected_layout || 0); layouts.then(function () {
OSD.updateSelectedLayout(OSD.data.selected_layout || 0);
MSP.promise(MSPCodes.MSP2_INAV_OSD_ALARMS).then(function (resp) { MSP.promise(MSPCodes.MSP2_INAV_OSD_ALARMS).then(function (resp) {
OSD.msp.decodeAlarms(resp); OSD.msp.decodeAlarms(resp);
MSP.promise(MSPCodes.MSP2_INAV_OSD_PREFERENCES).then(function (resp) { MSP.promise(MSPCodes.MSP2_INAV_OSD_PREFERENCES).then(function (resp) {
OSD.data.supported = true; OSD.data.supported = true;
OSD.msp.decodePreferences(resp); OSD.msp.decodePreferences(resp);
done(); done();
});
}); });
}); });
}); });
} else { });
MSP.promise(MSPCodes.MSP_OSD_CONFIG).then(function (data) {
OSD.msp.decode(data);
done();
});
}
}; };
OSD.updateSelectedLayout = function(new_layout) { OSD.updateSelectedLayout = function(new_layout) {
@ -1656,33 +1585,21 @@ OSD.updateDisplaySize = function () {
}; };
OSD.saveAlarms = function(callback) { OSD.saveAlarms = function(callback) {
// Before the layouts API was introduced, config and alarms were saved let data = OSD.msp.encodeAlarms();
// with the same MSP cmd.
if (!OSD.use_layouts_api()) {
return OSD.saveConfig(callback);
}
var data = OSD.msp.encodeAlarms();
return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_ALARMS, data).then(callback); return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_ALARMS, data).then(callback);
} }
OSD.saveConfig = function(callback) { OSD.saveConfig = function(callback) {
if (OSD.use_layouts_api()) { return OSD.saveAlarms(function () {
return OSD.saveAlarms(function () { var data = OSD.msp.encodePreferences();
var data = OSD.msp.encodePreferences(); return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_PREFERENCES, data).then(callback);
return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_PREFERENCES, data).then(callback); });
});
}
return MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, OSD.msp.encodeOther()).then(callback);
}; };
OSD.saveItem = function(item, callback) { OSD.saveItem = function(item, callback) {
var pos = OSD.data.items[item.id]; let pos = OSD.data.items[item.id];
if (OSD.use_layouts_api()) { let data = OSD.msp.encodeLayoutItem(OSD.data.selected_layout, item, pos);
var data = OSD.msp.encodeLayoutItem(OSD.data.selected_layout, item, pos); return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_LAYOUT_ITEM, data).then(callback);
return MSP.promise(MSPCodes.MSP2_INAV_OSD_SET_LAYOUT_ITEM, data).then(callback);
}
var data = OSD.msp.encodeItem(item.id, pos);
return MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, data).then(callback);
}; };
//noinspection JSUnusedLocalSymbols //noinspection JSUnusedLocalSymbols
@ -1727,12 +1644,10 @@ OSD.msp = {
result.push16(OSD.data.alarms.gforce_axis_max); result.push16(OSD.data.alarms.gforce_axis_max);
result.push8(OSD.data.alarms.current); result.push8(OSD.data.alarms.current);
} }
if (semver.gte(CONFIG.flightControllerVersion, '2.1.0')) { result.push16(OSD.data.alarms.imu_temp_alarm_min);
result.push16(OSD.data.alarms.imu_temp_alarm_min); result.push16(OSD.data.alarms.imu_temp_alarm_max);
result.push16(OSD.data.alarms.imu_temp_alarm_max); result.push16(OSD.data.alarms.baro_temp_alarm_min);
result.push16(OSD.data.alarms.baro_temp_alarm_min); result.push16(OSD.data.alarms.baro_temp_alarm_max);
result.push16(OSD.data.alarms.baro_temp_alarm_max);
}
return result; return result;
}, },
@ -1750,12 +1665,10 @@ OSD.msp = {
OSD.data.alarms.gforce_axis_max = alarms.read16(); OSD.data.alarms.gforce_axis_max = alarms.read16();
OSD.data.alarms.current = alarms.readU8(); OSD.data.alarms.current = alarms.readU8();
} }
if (semver.gte(CONFIG.flightControllerVersion, '2.1.0')) { OSD.data.alarms.imu_temp_alarm_min = alarms.read16();
OSD.data.alarms.imu_temp_alarm_min = alarms.read16(); OSD.data.alarms.imu_temp_alarm_max = alarms.read16();
OSD.data.alarms.imu_temp_alarm_max = alarms.read16(); OSD.data.alarms.baro_temp_alarm_min = alarms.read16();
OSD.data.alarms.baro_temp_alarm_min = alarms.read16(); OSD.data.alarms.baro_temp_alarm_max = alarms.read16();
OSD.data.alarms.baro_temp_alarm_max = alarms.read16();
}
}, },
encodePreferences: function() { encodePreferences: function() {
@ -2208,24 +2121,6 @@ OSD.GUI.updateMapPreview = function(mapCenter, name, directionSymbol, centerSymb
if ($('input[name="' + name + '"]').prop('checked')) { if ($('input[name="' + name + '"]').prop('checked')) {
var mapInitialX = OSD.data.display_size.x - 2; var mapInitialX = OSD.data.display_size.x - 2;
OSD.GUI.checkAndProcessSymbolPosition(mapCenter, centerSymbol); OSD.GUI.checkAndProcessSymbolPosition(mapCenter, centerSymbol);
if (semver.lt(CONFIG.flightControllerVersion, '2.1.1')) {
// INAV pre 2.1.1 had hardcoded map reference and scale
if (directionSymbol) {
OSD.GUI.checkAndProcessSymbolPosition(mapInitialX, SYM.DIRECTION);
OSD.GUI.checkAndProcessSymbolPosition(mapInitialX + OSD.data.display_size.x, directionSymbol.charCodeAt(0));
}
var scalePos = 1 + OSD.data.display_size.x * (OSD.data.display_size.y - 2);
OSD.GUI.checkAndProcessSymbolPosition(scalePos, SYM.SCALE);
var scale;
if (OSD.data.preferences.units === 0) {
scale = FONT.embed_dot("0.10") + FONT.symbol(SYM.MI);
} else {
scale = "100" + FONT.symbol(SYM.M);
}
for (var ii = 0; ii < scale.length; ii++) {
OSD.GUI.checkAndProcessSymbolPosition(scalePos + ii + 1, scale.charCodeAt(ii));
}
}
} }
}; };

View file

@ -347,7 +347,7 @@
<div class="helpicon cf_tip" data-i18n_title="gyro_lpf_type_help"></div> <div class="helpicon cf_tip" data-i18n_title="gyro_lpf_type_help"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v2_1"> <tr>
<th data-i18n="gyroStage2LpfCutoffFrequency"></th> <th data-i18n="gyroStage2LpfCutoffFrequency"></th>
<td> <td>
<input type="number" id="gyroStage2LpfCutoffFrequency" data-simple-bind="FILTER_CONFIG.gyroStage2LowpassHz" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" id="gyroStage2LpfCutoffFrequency" data-simple-bind="FILTER_CONFIG.gyroStage2LowpassHz" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
@ -456,14 +456,14 @@
<div class="helpicon cf_tip" data-i18n_title="dtermNotchCutoffHelp"></div> <div class="helpicon cf_tip" data-i18n_title="dtermNotchCutoffHelp"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v2_1"> <tr>
<th data-i18n="accNotchHz"></th> <th data-i18n="accNotchHz"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.accNotchHz" id="accNotchHz" class="rate-tpa_input" step="1" min="0" max="255" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.accNotchHz" id="accNotchHz" class="rate-tpa_input" step="1" min="0" max="255" /> Hz
<div class="helpicon cf_tip" data-i18n_title="accNotchHzHelp"></div> <div class="helpicon cf_tip" data-i18n_title="accNotchHzHelp"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v2_1"> <tr>
<th data-i18n="accNotchCutoff"></th> <th data-i18n="accNotchCutoff"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.accNotchCutoff" id="gyroNotchCutoff2" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.accNotchCutoff" id="gyroNotchCutoff2" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
@ -492,20 +492,6 @@
<div class="helpicon cf_tip" data-i18n_title="yawPLimitHelp"></div> <div class="helpicon cf_tip" data-i18n_title="yawPLimitHelp"></div>
</td> </td>
</tr> </tr>
<tr class="deprecated-v2_0">
<th data-i18n="rollPitchItermIgnoreRate"></th>
<td >
<input type="number" id="rollPitchItermIgnoreRate" class="rate-tpa_input" step="5" min="15" max="1000" />
<div class="helpicon cf_tip" data-i18n_title="rollPitchItermIgnoreRateHelp"></div>
</td>
</tr>
<tr class="deprecated-v2_0">
<th data-i18n="yawItermIgnoreRate"></th>
<td >
<input type="number" id="yawItermIgnoreRate" class="rate-tpa_input" step="5" min="15" max="1000" />
<div class="helpicon cf_tip" data-i18n_title="yawItermIgnoreRateHelp"></div>
</td>
</tr>
</table> </table>
</div> </div>
<div class="cf_column half"> <div class="cf_column half">

View file

@ -135,8 +135,6 @@ TABS.pid_tuning.initialize = function (callback) {
$accSoftLpfHz = $('#accSoftLpfHz'), $accSoftLpfHz = $('#accSoftLpfHz'),
$dtermLpfHz = $('#dtermLpfHz'), $dtermLpfHz = $('#dtermLpfHz'),
$yawLpfHz = $('#yawLpfHz'), $yawLpfHz = $('#yawLpfHz'),
$rollPitchItermIgnoreRate = $('#rollPitchItermIgnoreRate'),
$yawItermIgnoreRate = $('#yawItermIgnoreRate'),
$axisAccelerationLimitRollPitch = $('#axisAccelerationLimitRollPitch'), $axisAccelerationLimitRollPitch = $('#axisAccelerationLimitRollPitch'),
$axisAccelerationLimitYaw = $('#axisAccelerationLimitYaw'); $axisAccelerationLimitYaw = $('#axisAccelerationLimitYaw');
@ -147,8 +145,6 @@ TABS.pid_tuning.initialize = function (callback) {
$accSoftLpfHz.val(INAV_PID_CONFIG.accSoftLpfHz); $accSoftLpfHz.val(INAV_PID_CONFIG.accSoftLpfHz);
$dtermLpfHz.val(FILTER_CONFIG.dtermLpfHz); $dtermLpfHz.val(FILTER_CONFIG.dtermLpfHz);
$yawLpfHz.val(FILTER_CONFIG.yawLpfHz); $yawLpfHz.val(FILTER_CONFIG.yawLpfHz);
$rollPitchItermIgnoreRate.val(PID_ADVANCED.rollPitchItermIgnoreRate);
$yawItermIgnoreRate.val(PID_ADVANCED.yawItermIgnoreRate);
$axisAccelerationLimitRollPitch.val(PID_ADVANCED.axisAccelerationLimitRollPitch * 10); $axisAccelerationLimitRollPitch.val(PID_ADVANCED.axisAccelerationLimitRollPitch * 10);
$axisAccelerationLimitYaw.val(PID_ADVANCED.axisAccelerationLimitYaw * 10); $axisAccelerationLimitYaw.val(PID_ADVANCED.axisAccelerationLimitYaw * 10);
@ -180,14 +176,6 @@ TABS.pid_tuning.initialize = function (callback) {
FILTER_CONFIG.yawLpfHz = parseInt($yawLpfHz.val(), 10); FILTER_CONFIG.yawLpfHz = parseInt($yawLpfHz.val(), 10);
}); });
$rollPitchItermIgnoreRate.change(function () {
PID_ADVANCED.rollPitchItermIgnoreRate = parseInt($rollPitchItermIgnoreRate.val(), 10);
});
$yawItermIgnoreRate.change(function () {
PID_ADVANCED.yawItermIgnoreRate = parseInt($yawItermIgnoreRate.val(), 10);
});
$axisAccelerationLimitRollPitch.change(function () { $axisAccelerationLimitRollPitch.change(function () {
PID_ADVANCED.axisAccelerationLimitRollPitch = Math.round(parseInt($axisAccelerationLimitRollPitch.val(), 10) / 10); PID_ADVANCED.axisAccelerationLimitRollPitch = Math.round(parseInt($axisAccelerationLimitRollPitch.val(), 10) / 10);
}); });
@ -196,18 +184,6 @@ TABS.pid_tuning.initialize = function (callback) {
PID_ADVANCED.axisAccelerationLimitYaw = Math.round(parseInt($axisAccelerationLimitYaw.val(), 10) / 10); PID_ADVANCED.axisAccelerationLimitYaw = Math.round(parseInt($axisAccelerationLimitYaw.val(), 10) / 10);
}); });
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
$('.deprecated-v2_0').hide();
} else {
$('.deprecated-v2_0').show();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) {
$('.requires-v2_1').show();
} else {
$('.requires-v2_1').hide();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) {
$('.requires-v2_2').show(); $('.requires-v2_2').show();
} else { } else {

View file

@ -34,13 +34,11 @@ TABS.ports.initialize = function (callback) {
maxPorts: 1 maxPorts: 1
}); });
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { functionRules.push({
functionRules.push({ name: 'RANGEFINDER',
name: 'RANGEFINDER', groups: ['sensors'],
groups: ['sensors'], maxPorts: 1 }
maxPorts: 1 } );
);
}
if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.2.0")) {
functionRules.push({ functionRules.push({
@ -155,11 +153,7 @@ TABS.ports.initialize = function (callback) {
load_configuration_from_fc(); load_configuration_from_fc();
function load_configuration_from_fc() { function load_configuration_from_fc() {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { MSP.send_message(MSPCodes.MSP2_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
MSP.send_message(MSPCodes.MSP2_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
} else {
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
}
function on_configuration_loaded_handler() { function on_configuration_loaded_handler() {
$('#content').load("./tabs/ports.html", on_tab_loaded_handler); $('#content').load("./tabs/ports.html", on_tab_loaded_handler);
@ -332,11 +326,8 @@ TABS.ports.initialize = function (callback) {
SERIAL_CONFIG.ports.push(serialPort); SERIAL_CONFIG.ports.push(serialPort);
}); });
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { MSP.send_message(MSPCodes.MSP2_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP2_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
MSP.send_message(MSPCodes.MSP2_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP2_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
} else {
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
}
function save_to_eeprom() { function save_to_eeprom() {
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, on_saved_handler); MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, on_saved_handler);
} }

View file

@ -72,14 +72,6 @@ TABS.receiver.initialize = function (callback) {
// translate to user-selected language // translate to user-selected language
localize(); localize();
if (semver.lt(CONFIG.flightControllerVersion, '1.9.1')) {
rcmap_options = $('select[name="rcmap_helper"] option');
for (i = 0; i < rcmap_options.length; ++i) {
option = rcmap_options[i];
option.setAttribute("value", option.getAttribute("value") + "5678");
}
}
// fill in data from RC_tuning // fill in data from RC_tuning
$('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2)); $('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2));
$('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2)); $('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2));

View file

@ -18,7 +18,7 @@
<label><input type="checkbox" name="gyro_on" class="first" />Gyroscope</label> <label><input <label><input type="checkbox" name="gyro_on" class="first" />Gyroscope</label> <label><input
type="checkbox" name="accel_on" />Accelerometer</label> <label><input type="checkbox" type="checkbox" name="accel_on" />Accelerometer</label> <label><input type="checkbox"
name="mag_on" />Magnetometer</label> <label><input type="checkbox" name="baro_on" />Barometer</label> <label><input name="mag_on" />Magnetometer</label> <label><input type="checkbox" name="baro_on" />Barometer</label> <label><input
type="checkbox" name="sonar_on" />Sonar</label> <label><input type="checkbox" name="airspeed_on" />Air speed</label> <label class="requires-v2_1_0"><input type="checkbox" name="sonar_on" />Sonar</label> <label><input type="checkbox" name="airspeed_on" />Air speed</label> <label><input
type="checkbox" name="temperature_on" />Temperatures</label><label><input type="checkbox" name="debug_on" />Debug</label> type="checkbox" name="temperature_on" />Temperatures</label><label><input type="checkbox" name="debug_on" />Debug</label>
<a class="debug-trace" href="javascript:void(0);">Open Debug Trace</a> <a class="debug-trace" href="javascript:void(0);">Open Debug Trace</a>

View file

@ -211,15 +211,12 @@ TABS.sensors.initialize = function (callback) {
checkboxes.eq(4).prop('disabled', true); checkboxes.eq(4).prop('disabled', true);
} }
if (semver.lt(CONFIG.flightControllerVersion, "1.9.1") || (!bit_check(CONFIG.activeSensors, 6))) { // airspeed if (!bit_check(CONFIG.activeSensors, 6)) { // airspeed
checkboxes.eq(5).prop('disabled', true); checkboxes.eq(5).prop('disabled', true);
} }
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { if (!bit_check(CONFIG.activeSensors, 7)) {
if (!bit_check(CONFIG.activeSensors, 7)) checkboxes.eq(6).prop('disabled', true);
checkboxes.eq(6).prop('disabled', true);
} else {
$(".requires-v2_1_0").hide();
} }
$('.tab-sensors .info .checkboxes input').change(function () { $('.tab-sensors .info .checkboxes input').change(function () {
@ -486,7 +483,7 @@ TABS.sensors.initialize = function (callback) {
}, rates.airspeed, true); }, rates.airspeed, true);
} }
if (checkboxes[6] && (semver.gte(CONFIG.flightControllerVersion, "2.1.0"))) { if (checkboxes[6]) {
helper.interval.add('temperature_pull', function temperature_data_pull() { helper.interval.add('temperature_pull', function temperature_data_pull() {
/* /*
@ -512,11 +509,7 @@ TABS.sensors.initialize = function (callback) {
return; return;
} }
if (semver.gte(CONFIG.flightControllerVersion, '2.1.0')) { MSP.send_message(MSPCodes.MSP2_INAV_DEBUG, false, false, update_debug_graphs);
MSP.send_message(MSPCodes.MSP2_INAV_DEBUG, false, false, update_debug_graphs);
} else {
MSP.send_message(MSPCodes.MSP_DEBUG, false, false, update_debug_graphs);
}
}, rates.debug, true); }, rates.debug, true);
} }

View file

@ -235,15 +235,11 @@ TABS.setup.initialize3D = function () {
// load the model including materials // load the model including materials
if (useWebGlRenderer) { if (useWebGlRenderer) {
if (FC.isNewMixer()) { if (MIXER_CONFIG.appliedMixerPreset === -1) {
if (MIXER_CONFIG.appliedMixerPreset === -1) { model_file = 'custom';
model_file = 'custom'; GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("mixerNotConfigured") + "</strong></span>");
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("mixerNotConfigured") + "</strong></span>");
} else {
model_file = helper.mixer.getById(MIXER_CONFIG.appliedMixerPreset).model;
}
} else { } else {
model_file = helper.mixer.getById(BF_CONFIG.mixerConfiguration).model; model_file = helper.mixer.getById(MIXER_CONFIG.appliedMixerPreset).model;
} }
} else { } else {
model_file = 'fallback' model_file = 'fallback'