Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/iNavFlight/inav-configurator.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
path: root/js
diff options
context:
space:
mode:
authorDarren Lines <darren@darrenlines.uk>2022-03-01 23:06:11 +0300
committerDarren Lines <darren@darrenlines.uk>2022-03-01 23:06:11 +0300
commitc07b81ed45ce07eb5092c6830de618cf047ee5f7 (patch)
treee94d43828933513190f81dc946ed947cc1ed797c /js
parentea20a04362baa203cb40979291279c78fd583403 (diff)
parent2d856f6edb707172df60b64534cf80cb5f2cf501 (diff)
Merge branch 'master' into MrD-Highlight-parameters-that-change-with-profiles-or-battery-profiles
Diffstat (limited to 'js')
-rw-r--r--js/fc.js295
-rw-r--r--js/gui.js1
-rw-r--r--js/msp.js2
-rw-r--r--js/msp/MSPCodes.js4
-rw-r--r--js/msp/MSPHelper.js147
-rwxr-xr-xjs/serial_backend.js10
-rw-r--r--js/settings.js2
-rw-r--r--js/tasks.js25
8 files changed, 108 insertions, 378 deletions
diff --git a/js/fc.js b/js/fc.js
index e81cdcf3..62800900 100644
--- a/js/fc.js
+++ b/js/fc.js
@@ -38,7 +38,6 @@ var CONFIG,
DATAFLASH,
SDCARD,
BLACKBOX,
- TRANSPONDER,
RC_deadband,
SENSOR_ALIGNMENT,
RX_CONFIG,
@@ -77,14 +76,11 @@ var FC = {
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
},
isRpyFfComponentUsed: function () {
- return (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE || MIXER_CONFIG.platformType == PLATFORM_ROVER || MIXER_CONFIG.platformType == PLATFORM_BOAT) || ((MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) && semver.gte(CONFIG.flightControllerVersion, "2.6.0"));
+ return true; // Currently all planes have roll, pitch and yaw FF
},
isRpyDComponentUsed: function () {
return true; // Currently all platforms use D term
},
- isCdComponentUsed: function () {
- return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
- },
resetState: function () {
SENSOR_STATUS = {
isHardwareHealthy: 0,
@@ -252,23 +248,6 @@ var FC = {
packetCount: 0
};
- /* MISSION_PLANNER = {
- maxWaypoints: 0,
- isValidMission: 0,
- countBusyPoints: 0,
- bufferPoint: {
- number: 0,
- action: 0,
- lat: 0,
- lon: 0,
- alt: 0,
- endMission: 0,
- p1: 0,
- p2: 0,
- p3: 0
- }
- }; */
-
MISSION_PLANNER = new WaypointCollection();
ANALOG = {
@@ -479,11 +458,6 @@ var FC = {
blackboxRateDenom: 1
};
- TRANSPONDER = {
- supported: false,
- data: []
- };
-
RC_deadband = {
deadband: 0,
yaw_deadband: 0,
@@ -601,10 +575,6 @@ var FC = {
{bit: 31, group: 'other', name: "FW_AUTOTRIM", haveTip: true, showNameInTip: true}
];
- if (semver.gte(CONFIG.flightControllerVersion, "2.4.0") && semver.lt(CONFIG.flightControllerVersion, "2.5.0")) {
- features.push({bit: 5, group: 'other', name: 'DYNAMIC_FILTERS', haveTip: true, showNameInTip: true});
- }
-
return features.reverse();
},
isFeatureEnabled: function (featureName, features) {
@@ -664,168 +634,69 @@ var FC = {
];
},
getEscProtocols: function () {
-
- if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
- return {
- 0: {
- name: "STANDARD",
- message: null,
- defaultRate: 400,
- rates: {
- 50: "50Hz",
- 400: "400Hz"
- }
- },
- 1: {
- name: "ONESHOT125",
- message: null,
- defaultRate: 1000,
- rates: {
- 1000: "1kHz",
- 2000: "2kHz"
- }
- },
- 2: {
- name: "MULTISHOT",
- message: null,
- defaultRate: 2000,
- rates: {
- 1000: "1kHz",
- 2000: "2kHz"
- }
- },
- 3: {
- name: "BRUSHED",
- message: null,
- defaultRate: 8000,
- rates: {
- 8000: "8kHz",
- 16000: "16kHz",
- 32000: "32kHz"
- }
- },
- 4: {
- name: "DSHOT150",
- message: null,
- defaultRate: 4000,
- rates: {
- 4000: "4kHz"
- }
- },
- 5: {
- name: "DSHOT300",
- message: null,
- defaultRate: 8000,
- rates: {
- 8000: "8kHz"
- }
- },
- 6: {
- name: "DSHOT600",
- message: null,
- defaultRate: 16000,
- rates: {
- 16000: "16kHz"
- }
+ return {
+ 0: {
+ name: "STANDARD",
+ message: null,
+ defaultRate: 400,
+ rates: {
+ 50: "50Hz",
+ 400: "400Hz"
}
- };
- } else {
- return {
- 0: {
- name: "STANDARD",
- message: null,
- defaultRate: 400,
- rates: {
- 50: "50Hz",
- 400: "400Hz"
- }
- },
- 1: {
- name: "ONESHOT125",
- message: null,
- defaultRate: 1000,
- rates: {
- 400: "400Hz",
- 1000: "1kHz",
- 2000: "2kHz"
- }
- },
- 2: {
- name: "ONESHOT42",
- message: null,
- defaultRate: 2000,
- rates: {
- 400: "400Hz",
- 1000: "1kHz",
- 2000: "2kHz",
- 4000: "4kHz",
- 8000: "8kHz"
- }
- },
- 3: {
- name: "MULTISHOT",
- message: null,
- defaultRate: 2000,
- rates: {
- 400: "400Hz",
- 1000: "1kHz",
- 2000: "2kHz",
- 4000: "4kHz",
- 8000: "8kHz"
- }
- },
- 4: {
- name: "BRUSHED",
- message: null,
- defaultRate: 8000,
- rates: {
- 8000: "8kHz",
- 16000: "16kHz",
- 32000: "32kHz"
- }
- },
- 5: {
- name: "DSHOT150",
- message: null,
- defaultRate: 4000,
- rates: {
- 4000: "4kHz"
- }
- },
- 6: {
- name: "DSHOT300",
- message: null,
- defaultRate: 8000,
- rates: {
- 8000: "8kHz"
- }
- },
- 7: {
- name: "DSHOT600",
- message: null,
- defaultRate: 16000,
- rates: {
- 16000: "16kHz"
- }
- },
- 8: {
- name: "DSHOT1200",
- message: "escProtocolNotAdvised",
- defaultRate: 16000,
- rates: {
- 16000: "16kHz"
- }
- },
- 9: {
- name: "SERIALSHOT",
- message: "escProtocolExperimental",
- defaultRate: 4000,
- rates: {
- 4000: "4kHz"
- }
+ },
+ 1: {
+ name: "ONESHOT125",
+ message: null,
+ defaultRate: 1000,
+ rates: {
+ 1000: "1kHz",
+ 2000: "2kHz"
}
- };
- }
+ },
+ 2: {
+ name: "MULTISHOT",
+ message: null,
+ defaultRate: 2000,
+ rates: {
+ 1000: "1kHz",
+ 2000: "2kHz"
+ }
+ },
+ 3: {
+ name: "BRUSHED",
+ message: null,
+ defaultRate: 8000,
+ rates: {
+ 8000: "8kHz",
+ 16000: "16kHz",
+ 32000: "32kHz"
+ }
+ },
+ 4: {
+ name: "DSHOT150",
+ message: null,
+ defaultRate: 4000,
+ rates: {
+ 4000: "4kHz"
+ }
+ },
+ 5: {
+ name: "DSHOT300",
+ message: null,
+ defaultRate: 8000,
+ rates: {
+ 8000: "8kHz"
+ }
+ },
+ 6: {
+ name: "DSHOT600",
+ message: null,
+ defaultRate: 16000,
+ rates: {
+ 16000: "16kHz"
+ }
+ }
+ };
},
getServoRates: function () {
return {
@@ -866,37 +737,6 @@ var FC = {
getOsdDisabledFields: function () {
return [];
},
- getAccelerometerNames: function () {
- return [ "NONE", "AUTO", "MPU6050", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
- },
- getBarometerNames: function () {
- if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
- return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "MSP", "FAKE"];
- } else {
- return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"];
- }
- },
- getPitotNames: function () {
- if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
- return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"];
- } else {
- return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
- }
- },
- getRangefinderNames: function () {
- if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
- return [ "NONE", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "Benewake TFmini", "VL53L1X", "US42"];
- } else {
- return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
- }
- },
- getOpticalFlowNames: function () {
- if (semver.gte(CONFIG.flightControllerVersion, "2.7.0")) {
- return [ "NONE", "CXOF", "MSP", "FAKE" ];
- } else {
- return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
- }
- },
getArmingFlags: function () {
return {
0: "OK_TO_ARM",
@@ -933,7 +773,7 @@ var FC = {
]
},
getPidNames: function () {
- let list = [
+ return [
'Roll',
'Pitch',
'Yaw',
@@ -943,14 +783,9 @@ var FC = {
'Surface',
'Level',
'Heading Hold',
- 'Velocity Z'
+ 'Velocity Z',
+ 'Nav Heading'
];
-
- if (semver.gte(CONFIG.flightControllerVersion, '2.5.0')) {
- list.push("Nav Heading")
- }
-
- return list;
},
getRthAltControlMode: function () {
return ["Current", "Extra", "Fixed", "Max", "At least", "At least, linear descent"];
diff --git a/js/gui.js b/js/gui.js
index 46fe85db..4765e6ba 100644
--- a/js/gui.js
+++ b/js/gui.js
@@ -18,7 +18,6 @@ var GUI_control = function () {
];
this.defaultAllowedTabsWhenConnected = [
'failsafe',
- 'transponder',
'adjustments',
'auxiliary',
'cli',
diff --git a/js/msp.js b/js/msp.js
index e98cd4fd..727f9fa0 100644
--- a/js/msp.js
+++ b/js/msp.js
@@ -72,7 +72,7 @@ var MSP = {
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
- ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
+ ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
last_received_timestamp: null,
diff --git a/js/msp/MSPCodes.js b/js/msp/MSPCodes.js
index 6e39f7f0..856a6ade 100644
--- a/js/msp/MSPCodes.js
+++ b/js/msp/MSPCodes.js
@@ -64,8 +64,6 @@ var MSPCodes = {
MSP_SDCARD_SUMMARY: 79,
MSP_BLACKBOX_CONFIG: 80,
MSP_SET_BLACKBOX_CONFIG: 81,
- MSP_TRANSPONDER_CONFIG: 82,
- MSP_SET_TRANSPONDER_CONFIG: 83,
MSP_OSD_CONFIG: 84,
MSP_SET_OSD_CONFIG: 85,
MSP_OSD_CHAR_READ: 86,
@@ -107,7 +105,7 @@ var MSPCodes = {
MSP_RC_DEADBAND: 125,
MSP_SENSOR_ALIGNMENT: 126,
MSP_LED_STRIP_MODECOLOR:127,
- MSP_STATUS_EX: 150,
+ MSP_STATUS_EX: 150, // Deprecated, do not use.
MSP_SENSOR_STATUS: 151,
MSP_SET_RAW_RC: 200,
diff --git a/js/msp/MSPHelper.js b/js/msp/MSPHelper.js
index 976d39f4..f8f1c324 100644
--- a/js/msp/MSPHelper.js
+++ b/js/msp/MSPHelper.js
@@ -68,27 +68,6 @@ var mspHelper = (function (gui) {
colorCount,
color;
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
- case MSPCodes.MSP_STATUS:
- console.log('Using deprecated msp command: MSP_STATUS');
- CONFIG.cycleTime = data.getUint16(0, true);
- CONFIG.i2cError = data.getUint16(2, true);
- CONFIG.activeSensors = data.getUint16(4, true);
- CONFIG.mode = data.getUint32(6, true);
- CONFIG.profile = data.getUint8(10);
- gui.updateProfileChange();
- gui.updateStatusBar();
- break;
- case MSPCodes.MSP_STATUS_EX:
- CONFIG.cycleTime = data.getUint16(0, true);
- CONFIG.i2cError = data.getUint16(2, true);
- CONFIG.activeSensors = data.getUint16(4, true);
- CONFIG.profile = data.getUint8(10);
- CONFIG.cpuload = data.getUint16(11, true);
- CONFIG.armingFlags = data.getUint16(13, true);
- gui.updateStatusBar();
- gui.updateProfileChange();
- break;
-
case MSPCodes.MSPV2_INAV_STATUS:
CONFIG.cycleTime = data.getUint16(offset, true);
offset += 2;
@@ -125,12 +104,7 @@ var mspHelper = (function (gui) {
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
-
- if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
- SENSOR_STATUS.imu2HwStatus = data.getUint8(9);
- } else {
- SENSOR_STATUS.imu2HwStatus = 0;
- }
+ SENSOR_STATUS.imu2HwStatus = data.getUint8(9);
sensor_status_ex(SENSOR_STATUS);
break;
@@ -720,7 +694,7 @@ var mspHelper = (function (gui) {
BOARD_ALIGNMENT.pitch = data.getInt16(2, true); // -180 - 360
BOARD_ALIGNMENT.yaw = data.getInt16(4, true); // -180 - 360
break;
-
+
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
console.log('MSP_SET_BOARD_ALIGNMENT saved');
break;
@@ -1128,17 +1102,6 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_SET_BLACKBOX_CONFIG:
console.log("Blackbox config saved");
break;
- case MSPCodes.MSP_TRANSPONDER_CONFIG:
- TRANSPONDER.supported = (data.getUint8(offset++) & 1) != 0;
- TRANSPONDER.data = [];
- var bytesRemaining = data.byteLength - offset;
- for (i = 0; i < bytesRemaining; i++) {
- TRANSPONDER.data.push(data.getUint8(offset++));
- }
- break;
- case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
- console.log("Transponder config saved");
- break;
case MSPCodes.MSP_VTX_CONFIG:
VTX_CONFIG.device_type = data.getUint8(offset++);
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
@@ -1274,11 +1237,9 @@ var mspHelper = (function (gui) {
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
- if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
- CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
- CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
- CALIBRATION_DATA.magGain.Z = data.getInt16(25, true);
- }
+ CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
+ CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
+ CALIBRATION_DATA.magGain.Z = data.getInt16(25, true);
break;
@@ -1520,7 +1481,7 @@ var mspHelper = (function (gui) {
// fire callback
if (callback) {
- callback({'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected});
+ callback({ 'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected });
}
break;
}
@@ -1559,7 +1520,7 @@ var mspHelper = (function (gui) {
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 1));
break;
-
+
case MSPCodes.MSP_SET_VTX_CONFIG:
if (VTX_CONFIG.band > 0) {
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
@@ -1772,12 +1733,6 @@ var mspHelper = (function (gui) {
buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
break;
- case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
- for (i = 0; i < TRANSPONDER.data.length; i++) {
- buffer.push(TRANSPONDER.data[i]);
- }
- break;
-
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
for (i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;
@@ -1925,16 +1880,14 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
buffer.push(highByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
- if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
- buffer.push(lowByte(CALIBRATION_DATA.magGain.X));
- buffer.push(highByte(CALIBRATION_DATA.magGain.X));
+ buffer.push(lowByte(CALIBRATION_DATA.magGain.X));
+ buffer.push(highByte(CALIBRATION_DATA.magGain.X));
- buffer.push(lowByte(CALIBRATION_DATA.magGain.Y));
- buffer.push(highByte(CALIBRATION_DATA.magGain.Y));
+ buffer.push(lowByte(CALIBRATION_DATA.magGain.Y));
+ buffer.push(highByte(CALIBRATION_DATA.magGain.Y));
- buffer.push(lowByte(CALIBRATION_DATA.magGain.Z));
- buffer.push(highByte(CALIBRATION_DATA.magGain.Z));
- }
+ buffer.push(lowByte(CALIBRATION_DATA.magGain.Z));
+ buffer.push(highByte(CALIBRATION_DATA.magGain.Z));
break;
@@ -2151,9 +2104,9 @@ var mspHelper = (function (gui) {
};
self.sendBlackboxConfiguration = function (onDataCallback) {
- var buffer = [];
- var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
- buffer.push(BLACKBOX.blackboxDevice & 0xFF);
+ var buffer = [];
+ var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
+ buffer.push(BLACKBOX.blackboxDevice & 0xFF);
messageId = MSPCodes.MSP2_SET_BLACKBOX_CONFIG;
buffer.push(lowByte(BLACKBOX.blackboxRateNum));
buffer.push(highByte(BLACKBOX.blackboxRateNum));
@@ -2161,7 +2114,7 @@ var mspHelper = (function (gui) {
buffer.push(highByte(BLACKBOX.blackboxRateDenom));
//noinspection JSUnusedLocalSymbols
MSP.send_message(messageId, buffer, false, function (response) {
- onDataCallback();
+ onDataCallback();
});
};
@@ -2328,9 +2281,7 @@ var mspHelper = (function (gui) {
buffer.push(conditionIndex);
buffer.push(condition.getEnabled());
- if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
- buffer.push(condition.getActivatorId());
- }
+ buffer.push(condition.getActivatorId());
buffer.push(condition.getOperation());
buffer.push(condition.getOperandAType());
buffer.push(specificByte(condition.getOperandAValue(), 0));
@@ -2623,7 +2574,7 @@ var mspHelper = (function (gui) {
/*
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
- ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
+ ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
*/
@@ -2714,10 +2665,6 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
};
- self.loadLoopTime = function (callback) {
- MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, callback);
- };
-
self.loadAdvancedConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, callback);
};
@@ -2746,10 +2693,6 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_PIDNAMES, false, false, callback);
};
- self.loadStatus = function (callback) {
- MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
- };
-
self.loadFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, callback);
};
@@ -2757,7 +2700,7 @@ var mspHelper = (function (gui) {
self.loadBoardAlignment = function (callback) {
MSP.send_message(MSPCodes.MSP_BOARD_ALIGNMENT, false, false, callback);
};
-
+
self.loadCurrentMeterConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, callback);
};
@@ -2779,7 +2722,7 @@ var mspHelper = (function (gui) {
};
self.loadBatteryConfig = function (callback) {
- MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
+ MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
};
self.loadArmingConfig = function (callback) {
@@ -2834,10 +2777,6 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_INAV_PID, mspHelper.crunch(MSPCodes.MSP_SET_INAV_PID), false, callback);
};
- self.saveLooptimeConfig = function (callback) {
- MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, callback);
- };
-
self.saveAdvancedConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, callback);
};
@@ -2947,7 +2886,7 @@ var mspHelper = (function (gui) {
};
self.saveFwConfig = function (callback) {
- MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
+ MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
};
self.getMissionInfo = function (callback) {
@@ -2999,7 +2938,7 @@ var mspHelper = (function (gui) {
function nextSafehome() {
safehomeId++;
- if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
+ if (safehomeId < SAFEHOMES.getMaxSafehomeCount() - 1) {
MSP.send_message(MSPCodes.MSP2_INAV_SAFEHOME, [safehomeId], false, nextSafehome);
}
else {
@@ -3014,7 +2953,7 @@ var mspHelper = (function (gui) {
function nextSendSafehome() {
safehomeId++;
- if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
+ if (safehomeId < SAFEHOMES.getMaxSafehomeCount() - 1) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_SAFEHOME, SAFEHOMES.extractBuffer(safehomeId), false, nextSendSafehome);
}
else {
@@ -3043,9 +2982,7 @@ var mspHelper = (function (gui) {
var setting = {};
// Discard setting name
- if (semver.gte(CONFIG.apiVersion, "2.4.0")) {
- result.data.readString();
- }
+ result.data.readString();
// Discard PG ID
result.data.readU16();
@@ -3073,7 +3010,7 @@ var mspHelper = (function (gui) {
for (var ii = setting.min; ii <= setting.max; ii++) {
values.push(result.data.readString());
}
- setting.table = {values: values};
+ setting.table = { values: values };
}
SETTINGS[name] = setting;
return setting;
@@ -3128,7 +3065,7 @@ var mspHelper = (function (gui) {
default:
throw "Unknown setting type " + setting.type;
}
- return {setting: setting, value: value};
+ return { setting: setting, value: value };
});
});
};
@@ -3217,8 +3154,8 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, callback);
};
- self.getCraftName = function(callback) {
- MSP.send_message(MSPCodes.MSP_NAME, false, false, function(resp) {
+ self.getCraftName = function (callback) {
+ MSP.send_message(MSPCodes.MSP_NAME, false, false, function (resp) {
var name = resp.data.readString();
if (callback) {
callback(name);
@@ -3226,7 +3163,7 @@ var mspHelper = (function (gui) {
});
};
- self.setCraftName = function(name, callback) {
+ self.setCraftName = function (name, callback) {
var data = [];
name = name || "";
for (var ii = 0; ii < name.length; ii++) {
@@ -3247,26 +3184,26 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
};
- self.saveVTXConfig = function(callback) {
+ self.saveVTXConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
};
- self.loadBrakingConfig = function(callback) {
+ self.loadBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
}
- self.saveBrakingConfig = function(callback) {
+ self.saveBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
};
- self.loadParameterGroups = function(callback) {
+ self.loadParameterGroups = function (callback) {
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
var groups = [];
while (resp.data.offset < resp.data.byteLength) {
var id = resp.data.readU16();
var start = 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) {
callback(groups);
@@ -3274,7 +3211,7 @@ var mspHelper = (function (gui) {
});
};
- self.loadBrakingConfig = function(callback) {
+ self.loadBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
}
@@ -3283,19 +3220,11 @@ var mspHelper = (function (gui) {
};
self.loadGlobalVariablesStatus = function (callback) {
- if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
- MSP.send_message(MSPCodes.MSP2_INAV_GVAR_STATUS, false, false, callback);
- } else {
- callback();
- }
+ MSP.send_message(MSPCodes.MSP2_INAV_GVAR_STATUS, false, false, callback);
};
self.loadProgrammingPidStatus = function (callback) {
- if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
- MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
- } else {
- callback();
- }
+ MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
};
return self;
diff --git a/js/serial_backend.js b/js/serial_backend.js
index 5e40e8a4..9fd17adc 100755
--- a/js/serial_backend.js
+++ b/js/serial_backend.js
@@ -62,7 +62,7 @@ $(document).ready(function () {
} else {
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
- MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
+ MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceReady'));
//noinspection JSValidateTypes
@@ -334,12 +334,8 @@ function onConnect() {
/*
* Init PIDs bank with a length that depends on the version
*/
- let pidCount;
- if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
- pidCount = 11;
- } else {
- pidCount = 10;
- }
+ let pidCount = 11;
+
for (let i = 0; i < pidCount; i++) {
PIDs.push(new Array(4));
}
diff --git a/js/settings.js b/js/settings.js
index defbf8d7..7c9482d3 100644
--- a/js/settings.js
+++ b/js/settings.js
@@ -1,7 +1,5 @@
'use strict';
-const GulpClient = require("gulp");
-
var Settings = (function () {
let self = {};
diff --git a/js/tasks.js b/js/tasks.js
deleted file mode 100644
index 9a53d0ba..00000000
--- a/js/tasks.js
+++ /dev/null
@@ -1,25 +0,0 @@
-'use strict';
-
-var helper = helper || {};
-
-helper.task = (function () {
-
- var publicScope = {},
- privateScope = {};
-
- privateScope.getStatusPullInterval = function () {
- //TODO use serial connection speed to determine update interval
- return 250;
- };
-
- publicScope.statusPullStart = function () {
- helper.interval.add('status_pull', function () {
- MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
- MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
- });
-
- }, privateScope.getStatusPullInterval(), true);
- };
-
- return publicScope;
-})(); \ No newline at end of file