mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-19 14:25:13 +03:00
Merge branch 'master' into MrD-Add-switch-indicators-to-OSD
This commit is contained in:
commit
28e06b9149
20 changed files with 666 additions and 477 deletions
|
@ -1143,6 +1143,9 @@
|
||||||
"portsFunction_DJI_FPV": {
|
"portsFunction_DJI_FPV": {
|
||||||
"message": "DJI FPV VTX"
|
"message": "DJI FPV VTX"
|
||||||
},
|
},
|
||||||
|
"portsFunction_HDZERO_VTX": {
|
||||||
|
"message": "HDZero VTX"
|
||||||
|
},
|
||||||
"portsFunction_IMU2": {
|
"portsFunction_IMU2": {
|
||||||
"message": "Secondary IMU"
|
"message": "Secondary IMU"
|
||||||
},
|
},
|
||||||
|
@ -3604,9 +3607,6 @@
|
||||||
"platformConfiguration": {
|
"platformConfiguration": {
|
||||||
"message": "Platform configuration"
|
"message": "Platform configuration"
|
||||||
},
|
},
|
||||||
"platformHasFlaps": {
|
|
||||||
"message": "Has flaps"
|
|
||||||
},
|
|
||||||
"mixerPreset": {
|
"mixerPreset": {
|
||||||
"message": "Mixer preset"
|
"message": "Mixer preset"
|
||||||
},
|
},
|
||||||
|
|
|
@ -2,7 +2,7 @@
|
||||||
|
|
||||||
var CONFIGURATOR = {
|
var CONFIGURATOR = {
|
||||||
// all versions are specified and compared using semantic versioning http://semver.org/
|
// all versions are specified and compared using semantic versioning http://semver.org/
|
||||||
'minfirmwareVersionAccepted': '3.0.0',
|
'minfirmwareVersionAccepted': '4.1.0',
|
||||||
'maxFirmwareVersionAccepted': '6.0.0', // Condition is < (lt) so we accept all in 4.x branch
|
'maxFirmwareVersionAccepted': '6.0.0', // Condition is < (lt) so we accept all in 4.x branch
|
||||||
'connectionValid': false,
|
'connectionValid': false,
|
||||||
'connectionValidCliOnly': false,
|
'connectionValidCliOnly': false,
|
||||||
|
|
|
@ -13,6 +13,7 @@ helper.defaultsDialog = (function () {
|
||||||
|
|
||||||
let data = [{
|
let data = [{
|
||||||
"title": 'Mini Quad with 3"-7" propellers',
|
"title": 'Mini Quad with 3"-7" propellers',
|
||||||
|
"id": 2,
|
||||||
"notRecommended": false,
|
"notRecommended": false,
|
||||||
"reboot": true,
|
"reboot": true,
|
||||||
"settings": [
|
"settings": [
|
||||||
|
@ -89,6 +90,10 @@ helper.defaultsDialog = (function () {
|
||||||
key: "airmode_type",
|
key: "airmode_type",
|
||||||
value: "THROTTLE_THRESHOLD"
|
value: "THROTTLE_THRESHOLD"
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "airmode_throttle_threshold",
|
||||||
|
value: 1150
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "mc_iterm_relax",
|
key: "mc_iterm_relax",
|
||||||
value: "RP"
|
value: "RP"
|
||||||
|
@ -578,6 +583,7 @@ helper.defaultsDialog = (function () {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"title": 'Rovers & Boats',
|
"title": 'Rovers & Boats',
|
||||||
|
"id": 1,
|
||||||
"notRecommended": false,
|
"notRecommended": false,
|
||||||
"reboot": true,
|
"reboot": true,
|
||||||
"settings": [
|
"settings": [
|
||||||
|
@ -641,6 +647,7 @@ helper.defaultsDialog = (function () {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
"title": 'Keep current settings (Not recommended)',
|
"title": 'Keep current settings (Not recommended)',
|
||||||
|
"id": 0,
|
||||||
"notRecommended": true,
|
"notRecommended": true,
|
||||||
"reboot": false,
|
"reboot": false,
|
||||||
"settings": [
|
"settings": [
|
||||||
|
@ -721,6 +728,11 @@ helper.defaultsDialog = (function () {
|
||||||
let selectedDefaultPreset = data[$(event.currentTarget).data("index")];
|
let selectedDefaultPreset = data[$(event.currentTarget).data("index")];
|
||||||
if (selectedDefaultPreset && selectedDefaultPreset.settings) {
|
if (selectedDefaultPreset && selectedDefaultPreset.settings) {
|
||||||
|
|
||||||
|
if (selectedDefaultPreset.id == 0) {
|
||||||
|
// Close applying preset dialog if keeping current settings.
|
||||||
|
savingDefaultsModal.close();
|
||||||
|
}
|
||||||
|
|
||||||
mspHelper.loadBfConfig(function () {
|
mspHelper.loadBfConfig(function () {
|
||||||
privateScope.setFeaturesBits(selectedDefaultPreset)
|
privateScope.setFeaturesBits(selectedDefaultPreset)
|
||||||
});
|
});
|
||||||
|
|
121
js/fc.js
121
js/fc.js
|
@ -30,7 +30,7 @@ var CONFIG,
|
||||||
MOTOR_DATA,
|
MOTOR_DATA,
|
||||||
SERVO_DATA,
|
SERVO_DATA,
|
||||||
GPS_DATA,
|
GPS_DATA,
|
||||||
MISSION_PLANER,
|
MISSION_PLANNER,
|
||||||
ANALOG,
|
ANALOG,
|
||||||
ARMING_CONFIG,
|
ARMING_CONFIG,
|
||||||
FC_CONFIG,
|
FC_CONFIG,
|
||||||
|
@ -246,7 +246,7 @@ var FC = {
|
||||||
packetCount: 0
|
packetCount: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
/* MISSION_PLANER = {
|
/* MISSION_PLANNER = {
|
||||||
maxWaypoints: 0,
|
maxWaypoints: 0,
|
||||||
isValidMission: 0,
|
isValidMission: 0,
|
||||||
countBusyPoints: 0,
|
countBusyPoints: 0,
|
||||||
|
@ -263,7 +263,7 @@ var FC = {
|
||||||
}
|
}
|
||||||
}; */
|
}; */
|
||||||
|
|
||||||
MISSION_PLANER = new WaypointCollection();
|
MISSION_PLANNER = new WaypointCollection();
|
||||||
|
|
||||||
ANALOG = {
|
ANALOG = {
|
||||||
voltage: 0,
|
voltage: 0,
|
||||||
|
@ -999,7 +999,7 @@ var FC = {
|
||||||
'RC Channel 8', // 11
|
'RC Channel 8', // 11
|
||||||
'Gimbal Pitch', // 12
|
'Gimbal Pitch', // 12
|
||||||
'Gimbal Roll', // 13
|
'Gimbal Roll', // 13
|
||||||
'Flaps', // 14
|
'Flaperon Mode', // 14
|
||||||
'RC Channel 9', // 15
|
'RC Channel 9', // 15
|
||||||
'RC Channel 10', // 16
|
'RC Channel 10', // 16
|
||||||
'RC Channel 11', // 17
|
'RC Channel 11', // 17
|
||||||
|
@ -1045,215 +1045,269 @@ var FC = {
|
||||||
return {
|
return {
|
||||||
0: {
|
0: {
|
||||||
name: "True",
|
name: "True",
|
||||||
|
operandType: "Active",
|
||||||
hasOperand: [false, false],
|
hasOperand: [false, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
1: {
|
1: {
|
||||||
name: "Equal",
|
name: "Equal",
|
||||||
|
operandType: "Comparison",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
2: {
|
2: {
|
||||||
name: "Greater Than",
|
name: "Greater Than",
|
||||||
|
operandType: "Comparison",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
3: {
|
3: {
|
||||||
name: "Lower Than",
|
name: "Lower Than",
|
||||||
|
operandType: "Comparison",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
4: {
|
4: {
|
||||||
name: "Low",
|
name: "Low",
|
||||||
|
operandType: "RC Switch Check",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
5: {
|
5: {
|
||||||
name: "Mid",
|
name: "Mid",
|
||||||
|
operandType: "RC Switch Check",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
6: {
|
6: {
|
||||||
name: "High",
|
name: "High",
|
||||||
|
operandType: "RC Switch Check",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
7: {
|
7: {
|
||||||
name: "AND",
|
name: "AND",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
8: {
|
8: {
|
||||||
name: "OR",
|
name: "OR",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
9: {
|
9: {
|
||||||
name: "XOR",
|
name: "XOR",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
10: {
|
10: {
|
||||||
name: "NAND",
|
name: "NAND",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
11: {
|
11: {
|
||||||
name: "NOR",
|
name: "NOR",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
12: {
|
12: {
|
||||||
name: "NOT",
|
name: "NOT",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
13: {
|
13: {
|
||||||
name: "STICKY",
|
name: "Sticky",
|
||||||
|
operandType: "Logic Switches",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
14: {
|
14: {
|
||||||
name: "ADD",
|
name: "Basic: Add",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
15: {
|
15: {
|
||||||
name: "SUB",
|
name: "Basic: Subtract",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
16: {
|
16: {
|
||||||
name: "MUL",
|
name: "Basic: Multiply",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
17: {
|
17: {
|
||||||
name: "DIV",
|
name: "Basic: Divide",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
40: {
|
40: {
|
||||||
name: "MOD",
|
name: "Modulo",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
18: {
|
18: {
|
||||||
name: "GVAR SET",
|
name: "Set GVAR",
|
||||||
|
operandType: "Variables",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "none"
|
output: "none"
|
||||||
},
|
},
|
||||||
19: {
|
19: {
|
||||||
name: "GVAR INC",
|
name: "Increase GVAR",
|
||||||
|
operandType: "Variables",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "none"
|
output: "none"
|
||||||
},
|
},
|
||||||
20: {
|
20: {
|
||||||
name: "GVAR DEC",
|
name: "Decrease GVAR",
|
||||||
|
operandType: "Variables",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "none"
|
output: "none"
|
||||||
},
|
},
|
||||||
21: {
|
21: {
|
||||||
name: "IO PORT SET",
|
name: "Set IO Port",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "none"
|
output: "none"
|
||||||
},
|
},
|
||||||
22: {
|
22: {
|
||||||
name: "OVERRIDE ARMING SAFETY",
|
name: "Override Arming Safety",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [false, false],
|
hasOperand: [false, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
23: {
|
23: {
|
||||||
name: "OVERRIDE THROTTLE SCALE",
|
name: "Override Throttle Scale",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
29: {
|
29: {
|
||||||
name: "OVERRIDE THROTTLE",
|
name: "Override Throttle",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
24: {
|
24: {
|
||||||
name: "SWAP ROLL & YAW",
|
name: "Swap Roll & Yaw",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [false, false],
|
hasOperand: [false, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
25: {
|
25: {
|
||||||
name: "SET VTX POWER LEVEL",
|
name: "Set VTx Power Level",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
30: {
|
30: {
|
||||||
name: "SET VTX BAND",
|
name: "Set VTx Band",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
31: {
|
31: {
|
||||||
name: "SET VTX CHANNEL",
|
name: "Set VTx Channel",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
26: {
|
26: {
|
||||||
name: "INVERT ROLL",
|
name: "Invert Roll",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [false, false],
|
hasOperand: [false, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
27: {
|
27: {
|
||||||
name: "INVERT PITCH",
|
name: "Invert Pitch",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [false, false],
|
hasOperand: [false, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
28: {
|
28: {
|
||||||
name: "INVERT YAW",
|
name: "Invert Yaw",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [false, false],
|
hasOperand: [false, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
32: {
|
32: {
|
||||||
name: "SET OSD LAYOUT",
|
name: "Set OSD Layout",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
33: {
|
33: {
|
||||||
name: "SIN",
|
name: "Trigonometry: Sine",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
34: {
|
34: {
|
||||||
name: "COS",
|
name: "Trigonometry: Cosine",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
35: {
|
35: {
|
||||||
name: "TAN",
|
name: "Trigonometry: Tangent",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
36: {
|
36: {
|
||||||
name: "MAP INPUT",
|
name: "Map Input",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
37: {
|
37: {
|
||||||
name: "MAP OUTPUT",
|
name: "Map Output",
|
||||||
|
operandType: "Maths",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "raw"
|
output: "raw"
|
||||||
},
|
},
|
||||||
38: {
|
38: {
|
||||||
name: "RC CHANNEL OVERRIDE",
|
name: "Override RC Channel",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
|
|
||||||
41: {
|
41: {
|
||||||
name: "LOITER RADIUS OVERRIDE",
|
name: "Override Loiter Radius",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
42: {
|
42: {
|
||||||
name: "SET PROFILE",
|
name: "Set Profile",
|
||||||
|
operandType: "Set Flight Parameter",
|
||||||
hasOperand: [true, false],
|
hasOperand: [true, false],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
|
43: {
|
||||||
|
name: "Use Lowest Value",
|
||||||
|
operandType: "Comparison",
|
||||||
|
hasOperand: [true, true],
|
||||||
|
output: "raw"
|
||||||
|
},
|
||||||
|
44: {
|
||||||
|
name: "Use Highest Value",
|
||||||
|
operandType: "Comparison",
|
||||||
|
hasOperand: [true, true],
|
||||||
|
output: "raw"
|
||||||
|
},
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
getOperandTypes: function () {
|
getOperandTypes: function () {
|
||||||
|
@ -1314,6 +1368,7 @@ var FC = {
|
||||||
34: "GPS Valid Fix",
|
34: "GPS Valid Fix",
|
||||||
35: "Loiter Radius [cm]",
|
35: "Loiter Radius [cm]",
|
||||||
36: "Active Profile",
|
36: "Active Profile",
|
||||||
|
37: "Battery cells",
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
3: {
|
3: {
|
||||||
|
|
|
@ -256,16 +256,55 @@ let LogicCondition = function (enabled, activatorId, operation, operandAType, op
|
||||||
$row.find('.logic_cell__operation').html("<select class='logic_element__operation' ></select>");
|
$row.find('.logic_cell__operation').html("<select class='logic_element__operation' ></select>");
|
||||||
let $t = $row.find('.logic_element__operation');
|
let $t = $row.find('.logic_element__operation');
|
||||||
|
|
||||||
for (let k in FC.getLogicOperators()) {
|
let lcOperators = [];
|
||||||
if (FC.getLogicOperators().hasOwnProperty(k)) {
|
|
||||||
let o = FC.getLogicOperators()[k];
|
for (let lcID in FC.getLogicOperators()) {
|
||||||
if (self.getOperation() == parseInt(k, 10)) {
|
if (FC.getLogicOperators().hasOwnProperty(lcID)) {
|
||||||
$t.append('<option value="' + k + '" selected>' + o.name + '</option>');
|
let op = FC.getLogicOperators()[lcID];
|
||||||
|
lcOperators[parseInt(lcID, 10)] = {
|
||||||
|
id: parseInt(lcID, 10),
|
||||||
|
name: op.name,
|
||||||
|
operandType: op.operandType,
|
||||||
|
hasOperand: op.hasOperand,
|
||||||
|
output: op.output
|
||||||
|
};
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
lcOperators.sort((a, b) => {
|
||||||
|
let lcAT = a.operandType.toLowerCase(),
|
||||||
|
lcBT = b.operandType.toLowerCase(),
|
||||||
|
lcAN = a.name.toLowerCase(),
|
||||||
|
lcBN = b.name.toLowerCase();
|
||||||
|
|
||||||
|
if (lcAT == lcBT) {
|
||||||
|
return (lcAN < lcBN) ? -1 : (lcAN > lcBN) ? 1 : 0;
|
||||||
} else {
|
} else {
|
||||||
$t.append('<option value="' + k + '">' + o.name + '</option>');
|
return (lcAT < lcBT) ? -1 : 1;
|
||||||
}
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
let section = "";
|
||||||
|
|
||||||
|
lcOperators.forEach( val => {
|
||||||
|
if (section != val.operandType) {
|
||||||
|
if (section != "") {
|
||||||
|
$t.append('</optgroup>');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
section = val.operandType;
|
||||||
|
$t.append('<optgroup label="** ' + val.operandType + ' **">');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (self.getOperation() == val.id) {
|
||||||
|
$t.append('<option value="' + val.id + '" selected>' + val.name + '</option>');
|
||||||
|
} else {
|
||||||
|
$t.append('<option value="' + val.id + '">' + val.name + '</option>');
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
$t.append('</optgroup>');
|
||||||
|
|
||||||
$t.change(self.onOperatorChange);
|
$t.change(self.onOperatorChange);
|
||||||
|
|
||||||
self.renderOperand(0);
|
self.renderOperand(0);
|
||||||
|
|
60
js/model.js
60
js/model.js
|
@ -2,10 +2,12 @@
|
||||||
|
|
||||||
const SERVO_GIMBAL_PITCH = 0,
|
const SERVO_GIMBAL_PITCH = 0,
|
||||||
SERVO_GIMBAL_ROLL = 1,
|
SERVO_GIMBAL_ROLL = 1,
|
||||||
SERVO_ELEVATOR = 2,
|
SERVO_ELEVATOR = 1,
|
||||||
SERVO_FLAPPERON_1 = 3,
|
SERVO_ELEVON_1 = 1,
|
||||||
SERVO_FLAPPERON_2 = 4,
|
SERVO_ELEVON_2 = 2,
|
||||||
SERVO_RUDDER = 5,
|
SERVO_FLAPPERON_1 = 2,
|
||||||
|
SERVO_FLAPPERON_2 = 3,
|
||||||
|
SERVO_RUDDER = 4,
|
||||||
SERVO_BICOPTER_LEFT = 4,
|
SERVO_BICOPTER_LEFT = 4,
|
||||||
SERVO_BICOPTER_RIGHT = 5,
|
SERVO_BICOPTER_RIGHT = 5,
|
||||||
SERVO_DUALCOPTER_LEFT = 4,
|
SERVO_DUALCOPTER_LEFT = 4,
|
||||||
|
@ -162,10 +164,10 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
]
|
]
|
||||||
}, // 8
|
}, // 8
|
||||||
{
|
{
|
||||||
|
@ -181,10 +183,10 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
|
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
|
||||||
],
|
],
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
]
|
]
|
||||||
}, // 27
|
}, // 27
|
||||||
{
|
{
|
||||||
|
@ -289,6 +291,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: true,
|
legacy: true,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
|
@ -296,9 +299,9 @@ const mixerList = [
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),
|
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),
|
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
|
||||||
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
]
|
]
|
||||||
}, // 14
|
}, // 14
|
||||||
|
@ -448,6 +451,7 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, -0.3)
|
new MotorMixRule(1.0, 0.0, 0.0, -0.3)
|
||||||
|
@ -455,9 +459,9 @@ const mixerList = [
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),
|
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),
|
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
|
||||||
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
|
@ -469,16 +473,19 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
|
new ServoMixRule(1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
new ServoMixRule(2, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_ROLL, 100, 0),
|
/*new ServoMixRule(2, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
new ServoMixRule(4, INPUT_STABILIZED_PITCH, 50, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
|
||||||
new ServoMixRule(5, INPUT_STABILIZED_PITCH, -50, 0),
|
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
|
||||||
new ServoMixRule(5, INPUT_STABILIZED_YAW, -50, 0)
|
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -493,11 +500,11 @@ const mixerList = [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(2, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_PITCH, 50, 0),
|
new ServoMixRule(2, INPUT_STABILIZED_PITCH, 50, 0),
|
||||||
|
new ServoMixRule(2, INPUT_STABILIZED_YAW, -50, 0),
|
||||||
|
new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0),
|
||||||
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
|
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
|
||||||
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
|
|
||||||
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0),
|
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -508,13 +515,16 @@ const mixerList = [
|
||||||
enabled: true,
|
enabled: true,
|
||||||
legacy: false,
|
legacy: false,
|
||||||
platform: PLATFORM_AIRPLANE,
|
platform: PLATFORM_AIRPLANE,
|
||||||
|
hasFlaps: true,
|
||||||
motorMixer: [
|
motorMixer: [
|
||||||
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
|
||||||
],
|
],
|
||||||
servoMixer: [
|
servoMixer: [
|
||||||
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
|
||||||
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
|
||||||
|
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0),*/
|
||||||
]
|
]
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
|
|
@ -44,6 +44,7 @@ var mspHelper = (function (gui) {
|
||||||
'DJI_FPV': 21,
|
'DJI_FPV': 21,
|
||||||
'SMARTPORT_MASTER': 23,
|
'SMARTPORT_MASTER': 23,
|
||||||
'IMU2': 24,
|
'IMU2': 24,
|
||||||
|
'HDZERO_VTX': 25,
|
||||||
};
|
};
|
||||||
|
|
||||||
// Required for MSP_DEBUGMSG because console.log() doesn't allow omitting
|
// Required for MSP_DEBUGMSG because console.log() doesn't allow omitting
|
||||||
|
@ -447,7 +448,7 @@ var mspHelper = (function (gui) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_WP:
|
case MSPCodes.MSP_WP:
|
||||||
MISSION_PLANER.put(new Waypoint(
|
MISSION_PLANNER.put(new Waypoint(
|
||||||
data.getUint8(0),
|
data.getUint8(0),
|
||||||
data.getUint8(1),
|
data.getUint8(1),
|
||||||
data.getInt32(2, true),
|
data.getInt32(2, true),
|
||||||
|
@ -1422,9 +1423,9 @@ var mspHelper = (function (gui) {
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_WP_GETINFO:
|
case MSPCodes.MSP_WP_GETINFO:
|
||||||
// Reserved for waypoint capabilities data.getUint8(0);
|
// Reserved for waypoint capabilities data.getUint8(0);
|
||||||
MISSION_PLANER.setMaxWaypoints(data.getUint8(1));
|
MISSION_PLANNER.setMaxWaypoints(data.getUint8(1));
|
||||||
MISSION_PLANER.setValidMission(data.getUint8(2));
|
MISSION_PLANNER.setValidMission(data.getUint8(2));
|
||||||
MISSION_PLANER.setCountBusyPoints(data.getUint8(3));
|
MISSION_PLANNER.setCountBusyPoints(data.getUint8(3));
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_WP:
|
case MSPCodes.MSP_SET_WP:
|
||||||
console.log('Point saved');
|
console.log('Point saved');
|
||||||
|
@ -2988,14 +2989,14 @@ var mspHelper = (function (gui) {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadWaypoints = function (callback) {
|
self.loadWaypoints = function (callback) {
|
||||||
MISSION_PLANER.reinit();
|
MISSION_PLANNER.reinit();
|
||||||
let waypointId = 0;
|
let waypointId = 0;
|
||||||
let startTime = new Date().getTime();
|
let startTime = new Date().getTime();
|
||||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, loadWaypoint);
|
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, loadWaypoint);
|
||||||
|
|
||||||
function loadWaypoint() {
|
function loadWaypoint() {
|
||||||
waypointId++;
|
waypointId++;
|
||||||
if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
|
if (waypointId < MISSION_PLANNER.getCountBusyPoints()) {
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, loadWaypoint);
|
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, loadWaypoint);
|
||||||
} else {
|
} else {
|
||||||
GUI.log('Receive time: ' + (new Date().getTime() - startTime) + 'ms');
|
GUI.log('Receive time: ' + (new Date().getTime() - startTime) + 'ms');
|
||||||
|
@ -3011,11 +3012,11 @@ var mspHelper = (function (gui) {
|
||||||
|
|
||||||
function sendWaypoint() {
|
function sendWaypoint() {
|
||||||
waypointId++;
|
waypointId++;
|
||||||
if (waypointId < MISSION_PLANER.get().length) {
|
if (waypointId < MISSION_PLANNER.get().length) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, sendWaypoint);
|
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANNER.extractBuffer(waypointId), false, sendWaypoint);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, endMission);
|
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANNER.extractBuffer(waypointId), false, endMission);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -72,6 +72,14 @@ var Settings = (function () {
|
||||||
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
||||||
input.attr('type', 'number');
|
input.attr('type', 'number');
|
||||||
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
|
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
|
||||||
|
|
||||||
|
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
|
||||||
|
input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier)));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (typeof s.setting.max !== 'undefined' && s.setting.max !== null) {
|
||||||
|
input.attr('max', (s.setting.max / multiplier).toFixed(Math.log10(multiplier)));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// If data is defined, We want to convert this value into
|
// If data is defined, We want to convert this value into
|
||||||
|
|
|
@ -203,7 +203,7 @@
|
||||||
height: 100%;
|
height: 100%;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* #missionPlanerElevation {
|
/* #missionPlannerElevation {
|
||||||
height: 40%;
|
height: 40%;
|
||||||
} */
|
} */
|
||||||
|
|
||||||
|
|
|
@ -84,6 +84,12 @@
|
||||||
}
|
}
|
||||||
|
|
||||||
.mixer_btn_add {
|
.mixer_btn_add {
|
||||||
|
float: right;
|
||||||
|
margin: 15px 0 10px;
|
||||||
|
}
|
||||||
|
|
||||||
|
.mixer_btn_logic {
|
||||||
|
float: left;
|
||||||
margin: 15px 0 10px;
|
margin: 15px 0 10px;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -415,8 +415,42 @@ button {
|
||||||
border-bottom: 0;
|
border-bottom: 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.tab-osd .third_left {
|
||||||
|
float: left;
|
||||||
|
width: calc(50% - 197px);
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-osd .third_right {
|
||||||
|
float: right;
|
||||||
|
width: calc(50% - 197px);
|
||||||
|
}
|
||||||
|
|
||||||
.tab-osd .preview {
|
.tab-osd .preview {
|
||||||
width: 360px;
|
width: 360px;
|
||||||
|
left: calc(50% - 197px);
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-osd .preview_hd {
|
||||||
|
width: 600px !important;
|
||||||
|
left: calc(50% - 317px) !important;
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-osd .hd_43_left {
|
||||||
|
border-left: 1px solid red;
|
||||||
|
position: absolute;
|
||||||
|
left: 60px;
|
||||||
|
height: calc(100% - 27px);
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-osd .hd_43_right {
|
||||||
|
border-right: 1px solid red;
|
||||||
|
position: absolute;
|
||||||
|
right: 60px;
|
||||||
|
height: calc(100% - 27px);
|
||||||
|
}
|
||||||
|
|
||||||
|
.tab-osd .preview_hd_side {
|
||||||
|
width: calc(50% - 317px) !important;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-osd .preview {
|
.tab-osd .preview {
|
||||||
|
|
|
@ -36,32 +36,19 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||||
|
|
||||||
|
// This object separates out the dividers. This is also used to order the modes
|
||||||
const modeSections = {};
|
const modeSections = {};
|
||||||
modeSections["ARM"] = "Arming";
|
modeSections["Arming"] = ["ARM", "PREARM"];
|
||||||
modeSections["ANGLE"] = "Flight Modes";
|
modeSections["Flight Modes"] = ["ANGLE", "HORIZON", "MANUAL"];
|
||||||
modeSections["NAV RTH"] = "Navigation Modes";
|
modeSections["Navigation Modes"] = ["NAV COURSE HOLD", "NAV CRUISE", "NAV POSHOLD", "NAV RTH", "NAV WP", "GCS NAV"];
|
||||||
modeSections["NAV ALTHOLD"] = "Flight Mode Modifiers";
|
modeSections["Flight Mode Modifiers"] = ["NAV ALTHOLD", "HEADING HOLD", "AIR MODE", "SOARING", "SURFACE"];
|
||||||
modeSections["AUTO TUNE"] = "Fixed Wing";
|
modeSections["Fixed Wing"] = ["AUTO TUNE", "SERVO AUTOTRIM", "AUTO LEVEL", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON", "TURN ASSIST"];
|
||||||
modeSections["FPV ANGLE MIX"] = "Multi-rotor";
|
modeSections["Multi-rotor"] = ["FPV ANGLE MIX", "TURTLE", "MC BRAKING", "HEADFREE", "HEADADJ"];
|
||||||
modeSections["OSD OFF"] = "OSD Modes";
|
modeSections["OSD Modes"] = ["OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3"];
|
||||||
modeSections["CAMSTAB"] = "FPV Camera Modes";
|
modeSections["FPV Camera Modes"] = ["CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3"];
|
||||||
modeSections["BEEPER"] = "Misc Modes";
|
modeSections["Misc Modes"] = ["BEEPER", "LEDS OFF", "LIGHTS", "HOME RESET", "WP PLANNER", "BLACKBOX", "FAILSAFE", "KILLSWITCH", "TELEMETRY", "MSP RC OVERRIDE", "USER1", "USER2"];
|
||||||
|
|
||||||
function sort_modes_for_display() {
|
function sort_modes_for_display() {
|
||||||
// This array defines the order that the modes are displayed in the configurator modes page
|
|
||||||
const configuratorBoxOrder = [
|
|
||||||
"ARM", "PREARM", // Arming
|
|
||||||
"ANGLE", "HORIZON", "MANUAL", // Flight modes
|
|
||||||
"NAV RTH", "NAV COURSE HOLD", "NAV CRUISE", "NAV POSHOLD", "NAV WP", "GCS NAV", // Navigation modes
|
|
||||||
"NAV ALTHOLD", "HEADING HOLD", "AIR MODE", "SOARING", "SURFACE", // Flight mode modifiers
|
|
||||||
"AUTO TUNE", "SERVO AUTOTRIM", "AUTO LEVEL", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON", "TURN ASSIST", // Fixed wing specific
|
|
||||||
"FPV ANGLE MIX", "TURTLE", "MC BRAKING", "HEADFREE", "HEADADJ", // Multi-rotor specific
|
|
||||||
"OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3", // OSD
|
|
||||||
"CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3", // FPV Camera
|
|
||||||
"BEEPER", "LEDS OFF", "LIGHTS", "HOME RESET", "WP PLANNER", "BLACKBOX", "FAILSAFE", "KILLSWITCH", // Misc
|
|
||||||
"TELEMETRY", "MSP RC OVERRIDE", "USER1", "USER2"
|
|
||||||
];
|
|
||||||
|
|
||||||
// Sort the modes
|
// Sort the modes
|
||||||
var tmpAUX_CONFIG = [];
|
var tmpAUX_CONFIG = [];
|
||||||
var tmpAUX_CONFIG_IDS =[];
|
var tmpAUX_CONFIG_IDS =[];
|
||||||
|
@ -76,9 +63,11 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
AUX_CONFIG = [];
|
AUX_CONFIG = [];
|
||||||
AUX_CONFIG_IDS = [];
|
AUX_CONFIG_IDS = [];
|
||||||
|
|
||||||
for (i=0; i<configuratorBoxOrder.length; i++) {
|
for (let categoryModesIndex in modeSections) {
|
||||||
|
let categoryModes = modeSections[categoryModesIndex];
|
||||||
|
for (cM=0; cM<categoryModes.length; cM++){
|
||||||
for(j=0; j<tmpAUX_CONFIG.length; j++) {
|
for(j=0; j<tmpAUX_CONFIG.length; j++) {
|
||||||
if (configuratorBoxOrder[i] === tmpAUX_CONFIG[j]) {
|
if (categoryModes[cM] === tmpAUX_CONFIG[j]) {
|
||||||
AUX_CONFIG[sortedID] = tmpAUX_CONFIG[j];
|
AUX_CONFIG[sortedID] = tmpAUX_CONFIG[j];
|
||||||
AUX_CONFIG_IDS[sortedID] = tmpAUX_CONFIG_IDS[j];
|
AUX_CONFIG_IDS[sortedID] = tmpAUX_CONFIG_IDS[j];
|
||||||
ORIG_AUX_CONFIG_IDS[sortedID++] = j;
|
ORIG_AUX_CONFIG_IDS[sortedID++] = j;
|
||||||
|
@ -87,8 +76,9 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// There are modes that are missing from the configuratorBoxOrder array. Add them to the end until they are ordered correctly.
|
// There are modes that are missing from the modeSections object. Add them to the end until they are ordered correctly.
|
||||||
if (tmpAUX_CONFIG.length > AUX_CONFIG.length) {
|
if (tmpAUX_CONFIG.length > AUX_CONFIG.length) {
|
||||||
for (i=0; i<tmpAUX_CONFIG.length; i++) {
|
for (i=0; i<tmpAUX_CONFIG.length; i++) {
|
||||||
found = false;
|
found = false;
|
||||||
|
@ -214,11 +204,23 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
|
|
||||||
configureRangeTemplate(auxChannelCount);
|
configureRangeTemplate(auxChannelCount);
|
||||||
|
|
||||||
var modeTableBodyElement = $('.tab-auxiliary .modes tbody')
|
var modeTableBodyElement = $('.tab-auxiliary .modes tbody');
|
||||||
|
let modeSelectionID = "";
|
||||||
|
let modeSelectionRange = "";
|
||||||
|
|
||||||
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
||||||
|
|
||||||
if (AUX_CONFIG[modeIndex] in modeSections) {
|
// Get current mode category
|
||||||
var newSection = createModeSection(modeSections[AUX_CONFIG[modeIndex]]);
|
for (modeSelectionRange in modeSections) {
|
||||||
|
if (modeSections[modeSelectionRange].indexOf(AUX_CONFIG[modeIndex]) != -1) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Create divider if needed
|
||||||
|
if (modeSelectionRange != modeSelectionID) {
|
||||||
|
modeSelectionID = modeSelectionRange;
|
||||||
|
var newSection = createModeSection(modeSelectionRange);
|
||||||
modeTableBodyElement.append(newSection);
|
modeTableBodyElement.append(newSection);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,11 +1,11 @@
|
||||||
<div class="tab-mission-control">
|
<div class="tab-mission-control">
|
||||||
<div style="padding-top: 20px;padding-left: 20px; padding-right: 20px;position: relative;">
|
<div style="padding-top: 20px;padding-left: 20px; padding-right: 20px;position: relative;">
|
||||||
<div class="tab_title" data-i18n="tabMissionControl">Mission planer</div>
|
<div class="tab_title" data-i18n="tabMissionControl">Mission planner</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_wrapper">
|
<div class="content_wrapper">
|
||||||
<div class="cf_column fourth" id="missionControls">
|
<div class="cf_column fourth" id="missionControls">
|
||||||
<div class="spacer_right">
|
<div class="spacer_right">
|
||||||
<div id="missionPlanerAction" class="gui_box grey">
|
<div id="missionPlannerAction" class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionActionMenuHead">Action Menu</div>
|
<div class="spacer_box_title i18n-replaced" data-i18n="missionActionMenuHead">Action Menu</div>
|
||||||
<div class="btnMenu btnMenuIcon show_btn" id="showHideActionButton">
|
<div class="btnMenu btnMenuIcon show_btn" id="showHideActionButton">
|
||||||
|
@ -38,7 +38,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="missionPlanerTotalInfo" class="gui_box grey">
|
<div id="missionPlannerTotalInfo" class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionTotalInformationHead">Total information</div>
|
<div class="spacer_box_title i18n-replaced" data-i18n="missionTotalInformationHead">Total information</div>
|
||||||
<div class="btnMenu btnMenuIcon show_btn" id="showHideInfoButton">
|
<div class="btnMenu btnMenuIcon show_btn" id="showHideInfoButton">
|
||||||
|
@ -65,7 +65,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="missionPlanerSettings" class="gui_box grey" style="display: none">
|
<div id="missionPlannerSettings" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionDefaultSettingsHead">Default settings</div>
|
<div class="spacer_box_title i18n-replaced" data-i18n="missionDefaultSettingsHead">Default settings</div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
|
@ -129,7 +129,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="missionPlanerHome" class="gui_box grey" style="display: none">
|
<div id="missionPlannerHome" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionHomeHead">Take Off home</div>
|
<div class="spacer_box_title i18n-replaced" data-i18n="missionHomeHead">Take Off home</div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
|
@ -170,7 +170,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div id="missionPlanerSafehome" class="gui_box grey" style="display: none">
|
<div id="missionPlannerSafehome" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionSafehomeHead">Safe Home manager</div>
|
<div class="spacer_box_title i18n-replaced" data-i18n="missionSafehomeHead">Safe Home manager</div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
|
@ -331,7 +331,7 @@
|
||||||
</div>
|
</div>
|
||||||
<div class="cf_column threefourth_left" style="height: 100%;">
|
<div class="cf_column threefourth_left" style="height: 100%;">
|
||||||
<div id="missionMap"></div>
|
<div id="missionMap"></div>
|
||||||
<div id="missionPlanerElevation" class="gui_box grey" style="display: none">
|
<div id="missionPlannerElevation" class="gui_box grey" style="display: none">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title i18n-replaced" data-i18n="missionDefaultElevationHead">Elevation Profile</div>
|
<div class="spacer_box_title i18n-replaced" data-i18n="missionDefaultElevationHead">Elevation Profile</div>
|
||||||
<div class="btnMenu btnMenuIcon save_btn">
|
<div class="btnMenu btnMenuIcon save_btn">
|
||||||
|
|
|
@ -301,9 +301,9 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
//update RTH every 5th GPS update since it really shouldn't change
|
//update RTH every 5th GPS update since it really shouldn't change
|
||||||
if(rthUpdateInterval >= 5)
|
if(rthUpdateInterval >= 5)
|
||||||
{
|
{
|
||||||
MISSION_PLANER.bufferPoint.number = -1; //needed to get point 0 which id RTH
|
MISSION_PLANNER.bufferPoint.number = -1; //needed to get point 0 which id RTH
|
||||||
MSP.send_message(MSPCodes.MSP_WP, mspHelper.crunch(MSPCodes.MSP_WP), false, function rth_update() {
|
MSP.send_message(MSPCodes.MSP_WP, mspHelper.crunch(MSPCodes.MSP_WP), false, function rth_update() {
|
||||||
var coord = ol.proj.fromLonLat([MISSION_PLANER.bufferPoint.lon, MISSION_PLANER.bufferPoint.lat]);
|
var coord = ol.proj.fromLonLat([MISSION_PLANNER.bufferPoint.lon, MISSION_PLANNER.bufferPoint.lat]);
|
||||||
rthGeo.setCoordinates(coord);
|
rthGeo.setCoordinates(coord);
|
||||||
});
|
});
|
||||||
rthUpdateInterval = 0;
|
rthUpdateInterval = 0;
|
||||||
|
@ -433,16 +433,16 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
//
|
//
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
function loadSettings() {
|
function loadSettings() {
|
||||||
chrome.storage.local.get('missionPlanerSettings', function (result) {
|
chrome.storage.local.get('missionPlannerSettings', function (result) {
|
||||||
if (result.missionPlanerSettings) {
|
if (result.missionPlannerSettings) {
|
||||||
settings = result.missionPlanerSettings;
|
settings = result.missionPlannerSettings;
|
||||||
}
|
}
|
||||||
refreshSettings();
|
refreshSettings();
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
function saveSettings() {
|
function saveSettings() {
|
||||||
chrome.storage.local.set({'missionPlanerSettings': settings});
|
chrome.storage.local.set({'missionPlannerSettings': settings});
|
||||||
}
|
}
|
||||||
|
|
||||||
function refreshSettings() {
|
function refreshSettings() {
|
||||||
|
@ -452,7 +452,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function closeSettingsPanel() {
|
function closeSettingsPanel() {
|
||||||
$('#missionPlanerSettings').hide();
|
$('#missionPlannerSettings').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
|
@ -461,7 +461,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
//
|
//
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
function closeSafehomePanel() {
|
function closeSafehomePanel() {
|
||||||
$('#missionPlanerSafehome').hide();
|
$('#missionPlannerSafehome').hide();
|
||||||
cleanSafehomeLayers();
|
cleanSafehomeLayers();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -636,8 +636,8 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
//
|
//
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
function closeHomePanel() {
|
function closeHomePanel() {
|
||||||
$('#missionPlanerHome').hide();
|
$('#missionPlannerHome').hide();
|
||||||
$('#missionPlanerElevation').hide();
|
$('#missionPlannerElevation').hide();
|
||||||
cleanHomeLayers();
|
cleanHomeLayers();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -784,14 +784,14 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
totalmultimissionWPs = multimission.get().length + mission.get().length;
|
totalmultimissionWPs = multimission.get().length + mission.get().length;
|
||||||
$("#updateMultimissionButton").removeClass('disabled');
|
$("#updateMultimissionButton").removeClass('disabled');
|
||||||
$("#setActiveMissionButton").removeClass('disabled');
|
$("#setActiveMissionButton").removeClass('disabled');
|
||||||
$('#missionPlanerElevation').show();
|
$('#missionPlannerElevation').show();
|
||||||
} else {
|
} else {
|
||||||
$('#missionDistance').text('N/A');
|
$('#missionDistance').text('N/A');
|
||||||
totalmultimissionWPs = mission.get().length;
|
totalmultimissionWPs = mission.get().length;
|
||||||
$("#editMission").show();
|
$("#editMission").show();
|
||||||
$("#updateMultimissionButton").addClass('disabled');
|
$("#updateMultimissionButton").addClass('disabled');
|
||||||
$("#setActiveMissionButton").addClass('disabled');
|
$("#setActiveMissionButton").addClass('disabled');
|
||||||
$('#missionPlanerElevation').hide();
|
$('#missionPlannerElevation').hide();
|
||||||
setMultimissionEditControl(true);
|
setMultimissionEditControl(true);
|
||||||
}
|
}
|
||||||
$('#multimissionInfo').text(multimissionCount + ' missions (' + totalmultimissionWPs + '/' + mission.getMaxWaypoints() + ' WPs)');
|
$('#multimissionInfo').text(multimissionCount + ' missions (' + totalmultimissionWPs + '/' + mission.getMaxWaypoints() + ' WPs)');
|
||||||
|
@ -1443,7 +1443,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
button.style = 'background: url(\'../images/CF_settings_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
|
button.style = 'background: url(\'../images/CF_settings_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
|
||||||
|
|
||||||
var handleShowSettings = function () {
|
var handleShowSettings = function () {
|
||||||
$('#missionPlanerSettings').fadeIn(300);
|
$('#missionPlannerSettings').fadeIn(300);
|
||||||
};
|
};
|
||||||
|
|
||||||
button.addEventListener('click', handleShowSettings, false);
|
button.addEventListener('click', handleShowSettings, false);
|
||||||
|
@ -1476,7 +1476,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
button.style = 'background: url(\'../images/icons/cf_icon_safehome_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
|
button.style = 'background: url(\'../images/icons/cf_icon_safehome_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
|
||||||
|
|
||||||
var handleShowSafehome = function () {
|
var handleShowSafehome = function () {
|
||||||
$('#missionPlanerSafehome').fadeIn(300);
|
$('#missionPlannerSafehome').fadeIn(300);
|
||||||
//SAFEHOMES.flush();
|
//SAFEHOMES.flush();
|
||||||
//mspHelper.loadSafehomes();
|
//mspHelper.loadSafehomes();
|
||||||
cleanSafehomeLayers();
|
cleanSafehomeLayers();
|
||||||
|
@ -1514,11 +1514,11 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
button.style = 'background: url(\'../images/icons/cf_icon_elevation_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
|
button.style = 'background: url(\'../images/icons/cf_icon_elevation_white.svg\') no-repeat 1px -1px;background-color: rgba(0,60,136,.5);';
|
||||||
|
|
||||||
var handleShowSettings = function () {
|
var handleShowSettings = function () {
|
||||||
$('#missionPlanerHome').fadeIn(300);
|
$('#missionPlannerHome').fadeIn(300);
|
||||||
cleanHomeLayers();
|
cleanHomeLayers();
|
||||||
renderHomeTable();
|
renderHomeTable();
|
||||||
renderHomeOnMap();
|
renderHomeOnMap();
|
||||||
$('#missionPlanerElevation').fadeIn(300);
|
$('#missionPlannerElevation').fadeIn(300);
|
||||||
plotElevation();
|
plotElevation();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1775,7 +1775,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
// save map view settings when user moves it
|
// save map view settings when user moves it
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
map.on('moveend', function (evt) {
|
map.on('moveend', function (evt) {
|
||||||
chrome.storage.local.set({'missionPlanerLastValues': {
|
chrome.storage.local.set({'missionPlannerLastValues': {
|
||||||
center: ol.proj.toLonLat(map.getView().getCenter()),
|
center: ol.proj.toLonLat(map.getView().getCenter()),
|
||||||
zoom: map.getView().getZoom()
|
zoom: map.getView().getZoom()
|
||||||
}});
|
}});
|
||||||
|
@ -1783,10 +1783,10 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
// load map view settings on startup
|
// load map view settings on startup
|
||||||
//////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////
|
||||||
chrome.storage.local.get('missionPlanerLastValues', function (result) {
|
chrome.storage.local.get('missionPlannerLastValues', function (result) {
|
||||||
if (result.missionPlanerLastValues && result.missionPlanerLastValues.center) {
|
if (result.missionPlannerLastValues && result.missionPlannerLastValues.center) {
|
||||||
map.getView().setCenter(ol.proj.fromLonLat(result.missionPlanerLastValues.center));
|
map.getView().setCenter(ol.proj.fromLonLat(result.missionPlannerLastValues.center));
|
||||||
map.getView().setZoom(result.missionPlanerLastValues.zoom);
|
map.getView().setZoom(result.missionPlannerLastValues.zoom);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -2642,7 +2642,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
//
|
//
|
||||||
// Load/Save FC mission Toolbox
|
// Load/Save FC mission Toolbox
|
||||||
// mission = configurator store, WP number indexed from 0, MISSION_PLANER = FC NVM store, WP number indexed from 1
|
// mission = configurator store, WP number indexed from 0, MISSION_PLANNER = FC NVM store, WP number indexed from 1
|
||||||
/////////////////////////////////////////////
|
/////////////////////////////////////////////
|
||||||
function getWaypointsFromFC(loadEeprom) {
|
function getWaypointsFromFC(loadEeprom) {
|
||||||
if (loadEeprom) {
|
if (loadEeprom) {
|
||||||
|
@ -2660,12 +2660,12 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
} else {
|
} else {
|
||||||
$('#loadMissionButton').removeClass('disabled');
|
$('#loadMissionButton').removeClass('disabled');
|
||||||
}
|
}
|
||||||
if (!MISSION_PLANER.getCountBusyPoints()) {
|
if (!MISSION_PLANNER.getCountBusyPoints()) {
|
||||||
alert(chrome.i18n.getMessage('no_waypoints_to_load'));
|
alert(chrome.i18n.getMessage('no_waypoints_to_load'));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
mission.reinit();
|
mission.reinit();
|
||||||
mission.copy(MISSION_PLANER);
|
mission.copy(MISSION_PLANNER);
|
||||||
mission.update(false, true);
|
mission.update(false, true);
|
||||||
|
|
||||||
/* check multimissions */
|
/* check multimissions */
|
||||||
|
@ -2691,9 +2691,9 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function sendWaypointsToFC(saveEeprom) {
|
function sendWaypointsToFC(saveEeprom) {
|
||||||
MISSION_PLANER.reinit();
|
MISSION_PLANNER.reinit();
|
||||||
MISSION_PLANER.copy(mission);
|
MISSION_PLANNER.copy(mission);
|
||||||
MISSION_PLANER.update(false, true, true);
|
MISSION_PLANNER.update(false, true, true);
|
||||||
mspHelper.saveWaypoints(function() {
|
mspHelper.saveWaypoints(function() {
|
||||||
GUI.log('End send point');
|
GUI.log('End send point');
|
||||||
if (saveEeprom) {
|
if (saveEeprom) {
|
||||||
|
@ -2703,13 +2703,13 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
} else {
|
} else {
|
||||||
$('#saveMissionButton').removeClass('disabled');
|
$('#saveMissionButton').removeClass('disabled');
|
||||||
}
|
}
|
||||||
mission.setMaxWaypoints(MISSION_PLANER.getMaxWaypoints());
|
mission.setMaxWaypoints(MISSION_PLANNER.getMaxWaypoints());
|
||||||
mission.setValidMission(MISSION_PLANER.getValidMission());
|
mission.setValidMission(MISSION_PLANNER.getValidMission());
|
||||||
mission.setCountBusyPoints(MISSION_PLANER.getCountBusyPoints());
|
mission.setCountBusyPoints(MISSION_PLANNER.getCountBusyPoints());
|
||||||
multimission.setMaxWaypoints(mission.getMaxWaypoints());
|
multimission.setMaxWaypoints(mission.getMaxWaypoints());
|
||||||
updateTotalInfo();
|
updateTotalInfo();
|
||||||
mission.reinit();
|
mission.reinit();
|
||||||
mission.copy(MISSION_PLANER);
|
mission.copy(MISSION_PLANNER);
|
||||||
mission.update(false, true);
|
mission.update(false, true);
|
||||||
refreshLayers();
|
refreshLayers();
|
||||||
$('#MPeditPoint').fadeOut(300);
|
$('#MPeditPoint').fadeOut(300);
|
||||||
|
@ -2783,7 +2783,7 @@ TABS.mission_control.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function plotElevation() {
|
function plotElevation() {
|
||||||
if ($('#missionPlanerElevation').is(":visible") && !disableMarkerEdit) {
|
if ($('#missionPlannerElevation').is(":visible") && !disableMarkerEdit) {
|
||||||
if (mission.isEmpty()) {
|
if (mission.isEmpty()) {
|
||||||
var data = [[0], [0]];
|
var data = [[0], [0]];
|
||||||
var layout = {showlegend: true,
|
var layout = {showlegend: true,
|
||||||
|
|
|
@ -15,12 +15,6 @@
|
||||||
<span data-i18n="platformType"></span>
|
<span data-i18n="platformType"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div id="has-flaps-wrapper" class="checkbox">
|
|
||||||
<input type="checkbox" id="has-flaps" class="toggle" />
|
|
||||||
<label for="has-flaps">
|
|
||||||
<span data-i18n="platformHasFlaps"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -118,12 +112,12 @@
|
||||||
|
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
<div class="btn default_btn narrow pull-left mixer_btn_add">
|
|
||||||
<a href="#" data-role="role-logic-conditions-open" data-i18n="tabLogicConditions"></a>
|
|
||||||
</div>
|
|
||||||
<div class="btn default_btn narrow pull-right green mixer_btn_add">
|
<div class="btn default_btn narrow pull-right green mixer_btn_add">
|
||||||
<a href="#" data-role="role-servo-add" data-i18n="servoMixerAdd"></a>
|
<a href="#" data-role="role-servo-add" data-i18n="servoMixerAdd"></a>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="btn default_btn narrow pull-left mixer_btn_logic">
|
||||||
|
<a href="#" data-role="role-logic-conditions-open" data-i18n="tabLogicConditions"></a>
|
||||||
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
|
|
@ -124,6 +124,10 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
GUI.fillSelect($row.find(".mix-rule-input"), FC.getServoMixInputNames(), servoRule.getInput());
|
GUI.fillSelect($row.find(".mix-rule-input"), FC.getServoMixInputNames(), servoRule.getInput());
|
||||||
|
|
||||||
|
if (!MIXER_CONFIG.hasFlaps) {
|
||||||
|
$row.find(".mix-rule-input").children('option[value="14"]').remove();
|
||||||
|
}
|
||||||
|
|
||||||
$row.find(".mix-rule-input").val(servoRule.getInput()).change(function () {
|
$row.find(".mix-rule-input").val(servoRule.getInput()).change(function () {
|
||||||
servoRule.setInput($(this).val());
|
servoRule.setInput($(this).val());
|
||||||
updateFixedValueVisibility($row, $(this));
|
updateFixedValueVisibility($row, $(this));
|
||||||
|
@ -272,8 +276,6 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
let $platformSelect = $('#platform-type'),
|
let $platformSelect = $('#platform-type'),
|
||||||
platforms = helper.platform.getList(),
|
platforms = helper.platform.getList(),
|
||||||
$hasFlapsWrapper = $('#has-flaps-wrapper'),
|
|
||||||
$hasFlaps = $('#has-flaps'),
|
|
||||||
$mixerPreset = $('#mixer-preset'),
|
$mixerPreset = $('#mixer-preset'),
|
||||||
$wizardButton = $("#mixer-wizard");
|
$wizardButton = $("#mixer-wizard");
|
||||||
|
|
||||||
|
@ -354,30 +356,12 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
$hasFlaps.prop("checked", MIXER_CONFIG.hasFlaps);
|
|
||||||
$hasFlaps.change(function () {
|
|
||||||
if ($(this).is(":checked")) {
|
|
||||||
MIXER_CONFIG.hasFlaps = 1;
|
|
||||||
} else {
|
|
||||||
MIXER_CONFIG.hasFlaps = 0;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
$hasFlaps.change();
|
|
||||||
|
|
||||||
$platformSelect.change(function () {
|
$platformSelect.change(function () {
|
||||||
MIXER_CONFIG.platformType = parseInt($platformSelect.val(), 10);
|
MIXER_CONFIG.platformType = parseInt($platformSelect.val(), 10);
|
||||||
currentPlatform = helper.platform.getById(MIXER_CONFIG.platformType);
|
currentPlatform = helper.platform.getById(MIXER_CONFIG.platformType);
|
||||||
|
|
||||||
var $platformSelectParent = $platformSelect.parent('.select');
|
var $platformSelectParent = $platformSelect.parent('.select');
|
||||||
|
|
||||||
if (currentPlatform.flapsPossible) {
|
|
||||||
$hasFlapsWrapper.removeClass('is-hidden');
|
|
||||||
$platformSelectParent.removeClass('no-bottom-border');
|
|
||||||
} else {
|
|
||||||
$hasFlapsWrapper.addClass('is-hidden');
|
|
||||||
$platformSelectParent.addClass('no-bottom-border');
|
|
||||||
}
|
|
||||||
|
|
||||||
fillMixerPreset();
|
fillMixerPreset();
|
||||||
$mixerPreset.change();
|
$mixerPreset.change();
|
||||||
});
|
});
|
||||||
|
@ -430,6 +414,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
$('#load-mixer-button').click(function () {
|
$('#load-mixer-button').click(function () {
|
||||||
helper.mixer.loadServoRules(currentMixerPreset);
|
helper.mixer.loadServoRules(currentMixerPreset);
|
||||||
helper.mixer.loadMotorRules(currentMixerPreset);
|
helper.mixer.loadMotorRules(currentMixerPreset);
|
||||||
|
MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
||||||
renderServoMixRules();
|
renderServoMixRules();
|
||||||
renderMotorMixRules();
|
renderMotorMixRules();
|
||||||
renderOutputMapping();
|
renderOutputMapping();
|
||||||
|
|
|
@ -25,19 +25,20 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="cf_column twothird">
|
<div class="gui_box preview" style="float: left; position: fixed;">
|
||||||
<div class="gui_box grey preview" style="float: left; position: fixed;">
|
<div class="gui_box_titlebar">
|
||||||
<div class="gui_box_titlebar image">
|
|
||||||
<div class="spacer_box_title" data-i18n="osd_preview_title"></div>
|
<div class="spacer_box_title" data-i18n="osd_preview_title"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="display-layout">
|
<div class="display-layout">
|
||||||
<div class="col right">
|
<div class="col right">
|
||||||
|
<div class="left_43_margin"></div>
|
||||||
|
<div class="right_43_margin"></div>
|
||||||
<div class="preview">
|
<div class="preview">
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="cf_column third_right" style="width: calc(100% - 377px);">
|
<div class="cf_column third_right">
|
||||||
<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="osd_video_format"></div>
|
<div class="spacer_box_title" data-i18n="osd_video_format"></div>
|
||||||
|
@ -270,7 +271,6 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
<div id="fontmanagercontent" style="display:none; width:712px;">
|
<div id="fontmanagercontent" style="display:none; width:712px;">
|
||||||
<div class="font-picker" style="margin-bottom: 10px;">
|
<div class="font-picker" style="margin-bottom: 10px;">
|
||||||
<h1 class="tab_title">Font:</h1>
|
<h1 class="tab_title">Font:</h1>
|
||||||
|
@ -297,9 +297,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
</div>
|
</div>
|
||||||
<div class="content_toolbar supported hide">
|
<div class="content_toolbar supported hide">
|
||||||
<div class="btn">
|
<div class="btn">
|
||||||
|
|
136
tabs/osd.js
136
tabs/osd.js
|
@ -455,7 +455,6 @@ OSD.initData = function () {
|
||||||
item_count: 0,
|
item_count: 0,
|
||||||
items: [],
|
items: [],
|
||||||
groups: {},
|
groups: {},
|
||||||
display_items: [],
|
|
||||||
preview: [],
|
preview: [],
|
||||||
isDjiHdFpv: false
|
isDjiHdFpv: false
|
||||||
};
|
};
|
||||||
|
@ -513,19 +512,27 @@ OSD.DjiElements = {
|
||||||
};
|
};
|
||||||
|
|
||||||
OSD.constants = {
|
OSD.constants = {
|
||||||
VISIBLE: 0x0800,
|
VISIBLE: 0x2000,
|
||||||
VIDEO_TYPES: [
|
VIDEO_TYPES: [
|
||||||
'AUTO',
|
'AUTO',
|
||||||
'PAL',
|
'PAL',
|
||||||
'NTSC'
|
'NTSC',
|
||||||
|
'HD'
|
||||||
],
|
],
|
||||||
VIDEO_LINES: {
|
VIDEO_LINES: {
|
||||||
PAL: 16,
|
PAL: 16,
|
||||||
NTSC: 13
|
NTSC: 13,
|
||||||
|
HD: 18
|
||||||
|
},
|
||||||
|
VIDEO_COLS: {
|
||||||
|
PAL: 30,
|
||||||
|
NTSC: 30,
|
||||||
|
HD: 50
|
||||||
},
|
},
|
||||||
VIDEO_BUFFER_CHARS: {
|
VIDEO_BUFFER_CHARS: {
|
||||||
PAL: 480,
|
PAL: 480,
|
||||||
NTSC: 390
|
NTSC: 390,
|
||||||
|
HD: 900
|
||||||
},
|
},
|
||||||
UNIT_TYPES: [
|
UNIT_TYPES: [
|
||||||
{name: 'osdUnitImperial', value: 0},
|
{name: 'osdUnitImperial', value: 0},
|
||||||
|
@ -2033,14 +2040,39 @@ OSD.updateDisplaySize = function () {
|
||||||
if (video_type == 'AUTO') {
|
if (video_type == 'AUTO') {
|
||||||
video_type = 'PAL';
|
video_type = 'PAL';
|
||||||
}
|
}
|
||||||
// compute the size
|
|
||||||
|
// save the original OSD element positions.
|
||||||
|
var origPos = [];
|
||||||
|
for (var ii = 0; ii < OSD.data.items.length; ii++) {
|
||||||
|
origPos.push(OSD.msp.helpers.pack.position(OSD.data.items[ii]));
|
||||||
|
}
|
||||||
|
|
||||||
|
// save the new video type and cols per line
|
||||||
|
FONT.constants.SIZES.LINE = OSD.constants.VIDEO_COLS[video_type];
|
||||||
|
OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type;
|
||||||
|
|
||||||
|
// set the new display size
|
||||||
OSD.data.display_size = {
|
OSD.data.display_size = {
|
||||||
x: FONT.constants.SIZES.LINE,
|
x: FONT.constants.SIZES.LINE,
|
||||||
y: OSD.constants.VIDEO_LINES[video_type],
|
y: OSD.constants.VIDEO_LINES[video_type],
|
||||||
total: null
|
total: OSD.constants.VIDEO_BUFFER_CHARS[video_type]
|
||||||
};
|
};
|
||||||
|
|
||||||
OSD.constants.VIDEO_TYPES[OSD.data.video_system] = video_type;
|
// recalculate the OSD element positions for the new cols per line
|
||||||
|
for (var ii = 0; ii < OSD.data.items.length; ii++) {
|
||||||
|
var item = OSD.msp.helpers.unpack.position(origPos[ii]);
|
||||||
|
// do not recalculate anything not visible or outside of the screen
|
||||||
|
if (item.isVisible && item.x < OSD.data.display_size.x && item.y < OSD.data.display_size.y) {
|
||||||
|
OSD.data.items[ii] = item;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// set the preview size
|
||||||
|
$('.third_left').toggleClass('preview_hd_side', (video_type == 'HD'))
|
||||||
|
$('.preview').toggleClass('preview_hd cut43_left', (video_type == 'HD'))
|
||||||
|
$('.third_right').toggleClass('preview_hd_side', (video_type == 'HD'))
|
||||||
|
$('.left_43_margin').toggleClass('hd_43_left', (video_type == 'HD'))
|
||||||
|
$('.right_43_margin').toggleClass('hd_43_right', (video_type == 'HD'))
|
||||||
};
|
};
|
||||||
|
|
||||||
OSD.saveAlarms = function(callback) {
|
OSD.saveAlarms = function(callback) {
|
||||||
|
@ -2064,27 +2096,36 @@ OSD.saveItem = function(item, callback) {
|
||||||
//noinspection JSUnusedLocalSymbols
|
//noinspection JSUnusedLocalSymbols
|
||||||
OSD.msp = {
|
OSD.msp = {
|
||||||
/**
|
/**
|
||||||
* Note, unsigned 16 bit int for position ispacked:
|
* Unsigned 16 bit int for position is packed:
|
||||||
* 0: unused
|
* 0: unused
|
||||||
* v: visible flag
|
* v: visible flag
|
||||||
* b: blink flag
|
* b: blink flag
|
||||||
* y: y coordinate
|
* y: y coordinate
|
||||||
* x: x coordinate
|
* x: x coordinate
|
||||||
* 0000 vbyy yyyx xxxx
|
* 00vb yyyy yyxx xxxx
|
||||||
*/
|
*/
|
||||||
helpers: {
|
helpers: {
|
||||||
unpack: {
|
unpack: {
|
||||||
position: function (bits) {
|
position: function (bits) {
|
||||||
var display_item = {};
|
var display_item = {};
|
||||||
// size * y + x
|
display_item.x = bits & 0x3F;
|
||||||
display_item.position = FONT.constants.SIZES.LINE * ((bits >> 5) & 0x001F) + (bits & 0x001F);
|
display_item.y = (bits >> 6) & 0x3F;
|
||||||
|
display_item.position = (display_item.y) * FONT.constants.SIZES.LINE + (display_item.x);
|
||||||
display_item.isVisible = (bits & OSD.constants.VISIBLE) != 0;
|
display_item.isVisible = (bits & OSD.constants.VISIBLE) != 0;
|
||||||
return display_item;
|
return display_item;
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
calculate: {
|
||||||
|
coords: function(display_item) {
|
||||||
|
display_item.x = (display_item.position % FONT.constants.SIZES.LINE) & 0x3F;
|
||||||
|
display_item.y = (display_item.position / FONT.constants.SIZES.LINE) & 0x3F;
|
||||||
|
return display_item;
|
||||||
|
}
|
||||||
|
},
|
||||||
pack: {
|
pack: {
|
||||||
position: function (display_item) {
|
position: function (display_item) {
|
||||||
return (display_item.isVisible ? 0x0800 : 0) | (((display_item.position / FONT.constants.SIZES.LINE) & 0x001F) << 5) | (display_item.position % FONT.constants.SIZES.LINE);
|
return (display_item.isVisible ? 0x2000 : 0)
|
||||||
|
| ((display_item.y & 0x3F) << 6) | (display_item.x & 0x3F);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
|
@ -2469,8 +2510,8 @@ OSD.GUI.updateFields = function() {
|
||||||
// Ensure the element is inside the viewport, at least partially.
|
// Ensure the element is inside the viewport, at least partially.
|
||||||
// In that case move it to the very first row/col, otherwise there's
|
// In that case move it to the very first row/col, otherwise there's
|
||||||
// no way to reposition items that are outside the viewport.
|
// no way to reposition items that are outside the viewport.
|
||||||
if (itemData.position >= OSD.data.preview.length) {
|
if (itemData.x > OSD.data.display_size.x || itemData.y > OSD.data.display_size.y) {
|
||||||
itemData.position = 0;
|
itemData.x = itemData.y = itemData.position = 0;
|
||||||
}
|
}
|
||||||
$position.show();
|
$position.show();
|
||||||
} else {
|
} else {
|
||||||
|
@ -2491,6 +2532,7 @@ OSD.GUI.updateFields = function() {
|
||||||
var item = $(this).data('item');
|
var item = $(this).data('item');
|
||||||
var itemData = OSD.data.items[item.id];
|
var itemData = OSD.data.items[item.id];
|
||||||
itemData.position = parseInt($(this).val());
|
itemData.position = parseInt($(this).val());
|
||||||
|
OSD.msp.helpers.calculate.coords(itemData);
|
||||||
OSD.GUI.saveItem(item);
|
OSD.GUI.saveItem(item);
|
||||||
}))
|
}))
|
||||||
);
|
);
|
||||||
|
@ -2610,14 +2652,6 @@ OSD.GUI.updateMapPreview = function(mapCenter, name, directionSymbol, centerSymb
|
||||||
OSD.GUI.updatePreviews = function() {
|
OSD.GUI.updatePreviews = function() {
|
||||||
// buffer the preview;
|
// buffer the preview;
|
||||||
OSD.data.preview = [];
|
OSD.data.preview = [];
|
||||||
OSD.data.display_size.total = OSD.data.display_size.x * OSD.data.display_size.y;
|
|
||||||
for (var ii = 0; ii < OSD.data.display_items.length; ii++) {
|
|
||||||
var field = OSD.data.display_items[ii];
|
|
||||||
// reset fields that somehow end up off the screen
|
|
||||||
if (field.position > OSD.data.display_size.total) {
|
|
||||||
field.position = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// clear the buffer
|
// clear the buffer
|
||||||
for (i = 0; i < OSD.data.display_size.total; i++) {
|
for (i = 0; i < OSD.data.display_size.total; i++) {
|
||||||
|
@ -2634,6 +2668,12 @@ OSD.GUI.updatePreviews = function() {
|
||||||
if (!itemData.isVisible) {
|
if (!itemData.isVisible) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (itemData.x >= OSD.data.display_size.x)
|
||||||
|
{
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
// DJI HD FPV: Hide elements that only appear in craft name
|
// DJI HD FPV: Hide elements that only appear in craft name
|
||||||
if (OSD.DjiElements.craftNameElements.includes(item.name) &&
|
if (OSD.DjiElements.craftNameElements.includes(item.name) &&
|
||||||
$('#djiUnsupportedElements').find('input').is(':checked')) {
|
$('#djiUnsupportedElements').find('input').is(':checked')) {
|
||||||
|
@ -2683,16 +2723,16 @@ OSD.GUI.updatePreviews = function() {
|
||||||
item.preview_img.style.pointerEvents = 'none';
|
item.preview_img.style.pointerEvents = 'none';
|
||||||
}
|
}
|
||||||
|
|
||||||
var centerishPosition = 255;
|
|
||||||
|
|
||||||
// AHI is one line up with NTSC (less lines) compared to PAL
|
var centerPosition = (OSD.data.display_size.x * OSD.data.display_size.y / 2);
|
||||||
if (OSD.constants.VIDEO_TYPES[OSD.data.video_system] == 'NTSC')
|
if (OSD.data.display_size.y % 2 == 0) {
|
||||||
centerishPosition -= OSD.data.display_size.x;
|
centerPosition += OSD.data.display_size.x / 2;
|
||||||
|
}
|
||||||
|
|
||||||
// artificial horizon
|
// artificial horizon
|
||||||
if ($('input[name="ARTIFICIAL_HORIZON"]').prop('checked')) {
|
if ($('input[name="ARTIFICIAL_HORIZON"]').prop('checked')) {
|
||||||
for (i = 0; i < 9; i++) {
|
for (i = 0; i < 9; i++) {
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - 4 + i, SYM.AH_BAR9_0 + 4);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - 4 + i, SYM.AH_BAR9_0 + 4);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2701,21 +2741,21 @@ OSD.GUI.updatePreviews = function() {
|
||||||
crsHNumber = Settings.getInputValue('osd_crosshairs_style');
|
crsHNumber = Settings.getInputValue('osd_crosshairs_style');
|
||||||
if (crsHNumber == 1) {
|
if (crsHNumber == 1) {
|
||||||
// AIRCRAFT style
|
// AIRCRAFT style
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - 2, SYM.AH_AIRCRAFT0);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - 2, SYM.AH_AIRCRAFT0);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - 1, SYM.AH_AIRCRAFT1);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - 1, SYM.AH_AIRCRAFT1);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition, SYM.AH_AIRCRAFT2);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition, SYM.AH_AIRCRAFT2);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition + 1, SYM.AH_AIRCRAFT3);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition + 1, SYM.AH_AIRCRAFT3);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition + 2, SYM.AH_AIRCRAFT4);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition + 2, SYM.AH_AIRCRAFT4);
|
||||||
} else if ((crsHNumber > 1) && (crsHNumber < 8)) {
|
} else if ((crsHNumber > 1) && (crsHNumber < 8)) {
|
||||||
// TYPES 3 to 8 (zero indexed)
|
// TYPES 3 to 8 (zero indexed)
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - 1, SYM.AH_CROSSHAIRS[crsHNumber][0]);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - 1, SYM.AH_CROSSHAIRS[crsHNumber][0]);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition, SYM.AH_CROSSHAIRS[crsHNumber][1]);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition, SYM.AH_CROSSHAIRS[crsHNumber][1]);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition + 1, SYM.AH_CROSSHAIRS[crsHNumber][2]);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition + 1, SYM.AH_CROSSHAIRS[crsHNumber][2]);
|
||||||
} else {
|
} else {
|
||||||
// DEFAULT or unknown style
|
// DEFAULT or unknown style
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - 1, SYM.AH_CENTER_LINE);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - 1, SYM.AH_CENTER_LINE);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition, SYM.AH_CROSSHAIRS[crsHNumber]);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition, SYM.AH_CROSSHAIRS[crsHNumber]);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition + 1, SYM.AH_CENTER_LINE_RIGHT);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition + 1, SYM.AH_CENTER_LINE_RIGHT);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2724,21 +2764,17 @@ OSD.GUI.updatePreviews = function() {
|
||||||
var hudwidth = OSD.constants.AHISIDEBARWIDTHPOSITION;
|
var hudwidth = OSD.constants.AHISIDEBARWIDTHPOSITION;
|
||||||
var hudheight = OSD.constants.AHISIDEBARHEIGHTPOSITION;
|
var hudheight = OSD.constants.AHISIDEBARHEIGHTPOSITION;
|
||||||
for (i = -hudheight; i <= hudheight; i++) {
|
for (i = -hudheight; i <= hudheight; i++) {
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - hudwidth + (i * FONT.constants.SIZES.LINE), SYM.AH_DECORATION);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - hudwidth + (i * FONT.constants.SIZES.LINE), SYM.AH_DECORATION);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition + hudwidth + (i * FONT.constants.SIZES.LINE), SYM.AH_DECORATION);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition + hudwidth + (i * FONT.constants.SIZES.LINE), SYM.AH_DECORATION);
|
||||||
}
|
}
|
||||||
// AH level indicators
|
// AH level indicators
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition - hudwidth + 1, SYM.AH_LEFT);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition - hudwidth + 1, SYM.AH_LEFT);
|
||||||
OSD.GUI.checkAndProcessSymbolPosition(centerishPosition + hudwidth - 1, SYM.AH_RIGHT);
|
OSD.GUI.checkAndProcessSymbolPosition(centerPosition + hudwidth - 1, SYM.AH_RIGHT);
|
||||||
}
|
}
|
||||||
|
|
||||||
var mapCenter = (OSD.data.display_size.x * OSD.data.display_size.y / 2);
|
OSD.GUI.updateMapPreview(centerPosition, 'MAP_NORTH', 'N', SYM.HOME);
|
||||||
if (OSD.data.display_size.y % 2 == 0) {
|
OSD.GUI.updateMapPreview(centerPosition, 'MAP_TAKEOFF', 'T', SYM.HOME);
|
||||||
mapCenter += OSD.data.display_size.x / 2;
|
OSD.GUI.updateMapPreview(centerPosition, 'RADAR', null, SYM.DIR_TO_HOME);
|
||||||
}
|
|
||||||
OSD.GUI.updateMapPreview(mapCenter, 'MAP_NORTH', 'N', SYM.HOME);
|
|
||||||
OSD.GUI.updateMapPreview(mapCenter, 'MAP_TAKEOFF', 'T', SYM.HOME);
|
|
||||||
OSD.GUI.updateMapPreview(mapCenter, 'RADAR', null, SYM.DIR_TO_HOME);
|
|
||||||
|
|
||||||
// render
|
// render
|
||||||
var $preview = $('.display-layout .preview').empty();
|
var $preview = $('.display-layout .preview').empty();
|
||||||
|
|
|
@ -190,6 +190,9 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
// UI Hooks
|
// UI Hooks
|
||||||
|
|
||||||
$('a.refresh').click(function () {
|
$('a.refresh').click(function () {
|
||||||
|
$("#content-watermark").remove();
|
||||||
|
$(".tab-pid_tuning").remove();
|
||||||
|
|
||||||
GUI.tab_switch_cleanup(function () {
|
GUI.tab_switch_cleanup(function () {
|
||||||
GUI.log(chrome.i18n.getMessage('pidTuningDataRefreshed'));
|
GUI.log(chrome.i18n.getMessage('pidTuningDataRefreshed'));
|
||||||
TABS.pid_tuning.initialize();
|
TABS.pid_tuning.initialize();
|
||||||
|
|
|
@ -93,6 +93,12 @@ TABS.ports.initialize = function (callback) {
|
||||||
maxPorts: 1 }
|
maxPorts: 1 }
|
||||||
);
|
);
|
||||||
|
|
||||||
|
functionRules.push({
|
||||||
|
name: 'HDZERO_VTX',
|
||||||
|
groups: ['peripherals'],
|
||||||
|
maxPorts: 1 }
|
||||||
|
);
|
||||||
|
|
||||||
functionRules.push({
|
functionRules.push({
|
||||||
name: 'SMARTPORT_MASTER',
|
name: 'SMARTPORT_MASTER',
|
||||||
groups: ['peripherals'],
|
groups: ['peripherals'],
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue