mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-25 17:25:14 +03:00
Merge branch 'master' into MrD-Highlight-parameters-that-change-with-profiles-or-battery-profiles
This commit is contained in:
commit
ea20a04362
18 changed files with 353 additions and 382 deletions
|
@ -976,7 +976,7 @@
|
||||||
"message": "Cycles/Sec (Hz)"
|
"message": "Cycles/Sec (Hz)"
|
||||||
},
|
},
|
||||||
"configurationGPS": {
|
"configurationGPS": {
|
||||||
"message": "GPS"
|
"message": "Configuration"
|
||||||
},
|
},
|
||||||
"configurationGPSProtocol": {
|
"configurationGPSProtocol": {
|
||||||
"message": "Protocol"
|
"message": "Protocol"
|
||||||
|
@ -1786,10 +1786,10 @@
|
||||||
"message":"<ol><li>Remove propellers</li><li>Connect LiPo and use Outputs Tab to test all motors</li><li>Note the position of each motor (motor #1 - Left Top and so on)</li><li>Fill the table below</li></ol>"
|
"message":"<ol><li>Remove propellers</li><li>Connect LiPo and use Outputs Tab to test all motors</li><li>Note the position of each motor (motor #1 - Left Top and so on)</li><li>Fill the table below</li></ol>"
|
||||||
},
|
},
|
||||||
"gpsHead": {
|
"gpsHead": {
|
||||||
"message": "GPS"
|
"message": "Position"
|
||||||
},
|
},
|
||||||
"gpsStatHead": {
|
"gpsStatHead": {
|
||||||
"message": "GPS Statistics"
|
"message": "Statistics"
|
||||||
},
|
},
|
||||||
"gpsMapHead": {
|
"gpsMapHead": {
|
||||||
"message": "Current GPS location"
|
"message": "Current GPS location"
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*global mspHelper,$,GUI,MSP,BF_CONFIG,chrome*/
|
/*global mspHelper,$,GUI,MSP,chrome*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
var helper = helper || {};
|
var helper = helper || {};
|
||||||
|
@ -733,7 +733,7 @@ helper.defaultsDialog = (function () {
|
||||||
savingDefaultsModal.close();
|
savingDefaultsModal.close();
|
||||||
}
|
}
|
||||||
|
|
||||||
mspHelper.loadBfConfig(function () {
|
mspHelper.loadFeatures(function () {
|
||||||
privateScope.setFeaturesBits(selectedDefaultPreset)
|
privateScope.setFeaturesBits(selectedDefaultPreset)
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
|
|
32
js/fc.js
32
js/fc.js
|
@ -2,7 +2,6 @@
|
||||||
|
|
||||||
// define all the global variables that are uses to hold FC state
|
// define all the global variables that are uses to hold FC state
|
||||||
var CONFIG,
|
var CONFIG,
|
||||||
BF_CONFIG,
|
|
||||||
LED_STRIP,
|
LED_STRIP,
|
||||||
LED_COLORS,
|
LED_COLORS,
|
||||||
LED_MODE_COLORS,
|
LED_MODE_COLORS,
|
||||||
|
@ -63,7 +62,10 @@ var CONFIG,
|
||||||
OUTPUT_MAPPING,
|
OUTPUT_MAPPING,
|
||||||
SETTINGS,
|
SETTINGS,
|
||||||
BRAKING_CONFIG,
|
BRAKING_CONFIG,
|
||||||
SAFEHOMES;
|
SAFEHOMES,
|
||||||
|
BOARD_ALIGNMENT,
|
||||||
|
CURRENT_METER_CONFIG,
|
||||||
|
FEATURES;
|
||||||
|
|
||||||
var FC = {
|
var FC = {
|
||||||
MAX_SERVO_RATE: 125,
|
MAX_SERVO_RATE: 125,
|
||||||
|
@ -127,21 +129,25 @@ var FC = {
|
||||||
name: ''
|
name: ''
|
||||||
};
|
};
|
||||||
|
|
||||||
BF_CONFIG = {
|
BOARD_ALIGNMENT = {
|
||||||
mixerConfiguration: 0,
|
roll: 0,
|
||||||
features: 0,
|
pitch: 0,
|
||||||
serialrx_type: 0,
|
yaw: 0
|
||||||
board_align_roll: 0,
|
};
|
||||||
board_align_pitch: 0,
|
|
||||||
board_align_yaw: 0,
|
CURRENT_METER_CONFIG = {
|
||||||
currentscale: 0,
|
scale: 0,
|
||||||
currentoffset: 0
|
offset: 0,
|
||||||
|
type: 0,
|
||||||
|
capacity: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
LED_STRIP = [];
|
LED_STRIP = [];
|
||||||
LED_COLORS = [];
|
LED_COLORS = [];
|
||||||
LED_MODE_COLORS = [];
|
LED_MODE_COLORS = [];
|
||||||
|
|
||||||
|
FEATURES = 0;
|
||||||
|
|
||||||
PID = {
|
PID = {
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -576,7 +582,7 @@ var FC = {
|
||||||
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
|
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
|
||||||
{bit: 4, group: 'other', name: 'MOTOR_STOP'},
|
{bit: 4, group: 'other', name: 'MOTOR_STOP'},
|
||||||
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
|
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
|
||||||
{bit: 7, group: 'gps', name: 'GPS', haveTip: true},
|
{bit: 7, group: 'other', name: 'GPS', haveTip: true},
|
||||||
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
|
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
|
||||||
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'},
|
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'},
|
||||||
{bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true},
|
{bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true},
|
||||||
|
@ -606,7 +612,7 @@ var FC = {
|
||||||
features = this.getFeatures();
|
features = this.getFeatures();
|
||||||
}
|
}
|
||||||
for (var i = 0; i < features.length; i++) {
|
for (var i = 0; i < features.length; i++) {
|
||||||
if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) {
|
if (features[i].name == featureName && bit_check(FEATURES, features[i].bit)) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*global mspHelper,BF_CONFIG*/
|
/*global mspHelper,FEATURES,bit_clear,bit_set*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
var helper = helper || {};
|
var helper = helper || {};
|
||||||
|
@ -67,20 +67,20 @@ helper.features = (function() {
|
||||||
|
|
||||||
publicScope.execute = function(callback) {
|
publicScope.execute = function(callback) {
|
||||||
exitPoint = callback;
|
exitPoint = callback;
|
||||||
mspHelper.loadBfConfig(privateScope.setBits);
|
mspHelper.loadFeatures(privateScope.setBits);
|
||||||
};
|
};
|
||||||
|
|
||||||
privateScope.setBits = function () {
|
privateScope.setBits = function () {
|
||||||
|
|
||||||
for (const bit of toSet) {
|
for (const bit of toSet) {
|
||||||
BF_CONFIG.features = bit_set(BF_CONFIG.features, bit);
|
FEATURES = bit_set(FEATURES, bit);
|
||||||
}
|
}
|
||||||
|
|
||||||
for (const bit of toUnset) {
|
for (const bit of toUnset) {
|
||||||
BF_CONFIG.features = bit_clear(BF_CONFIG.features, bit);
|
FEATURES = bit_clear(FEATURES, bit);
|
||||||
}
|
}
|
||||||
|
|
||||||
mspHelper.saveBfConfig(exitPoint);
|
mspHelper.saveFeatures(exitPoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
return publicScope;
|
return publicScope;
|
||||||
|
|
|
@ -33,6 +33,12 @@ var MSPCodes = {
|
||||||
MSP_SET_CHANNEL_FORWARDING: 33,
|
MSP_SET_CHANNEL_FORWARDING: 33,
|
||||||
MSP_MODE_RANGES: 34,
|
MSP_MODE_RANGES: 34,
|
||||||
MSP_SET_MODE_RANGE: 35,
|
MSP_SET_MODE_RANGE: 35,
|
||||||
|
MSP_FEATURE: 36,
|
||||||
|
MSP_SET_FEATURE: 37,
|
||||||
|
MSP_BOARD_ALIGNMENT: 38,
|
||||||
|
MSP_SET_BOARD_ALIGNMENT: 39,
|
||||||
|
MSP_CURRENT_METER_CONFIG: 40,
|
||||||
|
MSP_SET_CURRENT_METER_CONFIG: 41,
|
||||||
MSP_RX_CONFIG: 44,
|
MSP_RX_CONFIG: 44,
|
||||||
MSP_SET_RX_CONFIG: 45,
|
MSP_SET_RX_CONFIG: 45,
|
||||||
MSP_LED_COLORS: 46,
|
MSP_LED_COLORS: 46,
|
||||||
|
@ -44,8 +50,6 @@ var MSPCodes = {
|
||||||
MSP_CF_SERIAL_CONFIG: 54,
|
MSP_CF_SERIAL_CONFIG: 54,
|
||||||
MSP_SET_CF_SERIAL_CONFIG: 55,
|
MSP_SET_CF_SERIAL_CONFIG: 55,
|
||||||
MSP_SONAR: 58,
|
MSP_SONAR: 58,
|
||||||
MSP_PID_CONTROLLER: 59,
|
|
||||||
MSP_SET_PID_CONTROLLER: 60,
|
|
||||||
MSP_ARMING_CONFIG: 61,
|
MSP_ARMING_CONFIG: 61,
|
||||||
MSP_SET_ARMING_CONFIG: 62,
|
MSP_SET_ARMING_CONFIG: 62,
|
||||||
MSP_DATAFLASH_SUMMARY: 70,
|
MSP_DATAFLASH_SUMMARY: 70,
|
||||||
|
@ -149,10 +153,10 @@ var MSPCodes = {
|
||||||
// Additional private MSP for baseflight configurator (yes thats us \o/)
|
// Additional private MSP for baseflight configurator (yes thats us \o/)
|
||||||
MSP_RX_MAP: 64, // get channel map (also returns number of channels total)
|
MSP_RX_MAP: 64, // get channel map (also returns number of channels total)
|
||||||
MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
|
MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
|
||||||
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
|
MSP_BF_CONFIG: 66, // Depreciated
|
||||||
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
|
MSP_SET_BF_CONFIG: 67, // Depreciated
|
||||||
MSP_SET_REBOOT: 68, // reboot settings
|
MSP_SET_REBOOT: 68, // reboot settings
|
||||||
MSP_BF_BUILD_INFO: 69, // build date as well as some space for future expansion
|
MSP_BF_BUILD_INFO: 69, // Depreciated
|
||||||
|
|
||||||
// INAV specific codes
|
// INAV specific codes
|
||||||
MSPV2_SETTING: 0x1003,
|
MSPV2_SETTING: 0x1003,
|
||||||
|
|
|
@ -68,15 +68,6 @@ var mspHelper = (function (gui) {
|
||||||
colorCount,
|
colorCount,
|
||||||
color;
|
color;
|
||||||
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
|
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
|
||||||
case MSPCodes.MSP_IDENT:
|
|
||||||
//FIXME remove this frame when proven not needed
|
|
||||||
console.log('Using deprecated msp command: MSP_IDENT');
|
|
||||||
// Deprecated
|
|
||||||
CONFIG.version = parseFloat((data.getUint8(0) / 100).toFixed(2));
|
|
||||||
CONFIG.multiType = data.getUint8(1);
|
|
||||||
CONFIG.msp_version = data.getUint8(2);
|
|
||||||
CONFIG.capability = data.getUint32(3, true);
|
|
||||||
break;
|
|
||||||
case MSPCodes.MSP_STATUS:
|
case MSPCodes.MSP_STATUS:
|
||||||
console.log('Using deprecated msp command: MSP_STATUS');
|
console.log('Using deprecated msp command: MSP_STATUS');
|
||||||
CONFIG.cycleTime = data.getUint16(0, true);
|
CONFIG.cycleTime = data.getUint16(0, true);
|
||||||
|
@ -293,14 +284,6 @@ var mspHelper = (function (gui) {
|
||||||
RC_tuning.manual_pitch_rate = data.getUint8(offset++);
|
RC_tuning.manual_pitch_rate = data.getUint8(offset++);
|
||||||
RC_tuning.manual_yaw_rate = data.getUint8(offset++);
|
RC_tuning.manual_yaw_rate = data.getUint8(offset++);
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_PID:
|
|
||||||
// PID data arrived, we need to scale it and save to appropriate bank / array
|
|
||||||
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 3); i++, needle += 3) {
|
|
||||||
PIDs[i][0] = data.getUint8(needle);
|
|
||||||
PIDs[i][1] = data.getUint8(needle + 1);
|
|
||||||
PIDs[i][2] = data.getUint8(needle + 2);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case MSPCodes.MSP2_PID:
|
case MSPCodes.MSP2_PID:
|
||||||
// PID data arrived, we need to scale it and save to appropriate bank / array
|
// PID data arrived, we need to scale it and save to appropriate bank / array
|
||||||
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
|
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
|
||||||
|
@ -640,9 +623,6 @@ var mspHelper = (function (gui) {
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_RAW_GPS:
|
case MSPCodes.MSP_SET_RAW_GPS:
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_PID:
|
|
||||||
console.log('PID settings saved');
|
|
||||||
break;
|
|
||||||
case MSPCodes.MSP2_SET_PID:
|
case MSPCodes.MSP2_SET_PID:
|
||||||
console.log('PID settings saved');
|
console.log('PID settings saved');
|
||||||
break;
|
break;
|
||||||
|
@ -734,19 +714,36 @@ var mspHelper = (function (gui) {
|
||||||
case MSPCodes.MSP_SET_RX_MAP:
|
case MSPCodes.MSP_SET_RX_MAP:
|
||||||
console.log('RCMAP saved');
|
console.log('RCMAP saved');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_BF_CONFIG:
|
|
||||||
BF_CONFIG.mixerConfiguration = data.getUint8(0);
|
case MSPCodes.MSP_BOARD_ALIGNMENT:
|
||||||
BF_CONFIG.features = data.getUint32(1, true);
|
BOARD_ALIGNMENT.roll = data.getInt16(0, true); // -180 - 360
|
||||||
BF_CONFIG.serialrx_type = data.getUint8(5);
|
BOARD_ALIGNMENT.pitch = data.getInt16(2, true); // -180 - 360
|
||||||
BF_CONFIG.board_align_roll = data.getInt16(6, true); // -180 - 360
|
BOARD_ALIGNMENT.yaw = data.getInt16(4, true); // -180 - 360
|
||||||
BF_CONFIG.board_align_pitch = data.getInt16(8, true); // -180 - 360
|
|
||||||
BF_CONFIG.board_align_yaw = data.getInt16(10, true); // -180 - 360
|
|
||||||
BF_CONFIG.currentscale = data.getInt16(12, true);
|
|
||||||
BF_CONFIG.currentoffset = data.getInt16(14, true);
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_BF_CONFIG:
|
|
||||||
console.log('BF_CONFIG saved');
|
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
|
||||||
|
console.log('MSP_SET_BOARD_ALIGNMENT saved');
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_CURRENT_METER_CONFIG:
|
||||||
|
CURRENT_METER_CONFIG.scale = data.getInt16(0, true);
|
||||||
|
CURRENT_METER_CONFIG.offset = data.getInt16(2, true);
|
||||||
|
CURRENT_METER_CONFIG.type = data.getUint8(4);
|
||||||
|
CURRENT_METER_CONFIG.capacity = data.getInt16(5, true);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||||
|
console.log('MSP_SET_CURRENT_METER_CONFIG saved');
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_FEATURE:
|
||||||
|
FEATURES = data.getUint32(0, true);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_SET_FEATURE:
|
||||||
|
console.log('MSP_SET_FEATURE saved');
|
||||||
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_REBOOT:
|
case MSPCodes.MSP_SET_REBOOT:
|
||||||
console.log('Reboot request accepted');
|
console.log('Reboot request accepted');
|
||||||
break;
|
break;
|
||||||
|
@ -800,28 +797,6 @@ var mspHelper = (function (gui) {
|
||||||
console.log('Channel forwarding saved');
|
console.log('Channel forwarding saved');
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_CF_SERIAL_CONFIG:
|
|
||||||
SERIAL_CONFIG.ports = [];
|
|
||||||
var bytesPerPort = 1 + 2 + 4;
|
|
||||||
var serialPortCount = data.byteLength / bytesPerPort;
|
|
||||||
|
|
||||||
for (i = 0; i < serialPortCount; i++) {
|
|
||||||
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
|
|
||||||
|
|
||||||
var serialPort = {
|
|
||||||
identifier: data.getUint8(offset),
|
|
||||||
functions: mspHelper.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, true)),
|
|
||||||
msp_baudrate: BAUD_RATES[data.getUint8(offset + 3)],
|
|
||||||
sensors_baudrate: BAUD_RATES[data.getUint8(offset + 4)],
|
|
||||||
telemetry_baudrate: BAUD_RATES[data.getUint8(offset + 5)],
|
|
||||||
blackbox_baudrate: BAUD_RATES[data.getUint8(offset + 6)]
|
|
||||||
};
|
|
||||||
|
|
||||||
offset += bytesPerPort;
|
|
||||||
SERIAL_CONFIG.ports.push(serialPort);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSPCodes.MSP2_CF_SERIAL_CONFIG:
|
case MSPCodes.MSP2_CF_SERIAL_CONFIG:
|
||||||
SERIAL_CONFIG.ports = [];
|
SERIAL_CONFIG.ports = [];
|
||||||
var bytesPerPort = 1 + 4 + 4;
|
var bytesPerPort = 1 + 4 + 4;
|
||||||
|
@ -844,7 +819,6 @@ var mspHelper = (function (gui) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
|
|
||||||
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
|
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
|
||||||
console.log('Serial config saved');
|
console.log('Serial config saved');
|
||||||
break;
|
break;
|
||||||
|
@ -1559,24 +1533,33 @@ var mspHelper = (function (gui) {
|
||||||
i;
|
i;
|
||||||
|
|
||||||
switch (code) {
|
switch (code) {
|
||||||
case MSPCodes.MSP_SET_BF_CONFIG:
|
|
||||||
buffer.push(BF_CONFIG.mixerConfiguration);
|
case MSPCodes.MSP_SET_FEATURE:
|
||||||
buffer.push(specificByte(BF_CONFIG.features, 0));
|
buffer.push(specificByte(FEATURES, 0));
|
||||||
buffer.push(specificByte(BF_CONFIG.features, 1));
|
buffer.push(specificByte(FEATURES, 1));
|
||||||
buffer.push(specificByte(BF_CONFIG.features, 2));
|
buffer.push(specificByte(FEATURES, 2));
|
||||||
buffer.push(specificByte(BF_CONFIG.features, 3));
|
buffer.push(specificByte(FEATURES, 3));
|
||||||
buffer.push(BF_CONFIG.serialrx_type);
|
|
||||||
buffer.push(specificByte(BF_CONFIG.board_align_roll, 0));
|
|
||||||
buffer.push(specificByte(BF_CONFIG.board_align_roll, 1));
|
|
||||||
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 0));
|
|
||||||
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 1));
|
|
||||||
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 0));
|
|
||||||
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 1));
|
|
||||||
buffer.push(lowByte(BF_CONFIG.currentscale));
|
|
||||||
buffer.push(highByte(BF_CONFIG.currentscale));
|
|
||||||
buffer.push(lowByte(BF_CONFIG.currentoffset));
|
|
||||||
buffer.push(highByte(BF_CONFIG.currentoffset));
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
|
||||||
|
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 0));
|
||||||
|
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 1));
|
||||||
|
buffer.push(specificByte(BOARD_ALIGNMENT.pitch, 0));
|
||||||
|
buffer.push(specificByte(BOARD_ALIGNMENT.pitch, 1));
|
||||||
|
buffer.push(specificByte(BOARD_ALIGNMENT.yaw, 0));
|
||||||
|
buffer.push(specificByte(BOARD_ALIGNMENT.yaw, 1));
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||||
|
buffer.push(specificByte(CURRENT_METER_CONFIG.scale, 0));
|
||||||
|
buffer.push(specificByte(CURRENT_METER_CONFIG.scale, 1));
|
||||||
|
buffer.push(specificByte(CURRENT_METER_CONFIG.offset, 0));
|
||||||
|
buffer.push(specificByte(CURRENT_METER_CONFIG.offset, 1));
|
||||||
|
buffer.push(CURRENT_METER_CONFIG.type);
|
||||||
|
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 0));
|
||||||
|
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 1));
|
||||||
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_VTX_CONFIG:
|
case MSPCodes.MSP_SET_VTX_CONFIG:
|
||||||
if (VTX_CONFIG.band > 0) {
|
if (VTX_CONFIG.band > 0) {
|
||||||
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
|
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
|
||||||
|
@ -1589,13 +1572,6 @@ var mspHelper = (function (gui) {
|
||||||
buffer.push(0);
|
buffer.push(0);
|
||||||
buffer.push(VTX_CONFIG.low_power_disarm);
|
buffer.push(VTX_CONFIG.low_power_disarm);
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_PID:
|
|
||||||
for (i = 0; i < PIDs.length; i++) {
|
|
||||||
buffer.push(parseInt(PIDs[i][0]));
|
|
||||||
buffer.push(parseInt(PIDs[i][1]));
|
|
||||||
buffer.push(parseInt(PIDs[i][2]));
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case MSPCodes.MSP2_SET_PID:
|
case MSPCodes.MSP2_SET_PID:
|
||||||
for (i = 0; i < PIDs.length; i++) {
|
for (i = 0; i < PIDs.length; i++) {
|
||||||
buffer.push(parseInt(PIDs[i][0]));
|
buffer.push(parseInt(PIDs[i][0]));
|
||||||
|
@ -1812,24 +1788,6 @@ var mspHelper = (function (gui) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
|
|
||||||
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
|
|
||||||
var serialPort = SERIAL_CONFIG.ports[i];
|
|
||||||
|
|
||||||
buffer.push(serialPort.identifier);
|
|
||||||
|
|
||||||
var functionMask = mspHelper.SERIAL_PORT_FUNCTIONSToMask(serialPort.functions);
|
|
||||||
buffer.push(specificByte(functionMask, 0));
|
|
||||||
buffer.push(specificByte(functionMask, 1));
|
|
||||||
|
|
||||||
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
|
|
||||||
buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate));
|
|
||||||
buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate));
|
|
||||||
buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate));
|
|
||||||
buffer.push(BAUD_RATES.indexOf(serialPort.blackbox_baudrate));
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
|
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
|
||||||
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
|
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
|
||||||
var serialPort = SERIAL_CONFIG.ports[i];
|
var serialPort = SERIAL_CONFIG.ports[i];
|
||||||
|
@ -2752,14 +2710,6 @@ var mspHelper = (function (gui) {
|
||||||
* Basic sending methods used for chaining purposes
|
* Basic sending methods used for chaining purposes
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
|
||||||
* @deprecated
|
|
||||||
* @param callback
|
|
||||||
*/
|
|
||||||
self.loadMspIdent = function (callback) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_IDENT, false, false, callback);
|
|
||||||
};
|
|
||||||
|
|
||||||
self.loadINAVPidConfig = function (callback) {
|
self.loadINAVPidConfig = function (callback) {
|
||||||
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
|
||||||
};
|
};
|
||||||
|
@ -2800,8 +2750,16 @@ var mspHelper = (function (gui) {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadBfConfig = function (callback) {
|
self.loadFeatures = function (callback) {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, callback);
|
||||||
|
};
|
||||||
|
|
||||||
|
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);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.queryFcStatus = function (callback) {
|
self.queryFcStatus = function (callback) {
|
||||||
|
@ -2904,8 +2862,16 @@ var mspHelper = (function (gui) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback);
|
MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveBfConfig = function (callback) {
|
self.saveFeatures = function (callback) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, callback);
|
MSP.send_message(MSPCodes.MSP_SET_FEATURE, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE), false, callback);
|
||||||
|
};
|
||||||
|
|
||||||
|
self.saveCurrentMeterConfig = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, callback);
|
||||||
|
};
|
||||||
|
|
||||||
|
self.saveBoardAlignment = function (callback) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_BOARD_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_BOARD_ALIGNMENT), false, callback);
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveMisc = function (callback) {
|
self.saveMisc = function (callback) {
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
"jquery-ui-npm": "1.12.0",
|
"jquery-ui-npm": "1.12.0",
|
||||||
"marked": "^0.3.17",
|
"marked": "^0.3.17",
|
||||||
"minimist": "^1.2.0",
|
"minimist": "^1.2.0",
|
||||||
"nw": "^0.50.3-sdk",
|
"nw": "^0.61.0-sdk",
|
||||||
"nw-dialog": "^1.0.7",
|
"nw-dialog": "^1.0.7",
|
||||||
"openlayers": "^4.6.5",
|
"openlayers": "^4.6.5",
|
||||||
"plotly": "^1.0.6",
|
"plotly": "^1.0.6",
|
||||||
|
|
|
@ -18,15 +18,7 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_data() {
|
function get_rc_data() {
|
||||||
if (SERIAL_CONFIG.ports.length == 0) {
|
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||||
MSP.send_message(MSPCodes.MSP_RC, false, false, get_serial_config);
|
|
||||||
} else {
|
|
||||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
function get_serial_config() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, load_html);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
|
|
|
@ -76,64 +76,6 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="config-section gui_box grey">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" data-i18n="configurationGPS"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="note">
|
|
||||||
<div class="note_spacer">
|
|
||||||
<p data-i18n="configurationGPSHelp"></p>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="features gps"></div>
|
|
||||||
<!--feature list generated content-->
|
|
||||||
|
|
||||||
<div class="select">
|
|
||||||
<select id="gps_protocol" class="gps_protocol">
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<label for="gps_protocol">
|
|
||||||
<span data-i18n="configurationGPSProtocol"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="select">
|
|
||||||
<select id="gps_ubx_sbas" class="gps_ubx_sbas">
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<label for="gps_ubx_sbas">
|
|
||||||
<span data-i18n="configurationGPSubxSbas"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number is-hidden">
|
|
||||||
<input type="number" id="mag_declination" name="mag_declination" step="0.1" min="-180" max="180" />
|
|
||||||
<label for="mag_declination">
|
|
||||||
<span data-i18n="configurationMagDeclination"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="checkbox">
|
|
||||||
<input type="checkbox" class="toggle update_preview" data-setting="gps_ublox_use_galileo" data-live="true">
|
|
||||||
<label for="gps_use_galileo">
|
|
||||||
<span data-i18n="configurationGPSUseGalileo"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="tzOffset" data-setting="tz_offset" data-setting-multiplier="1" step="1" min="-1440" max="1440" />
|
|
||||||
<label for="tzOffset">
|
|
||||||
<span data-i18n="tzOffset"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="tzOffsetHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="select">
|
|
||||||
<select id="tzAutomaticDST" data-setting="tz_automatic_dst"></select>
|
|
||||||
<label for="tzAutomaticDST">
|
|
||||||
<span data-i18n="tzAutomaticDST"></span>
|
|
||||||
</label>
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="tzAutomaticDSTHelp"></div>
|
|
||||||
</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">
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*global chrome,GUI,FC_CONFIG,$,mspHelper,googleAnalytics,ADVANCED_CONFIG,VTX_CONFIG,CONFIG,MSPChainerClass*/
|
/*global chrome,GUI,FC_CONFIG,$,mspHelper,googleAnalytics,ADVANCED_CONFIG,VTX_CONFIG,CONFIG,MSPChainerClass,BOARD_ALIGNMENT,TABS,MISC*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
TABS.configuration = {};
|
TABS.configuration = {};
|
||||||
|
@ -30,7 +30,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
var loadChainer = new MSPChainerClass();
|
var loadChainer = new MSPChainerClass();
|
||||||
|
|
||||||
var loadChain = [
|
var loadChain = [
|
||||||
mspHelper.loadBfConfig,
|
mspHelper.loadFeatures,
|
||||||
mspHelper.loadArmingConfig,
|
mspHelper.loadArmingConfig,
|
||||||
mspHelper.loadLoopTime,
|
mspHelper.loadLoopTime,
|
||||||
mspHelper.load3dConfig,
|
mspHelper.load3dConfig,
|
||||||
|
@ -39,6 +39,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
mspHelper.loadINAVPidConfig,
|
mspHelper.loadINAVPidConfig,
|
||||||
mspHelper.loadVTXConfig,
|
mspHelper.loadVTXConfig,
|
||||||
mspHelper.loadMixerConfig,
|
mspHelper.loadMixerConfig,
|
||||||
|
mspHelper.loadBoardAlignment,
|
||||||
|
mspHelper.loadCurrentMeterConfig,
|
||||||
loadCraftName,
|
loadCraftName,
|
||||||
mspHelper.loadMiscV2
|
mspHelper.loadMiscV2
|
||||||
];
|
];
|
||||||
|
@ -50,7 +52,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
var saveChainer = new MSPChainerClass();
|
var saveChainer = new MSPChainerClass();
|
||||||
|
|
||||||
var saveChain = [
|
var saveChain = [
|
||||||
mspHelper.saveBfConfig,
|
|
||||||
mspHelper.save3dConfig,
|
mspHelper.save3dConfig,
|
||||||
mspHelper.saveSensorAlignment,
|
mspHelper.saveSensorAlignment,
|
||||||
mspHelper.saveAccTrim,
|
mspHelper.saveAccTrim,
|
||||||
|
@ -59,6 +60,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
mspHelper.saveAdvancedConfig,
|
mspHelper.saveAdvancedConfig,
|
||||||
mspHelper.saveINAVPidConfig,
|
mspHelper.saveINAVPidConfig,
|
||||||
mspHelper.saveVTXConfig,
|
mspHelper.saveVTXConfig,
|
||||||
|
mspHelper.saveBoardAlignment,
|
||||||
|
mspHelper.saveCurrentMeterConfig,
|
||||||
saveCraftName,
|
saveCraftName,
|
||||||
mspHelper.saveMiscV2,
|
mspHelper.saveMiscV2,
|
||||||
saveSettings,
|
saveSettings,
|
||||||
|
@ -133,7 +136,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
helper.features.updateUI($('.tab-configuration'), BF_CONFIG.features);
|
helper.features.updateUI($('.tab-configuration'), FEATURES);
|
||||||
|
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
localize();
|
localize();
|
||||||
|
@ -146,32 +149,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
||||||
|
|
||||||
// generate GPS
|
|
||||||
var gpsProtocols = FC.getGpsProtocols();
|
|
||||||
var gpsSbas = FC.getGpsSbasProviders();
|
|
||||||
|
|
||||||
var gps_protocol_e = $('#gps_protocol');
|
|
||||||
for (i = 0; i < gpsProtocols.length; i++) {
|
|
||||||
gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>');
|
|
||||||
}
|
|
||||||
|
|
||||||
gps_protocol_e.change(function () {
|
|
||||||
MISC.gps_type = parseInt($(this).val());
|
|
||||||
});
|
|
||||||
|
|
||||||
gps_protocol_e.val(MISC.gps_type);
|
|
||||||
|
|
||||||
var gps_ubx_sbas_e = $('#gps_ubx_sbas');
|
|
||||||
for (i = 0; i < gpsSbas.length; i++) {
|
|
||||||
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
|
|
||||||
}
|
|
||||||
|
|
||||||
gps_ubx_sbas_e.change(function () {
|
|
||||||
MISC.gps_ubx_sbas = parseInt($(this).val());
|
|
||||||
});
|
|
||||||
|
|
||||||
gps_ubx_sbas_e.val(MISC.gps_ubx_sbas);
|
|
||||||
|
|
||||||
// VTX
|
// VTX
|
||||||
var config_vtx = $('.config-vtx');
|
var config_vtx = $('.config-vtx');
|
||||||
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
|
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
|
||||||
|
@ -255,7 +232,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
||||||
|
|
||||||
// fill board alignment
|
// fill board alignment
|
||||||
$('input[name="board_align_yaw"]').val((BF_CONFIG.board_align_yaw / 10.0).toFixed(1));
|
$('input[name="board_align_yaw"]').val((BOARD_ALIGNMENT.yaw / 10.0).toFixed(1));
|
||||||
|
|
||||||
// fill magnetometer
|
// fill magnetometer
|
||||||
$('#mag_declination').val(MISC.mag_declination);
|
$('#mag_declination').val(MISC.mag_declination);
|
||||||
|
@ -270,8 +247,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('#voltagescale').val(MISC.vbatscale);
|
$('#voltagescale').val(MISC.vbatscale);
|
||||||
|
|
||||||
// fill current
|
// fill current
|
||||||
$('#currentscale').val(BF_CONFIG.currentscale);
|
$('#currentscale').val(CURRENT_METER_CONFIG.scale);
|
||||||
$('#currentoffset').val(BF_CONFIG.currentoffset / 10);
|
$('#currentoffset').val(CURRENT_METER_CONFIG.offset / 10);
|
||||||
|
|
||||||
// fill battery capacity
|
// fill battery capacity
|
||||||
$('#battery_capacity').val(MISC.battery_capacity);
|
$('#battery_capacity').val(MISC.battery_capacity);
|
||||||
|
@ -351,13 +328,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
craftName = $('input[name="craft_name"]').val();
|
craftName = $('input[name="craft_name"]').val();
|
||||||
|
|
||||||
if (FC.isFeatureEnabled('GPS', features)) {
|
|
||||||
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
|
|
||||||
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
|
|
||||||
}
|
|
||||||
|
|
||||||
googleAnalytics.sendEvent('Setting', 'GPSEnabled', FC.isFeatureEnabled('GPS', features) ? "true" : "false");
|
|
||||||
|
|
||||||
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
|
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
|
||||||
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());
|
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());
|
||||||
|
|
||||||
|
@ -373,13 +343,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
helper.features.reset();
|
helper.features.reset();
|
||||||
helper.features.fromUI($('.tab-configuration'));
|
helper.features.fromUI($('.tab-configuration'));
|
||||||
helper.features.execute(function () {
|
helper.features.execute(function () {
|
||||||
BF_CONFIG.board_align_yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
|
BOARD_ALIGNMENT.yaw = Math.round(parseFloat($('input[name="board_align_yaw"]').val()) * 10);
|
||||||
BF_CONFIG.currentscale = parseInt($('#currentscale').val());
|
CURRENT_METER_CONFIG.scale = parseInt($('#currentscale').val());
|
||||||
BF_CONFIG.currentoffset = Math.round(parseFloat($('#currentoffset').val()) * 10);
|
CURRENT_METER_CONFIG.offset = Math.round(parseFloat($('#currentoffset').val()) * 10);
|
||||||
saveChainer.execute();
|
saveChainer.execute();
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
|
|
@ -14,14 +14,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_html);
|
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
/* function load_config() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
|
|
||||||
}
|
|
||||||
|
|
||||||
function load_misc() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
|
|
||||||
}*/
|
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
GUI.load("./tabs/failsafe.html", Settings.processHtml(function() {
|
GUI.load("./tabs/failsafe.html", Settings.processHtml(function() {
|
||||||
GUI.simpleBind();
|
GUI.simpleBind();
|
||||||
|
@ -150,80 +142,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
GUI.handleReconnect($('.tab_failsafe a'));
|
GUI.handleReconnect($('.tab_failsafe a'));
|
||||||
}
|
}
|
||||||
|
|
||||||
/*function process_html() {
|
|
||||||
|
|
||||||
// generate labels for assigned aux modes
|
|
||||||
var element;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
|
|
||||||
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
|
||||||
$('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay);
|
|
||||||
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
|
|
||||||
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Alternate, minimum distance failsafe procedure
|
|
||||||
GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
|
||||||
$failsafeMinDistanceProcedure.val(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
|
||||||
$failsafeMinDistanceProcedure.change(function () {
|
|
||||||
FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val();
|
|
||||||
});
|
|
||||||
|
|
||||||
$('a.save').click(function () {
|
|
||||||
FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val());
|
|
||||||
FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val());
|
|
||||||
FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val());
|
|
||||||
FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
|
|
||||||
FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val());
|
|
||||||
|
|
||||||
if ($('input[id="land"]').is(':checked')) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = 0;
|
|
||||||
} else if ($('input[id="drop"]').is(':checked')) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = 1;
|
|
||||||
} else if ($('input[id="rth"]').is(':checked')) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = 2;
|
|
||||||
} else if ($('input[id="nothing"]').is(':checked')) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = 3;
|
|
||||||
}
|
|
||||||
|
|
||||||
function save_failssafe_config() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_bf_config);
|
|
||||||
}
|
|
||||||
|
|
||||||
function save_bf_config() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
|
|
||||||
}
|
|
||||||
|
|
||||||
function save_to_eeprom() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
|
||||||
}
|
|
||||||
|
|
||||||
function reboot() {
|
|
||||||
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
|
||||||
|
|
||||||
GUI.tab_switch_cleanup(function () {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
|
||||||
});
|
|
||||||
}
|
|
||||||
|
|
||||||
function reinitialize() {
|
|
||||||
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
|
||||||
GUI.handleReconnect($('.tab_failsafe a'));
|
|
||||||
}
|
|
||||||
|
|
||||||
save_failssafe_config();
|
|
||||||
});
|
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
|
||||||
}*/
|
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.failsafe.cleanup = function (callback) {
|
TABS.failsafe.cleanup = function (callback) {
|
||||||
|
|
|
@ -1,8 +1,78 @@
|
||||||
<div class="tab-gps">
|
<div class="tab-gps toolbar_fixed_bottom">
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="tab_title" data-i18n="tabGPS">GPS</div>
|
<div class="tab_title" data-i18n="tabGPS">GPS</div>
|
||||||
<div class="cf_column fourth">
|
<div class="cf_column third_left">
|
||||||
<div class="spacer_right">
|
<div class="spacer_right">
|
||||||
|
|
||||||
|
<div class="config-section gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" data-i18n="configurationGPS"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<div class="note">
|
||||||
|
<div class="note_spacer">
|
||||||
|
<p data-i18n="configurationGPSHelp"></p>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" data-bit="7" class="feature toggle" name="GPS" title="GPS"
|
||||||
|
id="feature-7">
|
||||||
|
<label for="feature-7">
|
||||||
|
<span data-i18n="featureGPS"></span>
|
||||||
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="featureGPSTip"></div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="select">
|
||||||
|
<select id="gps_protocol" class="gps_protocol">
|
||||||
|
<!-- list generated here -->
|
||||||
|
</select>
|
||||||
|
<label for="gps_protocol">
|
||||||
|
<span data-i18n="configurationGPSProtocol"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="select">
|
||||||
|
<select id="gps_ubx_sbas" class="gps_ubx_sbas">
|
||||||
|
<!-- list generated here -->
|
||||||
|
</select>
|
||||||
|
<label for="gps_ubx_sbas">
|
||||||
|
<span data-i18n="configurationGPSubxSbas"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number is-hidden">
|
||||||
|
<input type="number" id="mag_declination" name="mag_declination" step="0.1" min="-180"
|
||||||
|
max="180" />
|
||||||
|
<label for="mag_declination">
|
||||||
|
<span data-i18n="configurationMagDeclination"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="checkbox">
|
||||||
|
<input type="checkbox" class="toggle update_preview" data-setting="gps_ublox_use_galileo"
|
||||||
|
data-live="true">
|
||||||
|
<label for="gps_use_galileo">
|
||||||
|
<span data-i18n="configurationGPSUseGalileo"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input type="number" id="tzOffset" data-setting="tz_offset" data-setting-multiplier="1"
|
||||||
|
step="1" min="-1440" max="1440" />
|
||||||
|
<label for="tzOffset">
|
||||||
|
<span data-i18n="tzOffset"></span>
|
||||||
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="tzOffsetHelp"></div>
|
||||||
|
</div>
|
||||||
|
<div class="select">
|
||||||
|
<select id="tzAutomaticDST" data-setting="tz_automatic_dst"></select>
|
||||||
|
<label for="tzAutomaticDST">
|
||||||
|
<span data-i18n="tzAutomaticDST"></span>
|
||||||
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="tzAutomaticDSTHelp"></div>
|
||||||
|
</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="gpsHead"></div>
|
<div class="spacer_box_title" data-i18n="gpsHead"></div>
|
||||||
|
@ -80,18 +150,23 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="cf_column threefourth_left">
|
<div class="cf_column twothird">
|
||||||
<div class="gui_box grey gps_map">
|
<div class="gui_box grey gps_map">
|
||||||
<div class="gui_box_titlebar" style="margin-bottom: 0;">
|
<div class="gui_box_titlebar" style="margin-bottom: 0;">
|
||||||
<div class="spacer_box_title" data-i18n="gpsMapHead"></div>
|
<div class="spacer_box_title" data-i18n="gpsMapHead"></div>
|
||||||
</div>
|
</div>
|
||||||
<div id="loadmap">
|
<div id="loadmap">
|
||||||
<div style="height:100%" id="gps-map">
|
<div style="height:100%" id="gps-map">
|
||||||
<button class="map-button" id="center_button" data-i18n="gps_map_center"></button>
|
<button class="map-button" id="center_button" data-i18n="gps_map_center"></button>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
<div class="content_toolbar">
|
||||||
</div>
|
<div class="btn save_btn">
|
||||||
|
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
119
tabs/gps.js
119
tabs/gps.js
|
@ -1,3 +1,4 @@
|
||||||
|
/*global $,MSPChainerClass,googleAnalytics,mspHelper,MSPCodes,GUI,chrome,MSP,TABS,Settings,helper,ol*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
TABS.gps = {};
|
TABS.gps = {};
|
||||||
|
@ -8,11 +9,48 @@ TABS.gps.initialize = function (callback) {
|
||||||
googleAnalytics.sendAppView('GPS');
|
googleAnalytics.sendAppView('GPS');
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_html() {
|
var loadChainer = new MSPChainerClass();
|
||||||
GUI.load("./tabs/gps.html", process_html);
|
|
||||||
|
var loadChain = [
|
||||||
|
mspHelper.loadFeatures,
|
||||||
|
mspHelper.loadMiscV2
|
||||||
|
];
|
||||||
|
|
||||||
|
loadChainer.setChain(loadChain);
|
||||||
|
loadChainer.setExitPoint(load_html);
|
||||||
|
loadChainer.execute();
|
||||||
|
|
||||||
|
var saveChainer = new MSPChainerClass();
|
||||||
|
|
||||||
|
var saveChain = [
|
||||||
|
mspHelper.saveMiscV2,
|
||||||
|
saveSettings,
|
||||||
|
mspHelper.saveToEeprom
|
||||||
|
];
|
||||||
|
|
||||||
|
function saveSettings(onComplete) {
|
||||||
|
Settings.saveInputs().then(onComplete);
|
||||||
}
|
}
|
||||||
|
|
||||||
load_html();
|
saveChainer.setChain(saveChain);
|
||||||
|
saveChainer.setExitPoint(reboot);
|
||||||
|
|
||||||
|
function reboot() {
|
||||||
|
//noinspection JSUnresolvedVariable
|
||||||
|
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||||
|
|
||||||
|
GUI.tab_switch_cleanup(function () {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
|
||||||
|
//noinspection JSUnresolvedVariable
|
||||||
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
|
GUI.handleReconnect($('.tab_gps a'));
|
||||||
|
});
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_html() {
|
||||||
|
GUI.load("./tabs/gps.html", Settings.processHtml(process_html));
|
||||||
|
}
|
||||||
|
|
||||||
let cursorInitialized = false;
|
let cursorInitialized = false;
|
||||||
let iconStyle;
|
let iconStyle;
|
||||||
|
@ -23,6 +61,36 @@ TABS.gps.initialize = function (callback) {
|
||||||
function process_html() {
|
function process_html() {
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
|
var features = FC.getFeatures();
|
||||||
|
|
||||||
|
helper.features.updateUI($('.tab-gps'), FEATURES);
|
||||||
|
|
||||||
|
// generate GPS
|
||||||
|
var gpsProtocols = FC.getGpsProtocols();
|
||||||
|
var gpsSbas = FC.getGpsSbasProviders();
|
||||||
|
|
||||||
|
var gps_protocol_e = $('#gps_protocol');
|
||||||
|
for (i = 0; i < gpsProtocols.length; i++) {
|
||||||
|
gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>');
|
||||||
|
}
|
||||||
|
|
||||||
|
gps_protocol_e.change(function () {
|
||||||
|
MISC.gps_type = parseInt($(this).val());
|
||||||
|
});
|
||||||
|
|
||||||
|
gps_protocol_e.val(MISC.gps_type);
|
||||||
|
|
||||||
|
var gps_ubx_sbas_e = $('#gps_ubx_sbas');
|
||||||
|
for (i = 0; i < gpsSbas.length; i++) {
|
||||||
|
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
|
||||||
|
}
|
||||||
|
|
||||||
|
gps_ubx_sbas_e.change(function () {
|
||||||
|
MISC.gps_ubx_sbas = parseInt($(this).val());
|
||||||
|
});
|
||||||
|
|
||||||
|
gps_ubx_sbas_e.val(MISC.gps_ubx_sbas);
|
||||||
|
|
||||||
let mapView = new ol.View({
|
let mapView = new ol.View({
|
||||||
center: ol.proj.fromLonLat([0, 0]),
|
center: ol.proj.fromLonLat([0, 0]),
|
||||||
zoom: 15
|
zoom: 15
|
||||||
|
@ -36,20 +104,20 @@ TABS.gps.initialize = function (callback) {
|
||||||
imagerySet: 'AerialWithLabels',
|
imagerySet: 'AerialWithLabels',
|
||||||
maxZoom: 19
|
maxZoom: 19
|
||||||
});
|
});
|
||||||
} else if ( globalSettings.mapProviderType == 'mapproxy' ) {
|
} else if (globalSettings.mapProviderType == 'mapproxy') {
|
||||||
mapLayer = new ol.source.TileWMS({
|
mapLayer = new ol.source.TileWMS({
|
||||||
url: globalSettings.proxyURL,
|
url: globalSettings.proxyURL,
|
||||||
params: {'LAYERS':globalSettings.proxyLayer}
|
params: { 'LAYERS': globalSettings.proxyLayer }
|
||||||
})
|
})
|
||||||
} else {
|
} else {
|
||||||
mapLayer = new ol.source.OSM();
|
mapLayer = new ol.source.OSM();
|
||||||
}
|
}
|
||||||
|
|
||||||
$("#center_button").click(function(){
|
$("#center_button").click(function () {
|
||||||
let lat = GPS_DATA.lat / 10000000;
|
let lat = GPS_DATA.lat / 10000000;
|
||||||
let lon = GPS_DATA.lon / 10000000;
|
let lon = GPS_DATA.lon / 10000000;
|
||||||
let center = ol.proj.fromLonLat([lon, lat]);
|
let center = ol.proj.fromLonLat([lon, lat]);
|
||||||
mapView.setCenter(center);
|
mapView.setCenter(center);
|
||||||
});
|
});
|
||||||
|
|
||||||
mapHandler = new ol.Map({
|
mapHandler = new ol.Map({
|
||||||
|
@ -144,7 +212,7 @@ TABS.gps.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
mapHandler.addLayer(currentPositionLayer);
|
mapHandler.addLayer(currentPositionLayer);
|
||||||
|
|
||||||
mapView.setCenter(center);
|
mapView.setCenter(center);
|
||||||
mapView.setZoom(14);
|
mapView.setZoom(14);
|
||||||
}
|
}
|
||||||
|
@ -172,6 +240,29 @@ TABS.gps.initialize = function (callback) {
|
||||||
get_raw_gps_data();
|
get_raw_gps_data();
|
||||||
});
|
});
|
||||||
|
|
||||||
|
|
||||||
|
$('a.save').on('click', function () {
|
||||||
|
if (FC.isFeatureEnabled('GPS', features)) {
|
||||||
|
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
|
||||||
|
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
|
||||||
|
}
|
||||||
|
|
||||||
|
googleAnalytics.sendEvent('Setting', 'GPSEnabled', FC.isFeatureEnabled('GPS', features) ? "true" : "false");
|
||||||
|
|
||||||
|
for (var i = 0; i < features.length; i++) {
|
||||||
|
var featureName = features[i].name;
|
||||||
|
if (FC.isFeatureEnabled(featureName, features)) {
|
||||||
|
googleAnalytics.sendEvent('Setting', 'Feature', featureName);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
helper.features.reset();
|
||||||
|
helper.features.fromUI($('.tab-gps'));
|
||||||
|
helper.features.execute(function () {
|
||||||
|
saveChainer.execute();
|
||||||
|
});
|
||||||
|
});
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*global $,MSP,MSPCodes,BF_CONFIG,TABS,GUI,CONFIGURATOR,helper,mspHelper,nwdialog,SDCARD,chrome*/
|
/*global $,MSP,MSPCodes,TABS,GUI,CONFIGURATOR,helper,mspHelper,nwdialog,SDCARD,chrome*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
var
|
var
|
||||||
|
@ -17,7 +17,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (CONFIGURATOR.connectionValid) {
|
if (CONFIGURATOR.connectionValid) {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() {
|
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, function() {
|
||||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
|
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
|
||||||
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
|
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
|
||||||
MSP.send_message(MSPCodes.MSP2_BLACKBOX_CONFIG, false, false, load_html);
|
MSP.send_message(MSPCodes.MSP2_BLACKBOX_CONFIG, false, false, load_html);
|
||||||
|
@ -59,7 +59,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
||||||
dataflashPresent = DATAFLASH.totalSize > 0,
|
dataflashPresent = DATAFLASH.totalSize > 0,
|
||||||
blackboxSupport = false;
|
blackboxSupport = false;
|
||||||
|
|
||||||
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(BF_CONFIG.features, 19)) {
|
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(FEATURES, 19)) {
|
||||||
blackboxSupport = true;
|
blackboxSupport = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
41
tabs/osd.js
41
tabs/osd.js
|
@ -2011,13 +2011,18 @@ OSD.updateDisplaySize = function () {
|
||||||
video_type = 'PAL';
|
video_type = 'PAL';
|
||||||
}
|
}
|
||||||
|
|
||||||
// save the original OSD element positions.
|
// save the original OSD element positions for all layouts
|
||||||
var origPos = [];
|
var osdLayouts = [];
|
||||||
for (var ii = 0; ii < OSD.data.items.length; ii++) {
|
for (var ii = 0; ii < OSD.data.layout_count; ii++) {
|
||||||
origPos.push(OSD.msp.helpers.pack.position(OSD.data.items[ii]));
|
var items = OSD.data.layouts[ii];
|
||||||
|
var origPos = [];
|
||||||
|
for (var jj = 0; jj < OSD.data.items.length; jj++) {
|
||||||
|
origPos.push(OSD.msp.helpers.pack.position(items[jj]));
|
||||||
|
}
|
||||||
|
osdLayouts.push(origPos);
|
||||||
}
|
}
|
||||||
|
|
||||||
// save the new video type and cols per line
|
// set the new video type and cols per line
|
||||||
FONT.constants.SIZES.LINE = OSD.constants.VIDEO_COLS[video_type];
|
FONT.constants.SIZES.LINE = OSD.constants.VIDEO_COLS[video_type];
|
||||||
OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type;
|
OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type;
|
||||||
|
|
||||||
|
@ -2028,16 +2033,20 @@ OSD.updateDisplaySize = function () {
|
||||||
total: OSD.constants.VIDEO_BUFFER_CHARS[video_type]
|
total: OSD.constants.VIDEO_BUFFER_CHARS[video_type]
|
||||||
};
|
};
|
||||||
|
|
||||||
// recalculate the OSD element positions for the new cols per line
|
// re-calculate the OSD element positions for each layout
|
||||||
for (var ii = 0; ii < OSD.data.items.length; ii++) {
|
for (var ii = 0; ii < OSD.data.layout_count; ii++) {
|
||||||
var item = OSD.msp.helpers.unpack.position(origPos[ii]);
|
var origPos = osdLayouts[ii];
|
||||||
// do not recalculate anything not visible or outside of the screen
|
var items = OSD.data.layouts[ii];
|
||||||
if (item.isVisible && item.x < OSD.data.display_size.x && item.y < OSD.data.display_size.y) {
|
for (var jj = 0; jj < OSD.data.item_count; jj++) {
|
||||||
OSD.data.items[ii] = item;
|
var item = OSD.msp.helpers.unpack.position(origPos[jj]);
|
||||||
}
|
// leave element alone if outside of screen (enable and disable element to relocate to 0,0)
|
||||||
}
|
if (item.x < OSD.data.display_size.x && item.y < OSD.data.display_size.y) {
|
||||||
|
items[jj] = item;
|
||||||
// set the preview size
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// set the preview size based on the video type
|
||||||
$('.third_left').toggleClass('preview_hd_side', (video_type == 'HD'))
|
$('.third_left').toggleClass('preview_hd_side', (video_type == 'HD'))
|
||||||
$('.preview').toggleClass('preview_hd cut43_left', (video_type == 'HD'))
|
$('.preview').toggleClass('preview_hd cut43_left', (video_type == 'HD'))
|
||||||
$('.third_right').toggleClass('preview_hd_side', (video_type == 'HD'))
|
$('.third_right').toggleClass('preview_hd_side', (video_type == 'HD'))
|
||||||
|
@ -2094,7 +2103,7 @@ OSD.msp = {
|
||||||
},
|
},
|
||||||
pack: {
|
pack: {
|
||||||
position: function (display_item) {
|
position: function (display_item) {
|
||||||
return (display_item.isVisible ? 0x2000 : 0)
|
return (display_item.isVisible ? OSD.constants.VISIBLE : 0)
|
||||||
| ((display_item.y & 0x3F) << 6) | (display_item.x & 0x3F);
|
| ((display_item.y & 0x3F) << 6) | (display_item.x & 0x3F);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*global helper,MSP,MSPChainerClass,googleAnalytics,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM_MULTIROTOR,BF_CONFIG,PLATFORM_TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
|
/*global helper,MSP,MSPChainerClass,googleAnalytics,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM_MULTIROTOR,PLATFORM_TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
TABS.outputs = {
|
TABS.outputs = {
|
||||||
|
@ -24,7 +24,7 @@ TABS.outputs.initialize = function (callback) {
|
||||||
|
|
||||||
loadChainer.setChain([
|
loadChainer.setChain([
|
||||||
mspHelper.loadMiscV2,
|
mspHelper.loadMiscV2,
|
||||||
mspHelper.loadBfConfig,
|
mspHelper.loadFeatures,
|
||||||
mspHelper.load3dConfig,
|
mspHelper.load3dConfig,
|
||||||
mspHelper.loadMotors,
|
mspHelper.loadMotors,
|
||||||
mspHelper.loadMotorMixRules,
|
mspHelper.loadMotorMixRules,
|
||||||
|
@ -46,7 +46,6 @@ TABS.outputs.initialize = function (callback) {
|
||||||
saveSettings,
|
saveSettings,
|
||||||
mspHelper.sendServoConfigurations,
|
mspHelper.sendServoConfigurations,
|
||||||
mspHelper.saveAdvancedConfig,
|
mspHelper.saveAdvancedConfig,
|
||||||
mspHelper.saveBfConfig,
|
|
||||||
mspHelper.saveMiscV2,
|
mspHelper.saveMiscV2,
|
||||||
mspHelper.saveToEeprom
|
mspHelper.saveToEeprom
|
||||||
]);
|
]);
|
||||||
|
@ -65,7 +64,7 @@ TABS.outputs.initialize = function (callback) {
|
||||||
|
|
||||||
function onLoad() {
|
function onLoad() {
|
||||||
|
|
||||||
self.feature3DEnabled = bit_check(BF_CONFIG.features, 12);
|
self.feature3DEnabled = bit_check(FEATURES, 12);
|
||||||
|
|
||||||
process_motors();
|
process_motors();
|
||||||
process_servos();
|
process_servos();
|
||||||
|
@ -193,7 +192,7 @@ TABS.outputs.initialize = function (callback) {
|
||||||
|
|
||||||
$('#servo-rate-container').show();
|
$('#servo-rate-container').show();
|
||||||
|
|
||||||
helper.features.updateUI($('.tab-motors'), BF_CONFIG.features);
|
helper.features.updateUI($('.tab-motors'), FEATURES);
|
||||||
GUI.simpleBind();
|
GUI.simpleBind();
|
||||||
|
|
||||||
let $reversibleMotorCheckbox = $('#feature-12');
|
let $reversibleMotorCheckbox = $('#feature-12');
|
||||||
|
|
|
@ -15,7 +15,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
mspHelper.loadINAVPidConfig,
|
mspHelper.loadINAVPidConfig,
|
||||||
mspHelper.loadPidAdvanced,
|
mspHelper.loadPidAdvanced,
|
||||||
mspHelper.loadFilterConfig,
|
mspHelper.loadFilterConfig,
|
||||||
mspHelper.loadBfConfig
|
mspHelper.loadFeatures
|
||||||
];
|
];
|
||||||
loadChain.push(mspHelper.loadRateProfileData);
|
loadChain.push(mspHelper.loadRateProfileData);
|
||||||
|
|
||||||
|
@ -101,7 +101,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
if (have_sensor(sensors_detected, 'mag')) {
|
if (have_sensor(sensors_detected, 'mag')) {
|
||||||
$('#pid_mag').show();
|
$('#pid_mag').show();
|
||||||
}
|
}
|
||||||
if (bit_check(BF_CONFIG.features, 7)) { //This will need to be reworked to remove BF_CONFIG reference eventually
|
if (bit_check(FEATURES, 7)) {
|
||||||
$('#pid_gps').show();
|
$('#pid_gps').show();
|
||||||
}
|
}
|
||||||
if (have_sensor(sensors_detected, 'sonar')) {
|
if (have_sensor(sensors_detected, 'sonar')) {
|
||||||
|
@ -132,7 +132,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
helper.tabs.init($('.tab-pid_tuning'));
|
helper.tabs.init($('.tab-pid_tuning'));
|
||||||
helper.features.updateUI($('.tab-pid_tuning'), BF_CONFIG.features);
|
helper.features.updateUI($('.tab-pid_tuning'), FEATURES);
|
||||||
|
|
||||||
hideUnusedPids(CONFIG.activeSensors);
|
hideUnusedPids(CONFIG.activeSensors);
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
/*global $,chrome,FC,helper,mspHelper,MIXER_CONFIG,BF_CONFIG*/
|
/*global $,chrome,FC,helper,mspHelper,MIXER_CONFIG*/
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
TABS.setup = {
|
TABS.setup = {
|
||||||
|
@ -22,12 +22,12 @@ TABS.setup.initialize = function (callback) {
|
||||||
var loadChainer = new MSPChainerClass();
|
var loadChainer = new MSPChainerClass();
|
||||||
|
|
||||||
var loadChain = [
|
var loadChain = [
|
||||||
mspHelper.loadBfConfig,
|
mspHelper.loadFeatures,
|
||||||
mspHelper.queryFcStatus,
|
mspHelper.queryFcStatus,
|
||||||
mspHelper.loadMixerConfig
|
mspHelper.loadMixerConfig,
|
||||||
|
mspHelper.loadMiscV2
|
||||||
];
|
];
|
||||||
|
|
||||||
loadChain.push(mspHelper.loadMiscV2);
|
|
||||||
loadChainer.setChain(loadChain);
|
loadChainer.setChain(loadChain);
|
||||||
loadChainer.setExitPoint(load_html);
|
loadChainer.setExitPoint(load_html);
|
||||||
loadChainer.execute();
|
loadChainer.execute();
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue