Merge branch 'master' into abo_mission_cont_multimissions
|
@ -560,7 +560,7 @@
|
||||||
"message": "Settings restored to <strong>default</strong>"
|
"message": "Settings restored to <strong>default</strong>"
|
||||||
},
|
},
|
||||||
"initialSetupEepromSaved": {
|
"initialSetupEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Setup"
|
||||||
},
|
},
|
||||||
|
|
||||||
"RX_PPM": {
|
"RX_PPM": {
|
||||||
|
@ -1009,7 +1009,7 @@
|
||||||
"message": "Craft name. Can be displayed by OSD and by compatible RC systems."
|
"message": "Craft name. Can be displayed by OSD and by compatible RC systems."
|
||||||
},
|
},
|
||||||
"configurationEepromSaved": {
|
"configurationEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Configuration"
|
||||||
},
|
},
|
||||||
"configurationButtonSave": {
|
"configurationButtonSave": {
|
||||||
"message": "Save and Reboot"
|
"message": "Save and Reboot"
|
||||||
|
@ -1216,7 +1216,7 @@
|
||||||
"message": "PID data <strong>refreshed</strong>"
|
"message": "PID data <strong>refreshed</strong>"
|
||||||
},
|
},
|
||||||
"pidTuningEepromSaved": {
|
"pidTuningEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: PID Tuning"
|
||||||
},
|
},
|
||||||
|
|
||||||
"receiverHelp": {
|
"receiverHelp": {
|
||||||
|
@ -1280,7 +1280,7 @@
|
||||||
"message": "RC Tuning data <strong>refreshed</strong>"
|
"message": "RC Tuning data <strong>refreshed</strong>"
|
||||||
},
|
},
|
||||||
"receiverEepromSaved": {
|
"receiverEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Receiver"
|
||||||
},
|
},
|
||||||
|
|
||||||
"auxiliaryHelp": {
|
"auxiliaryHelp": {
|
||||||
|
@ -1528,9 +1528,11 @@
|
||||||
"message": "Save"
|
"message": "Save"
|
||||||
},
|
},
|
||||||
"adjustmentsEepromSaved": {
|
"adjustmentsEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Adjustments"
|
||||||
|
},
|
||||||
|
"programmingEepromSaved": {
|
||||||
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Programming"
|
||||||
},
|
},
|
||||||
|
|
||||||
"transponderNotSupported": {
|
"transponderNotSupported": {
|
||||||
"message": "Your flight controller's firmware does not support transponder functionality."
|
"message": "Your flight controller's firmware does not support transponder functionality."
|
||||||
},
|
},
|
||||||
|
@ -1556,7 +1558,7 @@
|
||||||
"message": "Transponder data is <span style=\"color: red\">invalid</span>"
|
"message": "Transponder data is <span style=\"color: red\">invalid</span>"
|
||||||
},
|
},
|
||||||
"transponderEepromSaved": {
|
"transponderEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: Transponder"
|
||||||
},
|
},
|
||||||
"servosChangeDirection": {
|
"servosChangeDirection": {
|
||||||
"message": "Change Direction in TX To Match"
|
"message": "Change Direction in TX To Match"
|
||||||
|
@ -2012,7 +2014,7 @@
|
||||||
"message": "Save"
|
"message": "Save"
|
||||||
},
|
},
|
||||||
"ledStripEepromSaved": {
|
"ledStripEepromSaved": {
|
||||||
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>"
|
"message": "EEPROM <span style=\"color: #37a8db\">saved</span>: LED"
|
||||||
},
|
},
|
||||||
|
|
||||||
"controlAxisRoll": {
|
"controlAxisRoll": {
|
||||||
|
@ -2492,12 +2494,21 @@
|
||||||
"userControlMode": {
|
"userControlMode": {
|
||||||
"message": "User Control Mode"
|
"message": "User Control Mode"
|
||||||
},
|
},
|
||||||
|
"posholdDefaultSpeed": {
|
||||||
|
"message": "Default navigation speed [cm/s]"
|
||||||
|
},
|
||||||
|
"posholdDefaultSpeedHelp": {
|
||||||
|
"message": "Default speed during RTH, also used for WP navigation if no speed set for WP leg. Limited to Max. navigation speed"
|
||||||
|
},
|
||||||
"posholdMaxSpeed": {
|
"posholdMaxSpeed": {
|
||||||
"message": "Max. navigation speed [cm/s]"
|
"message": "Max. navigation speed [cm/s]"
|
||||||
},
|
},
|
||||||
"posholdMaxManualSpeed": {
|
"posholdMaxManualSpeed": {
|
||||||
"message": "Max. CRUISE speed [cm/s]"
|
"message": "Max. CRUISE speed [cm/s]"
|
||||||
},
|
},
|
||||||
|
"posholdMaxManualSpeedHelp": {
|
||||||
|
"message": "Maximum horizonal velocity allowed for pilot manual control during POSHOLD/CRUISE mode"
|
||||||
|
},
|
||||||
"posholdMaxClimbRate": {
|
"posholdMaxClimbRate": {
|
||||||
"message": "Max. navigation climb rate [cm/s]"
|
"message": "Max. navigation climb rate [cm/s]"
|
||||||
},
|
},
|
||||||
|
@ -2798,6 +2809,12 @@
|
||||||
"osd_plus_code_short": {
|
"osd_plus_code_short": {
|
||||||
"message" : "Plus Code Remove Leading Digits"
|
"message" : "Plus Code Remove Leading Digits"
|
||||||
},
|
},
|
||||||
|
"osd_esc_rpm_precision": {
|
||||||
|
"message": "ESC RPM precision"
|
||||||
|
},
|
||||||
|
"osd_esc_rpm_precision_help": {
|
||||||
|
"message": "The number of digits shown in the RPM display. If the RPM is higher than the number of digits, it will be shown in thousand RPM with as many decimal places as allowed."
|
||||||
|
},
|
||||||
"osd_crosshairs_style": {
|
"osd_crosshairs_style": {
|
||||||
"message" : "Crosshairs Style"
|
"message" : "Crosshairs Style"
|
||||||
},
|
},
|
||||||
|
@ -3245,6 +3262,9 @@
|
||||||
"osdElement_WIND_SPEED_VERTICAL_HELP": {
|
"osdElement_WIND_SPEED_VERTICAL_HELP": {
|
||||||
"message": "Shows estimated vertical wind speed and direction (up or down)."
|
"message": "Shows estimated vertical wind speed and direction (up or down)."
|
||||||
},
|
},
|
||||||
|
"osdElement_ACTIVE_PROFILE": {
|
||||||
|
"message": "Show the active profile"
|
||||||
|
},
|
||||||
"osdElement_LEVEL_PIDS": {
|
"osdElement_LEVEL_PIDS": {
|
||||||
"message": "Level PIDs"
|
"message": "Level PIDs"
|
||||||
},
|
},
|
||||||
|
@ -3863,10 +3883,16 @@
|
||||||
"fwLevelTrimMechanics": {
|
"fwLevelTrimMechanics": {
|
||||||
"message": "Fixed Wing Level Trim"
|
"message": "Fixed Wing Level Trim"
|
||||||
},
|
},
|
||||||
"d_boost_factor": {
|
"d_boost_min": {
|
||||||
"message": "D-Boost Factor"
|
"message": "D-Boost Min. Scale"
|
||||||
},
|
},
|
||||||
"d_boost_factor_help": {
|
"d_boost_min_help": {
|
||||||
|
"message": "Defines the max allowed Dterm attenuation during stick acceleration phase. Value 1.0 mean Dterm is not attenuate. 0.5 mean it's allowed to shrink by half. Lower values result in faster response during fast stick movement."
|
||||||
|
},
|
||||||
|
"d_boost_max": {
|
||||||
|
"message": "D-Boost Max. Scale"
|
||||||
|
},
|
||||||
|
"d_boost_max_help": {
|
||||||
"message": "Defines the maximum Dterm boost when maximum angular acceleration is reached. 1.0 means D-Boost is disabled, 2.0 means Dterm is allowed to grow by 100%. Values between 1.5 and 1.7 are usually the sweet spot."
|
"message": "Defines the maximum Dterm boost when maximum angular acceleration is reached. 1.0 means D-Boost is disabled, 2.0 means Dterm is allowed to grow by 100%. Values between 1.5 and 1.7 are usually the sweet spot."
|
||||||
},
|
},
|
||||||
"d_boost_max_at_acceleration": {
|
"d_boost_max_at_acceleration": {
|
||||||
|
|
|
@ -214,7 +214,11 @@ helper.defaultsDialog = (function () {
|
||||||
value: 10
|
value: 10
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "d_boost_factor",
|
key: "d_boost_min",
|
||||||
|
value: 1
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "d_boost_max",
|
||||||
value: 1
|
value: 1
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -392,7 +396,11 @@ helper.defaultsDialog = (function () {
|
||||||
value: 10
|
value: 10
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "d_boost_factor",
|
key: "d_boost_min",
|
||||||
|
value: 1
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "d_boost_max",
|
||||||
value: 1
|
value: 1
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
|
13
js/fc.js
|
@ -1243,6 +1243,17 @@ var FC = {
|
||||||
hasOperand: [true, true],
|
hasOperand: [true, true],
|
||||||
output: "boolean"
|
output: "boolean"
|
||||||
},
|
},
|
||||||
|
|
||||||
|
41: {
|
||||||
|
name: "LOITER RADIUS OVERRIDE",
|
||||||
|
hasOperand: [true, false],
|
||||||
|
output: "boolean"
|
||||||
|
},
|
||||||
|
42: {
|
||||||
|
name: "SET PROFILE",
|
||||||
|
hasOperand: [true, false],
|
||||||
|
output: "boolean"
|
||||||
|
},
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
getOperandTypes: function () {
|
getOperandTypes: function () {
|
||||||
|
@ -1301,6 +1312,8 @@ var FC = {
|
||||||
32: "CRSF LQ",
|
32: "CRSF LQ",
|
||||||
33: "CRSF SNR",
|
33: "CRSF SNR",
|
||||||
34: "GPS Valid Fix",
|
34: "GPS Valid Fix",
|
||||||
|
35: "Loiter Radius [cm]",
|
||||||
|
36: "Active Profile",
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
3: {
|
3: {
|
||||||
|
|
|
@ -2989,20 +2989,15 @@ var mspHelper = (function (gui) {
|
||||||
|
|
||||||
self.loadWaypoints = function (callback) {
|
self.loadWaypoints = function (callback) {
|
||||||
MISSION_PLANER.reinit();
|
MISSION_PLANER.reinit();
|
||||||
let waypointId = 1;
|
let waypointId = 0;
|
||||||
let startTime = new Date().getTime();
|
let startTime = new Date().getTime();
|
||||||
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, getFirstWP);
|
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, loadWaypoint);
|
||||||
|
|
||||||
function getFirstWP() {
|
function loadWaypoint() {
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, nextWaypoint)
|
|
||||||
};
|
|
||||||
|
|
||||||
function nextWaypoint() {
|
|
||||||
waypointId++;
|
waypointId++;
|
||||||
if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
|
if (waypointId < MISSION_PLANER.getCountBusyPoints()) {
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, nextWaypoint);
|
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');
|
||||||
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
|
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
|
||||||
}
|
}
|
||||||
|
@ -3010,14 +3005,14 @@ var mspHelper = (function (gui) {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveWaypoints = function (callback) {
|
self.saveWaypoints = function (callback) {
|
||||||
let waypointId = 1;
|
let waypointId = 0;
|
||||||
let startTime = new Date().getTime();
|
let startTime = new Date().getTime();
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, nextWaypoint)
|
sendWaypoint();
|
||||||
|
|
||||||
function nextWaypoint() {
|
function sendWaypoint() {
|
||||||
waypointId++;
|
waypointId++;
|
||||||
if (waypointId < MISSION_PLANER.get().length) {
|
if (waypointId < MISSION_PLANER.get().length) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.extractBuffer(waypointId), false, nextWaypoint);
|
MSP.send_message(MSPCodes.MSP_SET_WP, MISSION_PLANER.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_PLANER.extractBuffer(waypointId), false, endMission);
|
||||||
|
|
|
@ -13250,48 +13250,48 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01010000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01001010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000101
|
||||||
01010101
|
00100000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10100001
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00010101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 13 KiB |
BIN
resources/osd/bold/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -13253,48 +13253,48 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01010000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01001010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000101
|
||||||
01010101
|
00100000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10100001
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00010101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 13 KiB |
BIN
resources/osd/clarity/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -13256,48 +13256,48 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01010000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01001010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000101
|
||||||
01010101
|
00100000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10100001
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00010101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 13 KiB |
BIN
resources/osd/clarity_medium/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -13250,48 +13250,48 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01010000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01001010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000101
|
||||||
01010101
|
00100000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10100001
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00010101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 12 KiB After Width: | Height: | Size: 12 KiB |
BIN
resources/osd/default/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -124,7 +124,8 @@ SYM_HEADING_E | SYM.HEADING_E | Heading graph East
|
||||||
SYM_HEADING_W | SYM.HEADING_W | Heading graph West | 203 | 0xCB
|
SYM_HEADING_W | SYM.HEADING_W | Heading graph West | 203 | 0xCB
|
||||||
SYM_HEADING_DIVIDED_LINE | SYM.HEADING_DIVIDED_LINE | Heading graphic | 204 | 0xCC
|
SYM_HEADING_DIVIDED_LINE | SYM.HEADING_DIVIDED_LINE | Heading graphic | 204 | 0xCC
|
||||||
SYM_HEADING_LINE | SYM.HEADING_LINE | Heading graphic | 205 | 0xCD
|
SYM_HEADING_LINE | SYM.HEADING_LINE | Heading graphic | 205 | 0xCD
|
||||||
SYM_MAX | SYM.MAX | Max icon | 206 | 0xCE
|
SYM_MAX | SYM.MAX | Max icon | 206 | 0xCE
|
||||||
|
SYM_PROFILE | SYM.PROFILE | Profile icon | 207 | 0xCF
|
||||||
| | | |
|
| | | |
|
||||||
SYM_LOGO_START | | INAV Logo | 257 - 280 | 0x101 - 0x118
|
SYM_LOGO_START | | INAV Logo | 257 - 280 | 0x101 - 0x118
|
||||||
SYM_AH_LEFT | SYM.AH_LEFT | AHI Arrow left | 300 | 0x12C
|
SYM_AH_LEFT | SYM.AH_LEFT | AHI Arrow left | 300 | 0x12C
|
||||||
|
|
|
@ -13250,51 +13250,51 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01000000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00000010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101000
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101000
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00000010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 13 KiB After Width: | Height: | Size: 13 KiB |
BIN
resources/osd/impact/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -13247,51 +13247,51 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01000000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00000010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101000
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101000
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00000010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 12 KiB After Width: | Height: | Size: 12 KiB |
BIN
resources/osd/impact_mini/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -13250,51 +13250,51 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01010000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
|
01001010
|
||||||
|
10100000
|
||||||
|
00000101
|
||||||
|
00100000
|
||||||
|
00001010
|
||||||
|
10100001
|
||||||
|
00101010
|
||||||
|
10100101
|
||||||
|
01011000
|
||||||
|
00100101
|
||||||
|
00000001
|
||||||
|
01011000
|
||||||
|
00100100
|
||||||
|
10101000
|
||||||
|
01011000
|
||||||
|
00100100
|
||||||
|
10000010
|
||||||
|
00011000
|
||||||
|
00100100
|
||||||
|
10000010
|
||||||
|
00011000
|
||||||
|
00100100
|
||||||
|
10101000
|
||||||
|
01011000
|
||||||
|
00100100
|
||||||
|
10000001
|
||||||
|
01011000
|
||||||
|
00100100
|
||||||
|
10000101
|
||||||
|
01011000
|
||||||
|
00100101
|
||||||
|
00010101
|
||||||
|
01011000
|
||||||
|
00100101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 12 KiB After Width: | Height: | Size: 12 KiB |
BIN
resources/osd/large/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -13253,48 +13253,48 @@ MAX7456
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
01010000
|
||||||
|
00000101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01001010
|
||||||
01010101
|
10100000
|
||||||
01010101
|
00000101
|
||||||
01010101
|
00100000
|
||||||
01010101
|
00001010
|
||||||
01010101
|
10100001
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10100101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000010
|
||||||
01010101
|
00011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000001
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100100
|
||||||
01010101
|
10000101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00100101
|
||||||
01010101
|
00010101
|
||||||
01010101
|
01011000
|
||||||
01010101
|
00101010
|
||||||
01010101
|
10101010
|
||||||
01010101
|
10101000
|
||||||
01010101
|
01000000
|
||||||
01010101
|
00000000
|
||||||
01010101
|
00000001
|
||||||
01010101
|
|
||||||
01010101
|
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
01010101
|
01010101
|
||||||
|
|
Before Width: | Height: | Size: 12 KiB After Width: | Height: | Size: 12 KiB |
BIN
resources/osd/vision/207.png
Normal file
After Width: | Height: | Size: 1.9 KiB |
|
@ -86,7 +86,6 @@
|
||||||
<option value="19" i18n="adjustmentsFunction19"></option>
|
<option value="19" i18n="adjustmentsFunction19"></option>
|
||||||
<option value="20" i18n="adjustmentsFunction20"></option>
|
<option value="20" i18n="adjustmentsFunction20"></option>
|
||||||
<option value="21" i18n="adjustmentsFunction21"></option>
|
<option value="21" i18n="adjustmentsFunction21"></option>
|
||||||
<option value="22" i18n="adjustmentsFunction22"></option>
|
|
||||||
<option value="23" i18n="adjustmentsFunction23"></option>
|
<option value="23" i18n="adjustmentsFunction23"></option>
|
||||||
<option value="24" i18n="adjustmentsFunction24"></option>
|
<option value="24" i18n="adjustmentsFunction24"></option>
|
||||||
<option value="25" i18n="adjustmentsFunction25"></option>
|
<option value="25" i18n="adjustmentsFunction25"></option>
|
||||||
|
|
|
@ -216,12 +216,18 @@
|
||||||
<label for="user-control-mode"><span data-i18n="userControlMode"></span></label>
|
<label for="user-control-mode"><span data-i18n="userControlMode"></span></label>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="max-speed" type="number" data-setting="nav_auto_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
<input id="default-auto-speed" type="number" data-setting="nav_auto_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
<label for="max-speed"><span data-i18n="posholdMaxSpeed"></span></label>
|
<label for="default-auto-speed"><span data-i18n="posholdDefaultSpeed"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="posholdDefaultSpeedHelp"></div>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<input id="max-auto-speed" type="number" data-setting="nav_max_auto_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
|
<label for="max-auto-speed"><span data-i18n="posholdMaxSpeed"></span></label>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="max-manual-speed" type="number" data-setting="nav_manual_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
<input id="max-manual-speed" type="number" data-setting="nav_manual_speed" data-setting-multiplier="1" step="1" min="10" max="2000" />
|
||||||
<label for="max-manual-speed"><span data-i18n="posholdMaxManualSpeed"></span></label>
|
<label for="max-manual-speed"><span data-i18n="posholdMaxManualSpeed"></span></label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="posholdMaxManualSpeedHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input id="max-bank-angle" type="number" data-setting="nav_mc_bank_angle" data-setting-multiplier="1" step="1" min="15" max="45" />
|
<input id="max-bank-angle" type="number" data-setting="nav_mc_bank_angle" data-setting-multiplier="1" step="1" min="15" max="45" />
|
||||||
|
|
|
@ -75,6 +75,11 @@
|
||||||
<select class="update_preview" data-setting="osd_plus_code_short" data-live="true"></select>
|
<select class="update_preview" data-setting="osd_plus_code_short" data-live="true"></select>
|
||||||
<span data-i18n="osd_plus_code_short"></span>
|
<span data-i18n="osd_plus_code_short"></span>
|
||||||
</label>
|
</label>
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="osd_esc_rpm_precision_help"></div>
|
||||||
|
<label>
|
||||||
|
<select class="update_preview" data-setting="osd_esc_rpm_precision" data-live="true"></select>
|
||||||
|
<span data-i18n="osd_esc_rpm_precision"></span>
|
||||||
|
</label>
|
||||||
<label>
|
<label>
|
||||||
<select class="update_preview" data-setting="osd_crosshairs_style" data-live="true"></select>
|
<select class="update_preview" data-setting="osd_crosshairs_style" data-live="true"></select>
|
||||||
<span data-i18n="osd_crosshairs_style"></span>
|
<span data-i18n="osd_crosshairs_style"></span>
|
||||||
|
|
13
tabs/osd.js
|
@ -100,6 +100,7 @@ SYM.AH_NM = 0x3F;
|
||||||
SYM.WH_NM = 0x70;
|
SYM.WH_NM = 0x70;
|
||||||
SYM.VTX_POWER = 0x27;
|
SYM.VTX_POWER = 0x27;
|
||||||
SYM.MAX = 0xCE;
|
SYM.MAX = 0xCE;
|
||||||
|
SYM.PROFILE = 0xCF;
|
||||||
|
|
||||||
SYM.AH_AIRCRAFT0 = 0x1A2;
|
SYM.AH_AIRCRAFT0 = 0x1A2;
|
||||||
SYM.AH_AIRCRAFT1 = 0x1A3;
|
SYM.AH_AIRCRAFT1 = 0x1A3;
|
||||||
|
@ -900,7 +901,10 @@ OSD.constants = {
|
||||||
name: 'ESC_RPM',
|
name: 'ESC_RPM',
|
||||||
id: 106,
|
id: 106,
|
||||||
min_version: '2.3.0',
|
min_version: '2.3.0',
|
||||||
preview: FONT.symbol(SYM.RPM) + '983',
|
preview: function(){
|
||||||
|
let rpmPreview = '112974'.substr((6 - parseInt(Settings.getInputValue('osd_esc_rpm_precision'))));
|
||||||
|
return FONT.symbol(SYM.RPM) + rpmPreview;
|
||||||
|
}
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
name: 'GLIDESLOPE',
|
name: 'GLIDESLOPE',
|
||||||
|
@ -1717,6 +1721,13 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'osdGroupPIDs',
|
name: 'osdGroupPIDs',
|
||||||
items: [
|
items: [
|
||||||
|
{
|
||||||
|
name: 'ACTIVE_PROFILE',
|
||||||
|
id: 128,
|
||||||
|
preview: function(osd_data) {
|
||||||
|
return FONT.symbol(SYM.PROFILE) + '1';
|
||||||
|
}
|
||||||
|
},
|
||||||
{
|
{
|
||||||
name: 'ROLL_PIDS',
|
name: 'ROLL_PIDS',
|
||||||
id: 16,
|
id: 16,
|
||||||
|
|
|
@ -270,13 +270,6 @@
|
||||||
<div class="helpicon cf_tip" data-i18n_title="gyro_main_lpf_hz_help"></div>
|
<div class="helpicon cf_tip" data-i18n_title="gyro_main_lpf_hz_help"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
|
||||||
<th>Matrix Gyro Filter</th>
|
|
||||||
<td>
|
|
||||||
<select data-setting="dynamic_gyro_notch_enabled" />
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="dynamic_gyro_notch_enabled_help"></div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
<tr>
|
||||||
<th>Matrix Filter Min Frequency</th>
|
<th>Matrix Filter Min Frequency</th>
|
||||||
<td>
|
<td>
|
||||||
|
@ -291,12 +284,6 @@
|
||||||
<div class="helpicon cf_tip" title="The higher value, the higher selectivity of the Matrix Filter. Values between 150 and 300 are recommended"></div>
|
<div class="helpicon cf_tip" title="The higher value, the higher selectivity of the Matrix Filter. Values between 150 and 300 are recommended"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
|
||||||
<th>Unicorn Filter</th>
|
|
||||||
<td>
|
|
||||||
<select data-setting="setpoint_kalman_enabled" />
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
<tr>
|
||||||
<th>Unicorn Filter Q Factor</th>
|
<th>Unicorn Filter Q Factor</th>
|
||||||
<td>
|
<td>
|
||||||
|
@ -319,13 +306,6 @@
|
||||||
<div class="helpicon cf_tip" data-i18n_title="dtermLpfCutoffFrequencyHelp"></div>
|
<div class="helpicon cf_tip" data-i18n_title="dtermLpfCutoffFrequencyHelp"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
|
||||||
<th data-i18n="dterm_lpf2_hz"></th>
|
|
||||||
<td>
|
|
||||||
<input data-setting="dterm_lpf2_hz" type="number" class="rate-tpa_input" />
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="dterm_lpf2_hz_help"></div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
|
@ -358,13 +338,6 @@
|
||||||
<div class="cf_column">
|
<div class="cf_column">
|
||||||
<table class="settings-table settings-table--filtering">
|
<table class="settings-table settings-table--filtering">
|
||||||
<tbody>
|
<tbody>
|
||||||
<tr>
|
|
||||||
<th data-i18n="itermRelax"></th>
|
|
||||||
<td>
|
|
||||||
<select data-setting="mc_iterm_relax" />
|
|
||||||
<div class="helpicon cf_tip" data-i18n_title="itermRelaxHelp"></div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
<tr>
|
||||||
<th data-i18n="itermRelaxCutoff"></th>
|
<th data-i18n="itermRelaxCutoff"></th>
|
||||||
<td>
|
<td>
|
||||||
|
@ -407,10 +380,17 @@
|
||||||
<table class="settings-table settings-table--filtering">
|
<table class="settings-table settings-table--filtering">
|
||||||
<tbody>
|
<tbody>
|
||||||
<tr>
|
<tr>
|
||||||
<th data-i18n="d_boost_factor"></th>
|
<th data-i18n="d_boost_min"></th>
|
||||||
<td>
|
<td>
|
||||||
<input data-setting="d_boost_factor" class="rate-tpa_input" />
|
<input data-setting="d_boost_min" class="rate-tpa_input" />
|
||||||
<div class="helpicon cf_tip" data-i18n_title="d_boost_factor_help"></div>
|
<div class="helpicon cf_tip" data-i18n_title="d_boost_min_help"></div>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th data-i18n="d_boost_max"></th>
|
||||||
|
<td>
|
||||||
|
<input data-setting="d_boost_max" class="rate-tpa_input" />
|
||||||
|
<div class="helpicon cf_tip" data-i18n_title="d_boost_max_help"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
|
|
|
@ -54,6 +54,7 @@ TABS.programming.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
$('#save-button').click(function () {
|
$('#save-button').click(function () {
|
||||||
saveChainer.execute();
|
saveChainer.execute();
|
||||||
|
GUI.log(chrome.i18n.getMessage('programmingEepromSaved'));
|
||||||
});
|
});
|
||||||
|
|
||||||
helper.mspBalancedInterval.add('logic_conditions_pull', 100, 1, function () {
|
helper.mspBalancedInterval.add('logic_conditions_pull', 100, 1, function () {
|
||||||
|
|