mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-26 01:35:23 +03:00
Merge remote-tracking branch 'origin/release_5.1.0'
This commit is contained in:
commit
8fd2c5325a
17 changed files with 164 additions and 68 deletions
|
@ -2210,7 +2210,7 @@
|
||||||
"message": "Warning"
|
"message": "Warning"
|
||||||
},
|
},
|
||||||
"firmwareFlasherWarningText": {
|
"firmwareFlasherWarningText": {
|
||||||
"message": "Please do <span style=\"color: red\">not</span> try to flash <strong>non-iNAV</strong> hardware with this firmware flasher.<br />Do <span style=\"color: red\">not</span> <strong>disconnect</strong> the board or <strong>turn off</strong> your computer while flashing.<br /><br /><strong>Note: </strong>STM32 bootloader is stored in ROM, it cannot be bricked.<br /><strong>Note: </strong><span style=\"color: red\">Auto-Connect</span> is always disabled while you are inside firmware flasher.<br /><strong>Note: </strong>Make sure you have a backup; some upgrades/downgrades will wipe your configuration.<br /><strong>Note:</strong> If you have problems flashing try disconnecting all cables from your FC first, try rebooting, upgrade chrome, upgrade drivers.<br /><strong>Note:</strong> When flashing boards that have directly connected USB sockets (SPRacingF3Mini, Sparky, ColibriRace, etc) ensure you have read the USB Flashing section of the INAV manual and have the correct software and drivers installed"
|
"message": "Please do <span style=\"color: red\">not</span> try to flash <strong>non-iNAV</strong> hardware with this firmware flasher.<br />Do <span style=\"color: red\">not</span> <strong>disconnect</strong> the board or <strong>turn off</strong> your computer while flashing.<br /><br /><strong>Note: </strong>STM32 bootloader is stored in ROM, it cannot be bricked.<br /><!--strong>Note: </strong><span style=\"color: red\">Auto-Connect</span> is always disabled while you are inside firmware flasher.<br / --><strong>Note: </strong>Make sure you have a backup; some upgrades/downgrades will wipe your configuration.<br /><strong>Note:</strong> If you have problems flashing try disconnecting all cables from your FC first, try rebooting, upgrade chrome, upgrade drivers.<br /><strong>Note:</strong> When flashing boards that have directly connected USB sockets (Matek H743-SLIM, Holybro Kakute etc) ensure you have read the USB Flashing section of the INAV manual and have the correct software and drivers installed"
|
||||||
},
|
},
|
||||||
"firmwareFlasherRecoveryHead": {
|
"firmwareFlasherRecoveryHead": {
|
||||||
"message": "<strong>Recovery / Lost communication<strong>"
|
"message": "<strong>Recovery / Lost communication<strong>"
|
||||||
|
|
|
@ -287,19 +287,23 @@ helper.defaultsDialog = (function () {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "nav_fw_pos_z_p",
|
key: "nav_fw_pos_z_p",
|
||||||
value: 15
|
value: 25
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "nav_fw_pos_z_d",
|
key: "nav_fw_pos_z_i",
|
||||||
value: 5
|
value: 5
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_d",
|
||||||
|
value: 8
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "nav_fw_pos_xy_p",
|
key: "nav_fw_pos_xy_p",
|
||||||
value: 60
|
value: 55
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_turn_assist_pitch_gain",
|
key: "fw_turn_assist_pitch_gain",
|
||||||
value: 0.5
|
value: 0.4
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "max_angle_inclination_rll",
|
key: "max_angle_inclination_rll",
|
||||||
|
@ -359,11 +363,19 @@ helper.defaultsDialog = (function () {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "imu_acc_ignore_rate",
|
key: "imu_acc_ignore_rate",
|
||||||
value: 9
|
value: 7
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "imu_acc_ignore_slope",
|
key: "imu_acc_ignore_slope",
|
||||||
value: 5
|
value: 4
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_dcm_kp",
|
||||||
|
value: 1000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_dcm_ki",
|
||||||
|
value: 0
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "airmode_type",
|
key: "airmode_type",
|
||||||
|
@ -393,6 +405,22 @@ helper.defaultsDialog = (function () {
|
||||||
key: "nav_wp_radius",
|
key: "nav_wp_radius",
|
||||||
value: 5000
|
value: 5000
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_max_angle",
|
||||||
|
value: 45
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_motor_delay",
|
||||||
|
value: 100
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_max_altitude",
|
||||||
|
value: 5000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_climb_angle",
|
||||||
|
value: 25
|
||||||
|
},
|
||||||
],
|
],
|
||||||
"features": [
|
"features": [
|
||||||
{
|
{
|
||||||
|
@ -486,19 +514,23 @@ helper.defaultsDialog = (function () {
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "nav_fw_pos_z_p",
|
key: "nav_fw_pos_z_p",
|
||||||
value: 15
|
value: 35
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "nav_fw_pos_z_d",
|
key: "nav_fw_pos_z_i",
|
||||||
value: 5
|
value: 5
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_pos_z_d",
|
||||||
|
value: 10
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "nav_fw_pos_xy_p",
|
key: "nav_fw_pos_xy_p",
|
||||||
value: 60
|
value: 70
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "fw_turn_assist_pitch_gain",
|
key: "fw_turn_assist_pitch_gain",
|
||||||
value: 0.2
|
value: 0.3
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
key: "max_angle_inclination_rll",
|
key: "max_angle_inclination_rll",
|
||||||
|
@ -564,6 +596,14 @@ helper.defaultsDialog = (function () {
|
||||||
key: "imu_acc_ignore_slope",
|
key: "imu_acc_ignore_slope",
|
||||||
value: 5
|
value: 5
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "imu_dcm_kp",
|
||||||
|
value: 1000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "imu_dcm_ki",
|
||||||
|
value: 0
|
||||||
|
},
|
||||||
{
|
{
|
||||||
key: "airmode_type",
|
key: "airmode_type",
|
||||||
value: "STICK_CENTER_ONCE"
|
value: "STICK_CENTER_ONCE"
|
||||||
|
@ -592,6 +632,22 @@ helper.defaultsDialog = (function () {
|
||||||
key: "nav_wp_radius",
|
key: "nav_wp_radius",
|
||||||
value: 5000
|
value: 5000
|
||||||
},
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_max_angle",
|
||||||
|
value: 75
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_motor_delay",
|
||||||
|
value: 100
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_max_altitude",
|
||||||
|
value: 5000
|
||||||
|
},
|
||||||
|
{
|
||||||
|
key: "nav_fw_launch_climb_angle",
|
||||||
|
value: 25
|
||||||
|
},
|
||||||
],
|
],
|
||||||
"features": [
|
"features": [
|
||||||
{
|
{
|
||||||
|
|
2
js/fc.js
2
js/fc.js
|
@ -1246,7 +1246,7 @@ var FC = {
|
||||||
4: {
|
4: {
|
||||||
name: "Logic Condition",
|
name: "Logic Condition",
|
||||||
type: "range",
|
type: "range",
|
||||||
range: [0, 31],
|
range: [0, (LOGIC_CONDITIONS.getMaxLogicConditionCount()-1)],
|
||||||
default: 0
|
default: 0
|
||||||
},
|
},
|
||||||
5: {
|
5: {
|
||||||
|
|
15
js/gui.js
15
js/gui.js
|
@ -300,16 +300,27 @@ GUI_control.prototype.renderOperandValue = function ($container, operandMetadata
|
||||||
* @param {function} onChange
|
* @param {function} onChange
|
||||||
* @param {boolean} withAlways
|
* @param {boolean} withAlways
|
||||||
*/
|
*/
|
||||||
GUI_control.prototype.renderLogicConditionSelect = function ($container, logicConditions, current, onChange, withAlways) {
|
GUI_control.prototype.renderLogicConditionSelect = function ($container, logicConditions, current, onChange, withAlways, onlyEnabled) {
|
||||||
|
|
||||||
let $select = $container.append('<select class="mix-rule-condition">').find("select"),
|
let $select = $container.append('<select class="mix-rule-condition">').find("select"),
|
||||||
lcCount = logicConditions.getCount();
|
lcCount = logicConditions.getCount();
|
||||||
|
option = "";
|
||||||
|
|
||||||
if (withAlways) {
|
if (withAlways) {
|
||||||
$select.append('<option value="-1">Always</option>')
|
$select.append('<option value="-1">Always</option>')
|
||||||
}
|
}
|
||||||
for (let i = 0; i < lcCount ; i++) {
|
for (let i = 0; i < lcCount ; i++) {
|
||||||
$select.append('<option value="' + i + '">Logic Condition ' + i + ' </option>');
|
if (!onlyEnabled || i === current || (logicConditions.isEnabled(i))) {
|
||||||
|
option = '<option';
|
||||||
|
|
||||||
|
if (i === current && !logicConditions.isEnabled(i)) {
|
||||||
|
option+= ' class="lc_disabled"';
|
||||||
|
}
|
||||||
|
|
||||||
|
option+= ' value="' + i + '">Logic Condition ' + i + ' </option>';
|
||||||
|
|
||||||
|
$select.append(option);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
$select.val(current).change(onChange);
|
$select.val(current).change(onChange);
|
||||||
|
|
|
@ -42,8 +42,9 @@ function generateFilename(prefix, suffix) {
|
||||||
|
|
||||||
if (CONFIG) {
|
if (CONFIG) {
|
||||||
if (CONFIG.flightControllerIdentifier) {
|
if (CONFIG.flightControllerIdentifier) {
|
||||||
filename = CONFIG.flightControllerIdentifier + '_' + filename;
|
filename = CONFIG.flightControllerIdentifier + '_' + CONFIG.flightControllerVersion + "_" + filename;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (CONFIG.name && CONFIG.name.trim() !== '') {
|
if (CONFIG.name && CONFIG.name.trim() !== '') {
|
||||||
filename = filename + '_' + CONFIG.name.trim().replace(' ', '_');
|
filename = filename + '_' + CONFIG.name.trim().replace(' ', '_');
|
||||||
}
|
}
|
||||||
|
|
|
@ -218,9 +218,10 @@ let LogicCondition = function (enabled, activatorId, operation, operandAType, op
|
||||||
if (self.getEnabled()) {
|
if (self.getEnabled()) {
|
||||||
GUI.renderLogicConditionSelect(
|
GUI.renderLogicConditionSelect(
|
||||||
$e,
|
$e,
|
||||||
LOGIC_CONDITIONS,
|
LOGIC_CONDITIONS,
|
||||||
self.getActivatorId,
|
self.getActivatorId,
|
||||||
self.onActivatorChange,
|
self.onActivatorChange,
|
||||||
|
true,
|
||||||
true
|
true
|
||||||
);
|
);
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -28,6 +28,10 @@ let LogicConditionsCollection = function () {
|
||||||
return data.length
|
return data.length
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.isEnabled = function (lcID) {
|
||||||
|
return data[lcID].getEnabled();
|
||||||
|
}
|
||||||
|
|
||||||
self.open = function () {
|
self.open = function () {
|
||||||
self.render();
|
self.render();
|
||||||
$container.show();
|
$container.show();
|
||||||
|
|
|
@ -173,19 +173,20 @@ var Settings = (function () {
|
||||||
|
|
||||||
let dataStep = input.data("step");
|
let dataStep = input.data("step");
|
||||||
|
|
||||||
if (dataStep !== undefined) {
|
if (typeof dataStep === 'undefined') {
|
||||||
input.attr('step', dataStep);
|
dataStep = self.countDecimals(s.value);
|
||||||
} else {
|
dataStep = 1 / Math.pow(10, dataStep);
|
||||||
input.attr('step', "0.01");
|
input.data("step", dataStep);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
input.attr('step', dataStep);
|
||||||
input.attr('min', s.setting.min);
|
input.attr('min', s.setting.min);
|
||||||
input.attr('max', s.setting.max);
|
input.attr('max', s.setting.max);
|
||||||
input.val(s.value.toFixed(2));
|
input.val(s.value.toFixed(self.countDecimals(dataStep)));
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
|
||||||
|
|
||||||
|
input.data("step", 1);
|
||||||
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
|
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
|
||||||
input.attr('type', 'number');
|
input.attr('type', 'number');
|
||||||
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
|
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
|
||||||
|
@ -449,7 +450,7 @@ var Settings = (function () {
|
||||||
'm-lrg' : 'mi',
|
'm-lrg' : 'mi',
|
||||||
'cms' : 'mph',
|
'cms' : 'mph',
|
||||||
'v-cms' : 'fts',
|
'v-cms' : 'fts',
|
||||||
'decadegps' : 'degpd',
|
'decadegps' : 'degps',
|
||||||
'decideg' : 'deg',
|
'decideg' : 'deg',
|
||||||
'decideg-lrg' : 'deg',
|
'decideg-lrg' : 'deg',
|
||||||
'msec' : 'sec',
|
'msec' : 'sec',
|
||||||
|
@ -498,38 +499,33 @@ var Settings = (function () {
|
||||||
const multiplier = multiObj.multiplier;
|
const multiplier = multiObj.multiplier;
|
||||||
const unitName = multiObj.unitName;
|
const unitName = multiObj.unitName;
|
||||||
|
|
||||||
|
let decimalPlaces = 0;
|
||||||
// Update the step, min, and max; as we have the multiplier here.
|
// Update the step, min, and max; as we have the multiplier here.
|
||||||
if (element.attr('type') == 'number') {
|
if (element.attr('type') == 'number') {
|
||||||
let step = element.attr('step') || 1;
|
let step = parseFloat(element.attr('step')) || 1;
|
||||||
let decimalPlaces = 0;
|
|
||||||
|
|
||||||
step = step / multiplier;
|
if (multiplier !== 1) {
|
||||||
|
decimalPlaces = Math.min(Math.ceil(multiplier / 100), 3);
|
||||||
if (step < 1) {
|
|
||||||
decimalPlaces = step.toString().length - step.toString().indexOf(".") - 1;
|
|
||||||
if (parseInt(step.toString().slice(-1)) > 1 ) {
|
|
||||||
decimalPlaces--;
|
|
||||||
}
|
|
||||||
step = 1 / Math.pow(10, decimalPlaces);
|
step = 1 / Math.pow(10, decimalPlaces);
|
||||||
}
|
}
|
||||||
element.attr('step', step.toFixed(decimalPlaces));
|
element.attr('step', step.toFixed(decimalPlaces));
|
||||||
|
|
||||||
if (multiplier != 'FAHREN') {
|
if (multiplier !== 'FAHREN' && multiplier !== 1) {
|
||||||
element.attr('min', (element.attr('min') / multiplier).toFixed(decimalPlaces));
|
element.attr('min', (parseFloat(element.attr('min')) / multiplier).toFixed(decimalPlaces));
|
||||||
element.attr('max', (element.attr('max') / multiplier).toFixed(decimalPlaces));
|
element.attr('max', (parseFloat(element.attr('max')) / multiplier).toFixed(decimalPlaces));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update the input with a new formatted unit
|
// Update the input with a new formatted unit
|
||||||
let newValue = "";
|
let newValue = "";
|
||||||
if (multiplier == 'FAHREN') {
|
if (multiplier === 'FAHREN') {
|
||||||
element.attr('min', toFahrenheit(element.attr('min')).toFixed(2));
|
element.attr('min', toFahrenheit(element.attr('min')).toFixed(decimalPlaces));
|
||||||
element.attr('max', toFahrenheit(element.attr('max')).toFixed(2));
|
element.attr('max', toFahrenheit(element.attr('max')).toFixed(decimalPlaces));
|
||||||
newValue = toFahrenheit(oldValue).toFixed(2);
|
newValue = toFahrenheit(oldValue).toFixed(decimalPlaces);
|
||||||
} else {
|
} else {
|
||||||
const convertedValue = Number((oldValue / multiplier).toFixed(2));
|
newValue = Number((oldValue / multiplier)).toFixed(decimalPlaces);
|
||||||
newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
element.val(newValue);
|
element.val(newValue);
|
||||||
element.data('setting-multiplier', multiplier);
|
element.data('setting-multiplier', multiplier);
|
||||||
|
|
||||||
|
@ -564,12 +560,36 @@ var Settings = (function () {
|
||||||
value = Math.round(((parseFloat(input.val())-32) / 1.8) * 10);
|
value = Math.round(((parseFloat(input.val())-32) / 1.8) * 10);
|
||||||
} else {
|
} else {
|
||||||
multiplier = parseFloat(multiplier);
|
multiplier = parseFloat(multiplier);
|
||||||
value = Math.round(parseFloat(input.val()) * multiplier);
|
|
||||||
|
let presicion = input.data("step") || 1; // data-step is always based on the default firmware units.
|
||||||
|
presicion = self.countDecimals(presicion);
|
||||||
|
|
||||||
|
if (presicion === 0) {
|
||||||
|
value = Math.round(parseFloat(input.val()) * multiplier);
|
||||||
|
} else {
|
||||||
|
value = Math.round((parseFloat(input.val()) * multiplier) * Math.pow(10, presicion)) / Math.pow(10, presicion);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return mspHelper.setSetting(settingName, value);
|
return mspHelper.setSetting(settingName, value);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
self.countDecimals = function(value) {
|
||||||
|
let text = value.toString()
|
||||||
|
// verify if number 0.000005 is represented as "5e-6"
|
||||||
|
if (text.indexOf('e-') > -1) {
|
||||||
|
let [base, trail] = text.split('e-');
|
||||||
|
let deg = parseInt(trail, 10);
|
||||||
|
return deg;
|
||||||
|
}
|
||||||
|
// count decimals for number in representation like "0.123456"
|
||||||
|
if (Math.floor(value) !== value) {
|
||||||
|
return value.toString().split(".")[1].length || 0;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
};
|
||||||
|
|
||||||
self.saveInputs = function() {
|
self.saveInputs = function() {
|
||||||
var inputs = [];
|
var inputs = [];
|
||||||
$('[data-setting!=""][data-setting]').each(function() {
|
$('[data-setting!=""][data-setting]').each(function() {
|
||||||
|
|
4
main.css
4
main.css
|
@ -2010,6 +2010,10 @@ select {
|
||||||
padding: 1px;
|
padding: 1px;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.lc_disabled {
|
||||||
|
color: #aaa;
|
||||||
|
}
|
||||||
|
|
||||||
.ic_osd {
|
.ic_osd {
|
||||||
background-image: url("../images/icons/icon_osd.svg");
|
background-image: url("../images/icons/icon_osd.svg");
|
||||||
background-position-y: 4px;
|
background-position-y: 4px;
|
||||||
|
|
|
@ -81,18 +81,22 @@
|
||||||
background-color: #e4e4e4;
|
background-color: #e4e4e4;
|
||||||
border-bottom: 5px solid white;
|
border-bottom: 5px solid white;
|
||||||
color: grey;
|
color: grey;
|
||||||
min-width: 100px;
|
height: 85px;
|
||||||
|
width: 130px;
|
||||||
|
padding: 0px 5px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-auxiliary .mode .info .name {
|
.tab-auxiliary .mode .info .name {
|
||||||
font-weight: bold;
|
font-weight: bold;
|
||||||
font-size: 1.0em;
|
font-size: 1.0em;
|
||||||
|
padding-bottom: 5px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-auxiliary .mode .info .buttons {
|
.tab-auxiliary .mode .info .buttons {
|
||||||
position: absolute;
|
position: absolute;
|
||||||
bottom: 14px;
|
bottom: 14px;
|
||||||
width: 100%;
|
width: 100%;
|
||||||
|
margin-left:-5px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-auxiliary .mode .info .buttons a {
|
.tab-auxiliary .mode .info .buttons a {
|
||||||
|
|
|
@ -15,33 +15,16 @@
|
||||||
<label for="launchIdleThr"><span data-i18n="configurationLaunchIdleThr"></span></label>
|
<label for="launchIdleThr"><span data-i18n="configurationLaunchIdleThr"></span></label>
|
||||||
<div for="launchIdleThr" class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div>
|
<div for="launchIdleThr" class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleThrHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="launchIdleDelay" data-unit="msec" data-setting="nav_fw_launch_idle_motor_delay" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
<input type="number" id="launchIdleDelay" data-unit="msec" data-setting="nav_fw_launch_idle_motor_delay" data-setting-multiplier="1" step="1" min="0" max="60000" />
|
||||||
<label for="launchIdleDelay"><span data-i18n="configurationLaunchIdleDelay"></span></label>
|
<label for="launchIdleDelay"><span data-i18n="configurationLaunchIdleDelay"></span></label>
|
||||||
<div for="launchIdleDelay" class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleDelayHelp"></div>
|
<div for="launchIdleDelay" class="helpicon cf_tip" data-i18n_title="configurationLaunchIdleDelayHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="launchMaxAngle" data-unit="deg" data-setting="nav_fw_launch_max_angle" data-setting-multiplier="1" step="1" min="5" max="180" />
|
<input type="number" id="launchMaxAngle" data-unit="deg" data-setting="nav_fw_launch_max_angle" data-setting-multiplier="1" step="1" min="5" max="180" />
|
||||||
<label for="launchMaxAngle"><span data-i18n="configurationLaunchMaxAngle"></span></label>
|
<label for="launchMaxAngle"><span data-i18n="configurationLaunchMaxAngle"></span></label>
|
||||||
<div for="launchMaxAngle" class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div>
|
<div for="launchMaxAngle" class="helpicon cf_tip" data-i18n_title="configurationLaunchMaxAngleHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchVelocity" data-unit="cms" data-setting="nav_fw_launch_velocity" data-setting-multiplier="1" step="1" min="100" max="10000" />
|
|
||||||
<label for="launchVelocity"><span data-i18n="configurationLaunchVelocity"></span></label>
|
|
||||||
<div for="launchVelocity" class="helpicon cf_tip" data-i18n_title="configurationLaunchVelocityHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchAccel" data-unit="cmss" data-setting="nav_fw_launch_accel" data-setting-multiplier="1" step="1" min="1000" max="20000" />
|
|
||||||
<label for="launchAccel"><span data-i18n="configurationLaunchAccel"></span></label>
|
|
||||||
<div for="launchAccel" class="helpicon cf_tip" data-i18n_title="configurationLaunchAccelHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<input type="number" id="launchDetectTime" data-unit="msec-nc" data-setting="nav_fw_launch_detect_time" data-setting-multiplier="1" step="1" min="10" max="1000" />
|
|
||||||
<label for="launchDetectTime"><span data-i18n="configurationLaunchDetectTime"></span></label>
|
|
||||||
<div for="launchDetectTime" class="helpicon cf_tip" data-i18n_title="configurationLaunchDetectTimeHelp"></div>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="launchMotorDelay" data-unit="msec-nc" data-setting="nav_fw_launch_motor_delay" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
<input type="number" id="launchMotorDelay" data-unit="msec-nc" data-setting="nav_fw_launch_motor_delay" data-setting-multiplier="1" step="1" min="0" max="5000" />
|
||||||
<label for="launchMotorDelay"><span data-i18n="configurationLaunchMotorDelay"></span></label>
|
<label for="launchMotorDelay"><span data-i18n="configurationLaunchMotorDelay"></span></label>
|
||||||
|
@ -57,7 +40,7 @@
|
||||||
<label for="launchSpinupTime"><span data-i18n="configurationLaunchSpinupTime"></span></label>
|
<label for="launchSpinupTime"><span data-i18n="configurationLaunchSpinupTime"></span></label>
|
||||||
<div for="launchSpinupTime" class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div>
|
<div for="launchSpinupTime" class="helpicon cf_tip" data-i18n_title="configurationLaunchSpinupTimeHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="number">
|
<div class="number">
|
||||||
<input type="number" id="launchThr" data-unit="us" data-setting="nav_fw_launch_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
<input type="number" id="launchThr" data-unit="us" data-setting="nav_fw_launch_thr" data-setting-multiplier="1" step="1" min="1000" max="2000" />
|
||||||
<label for="launchThr"><span data-i18n="configurationLaunchThr"></span></label>
|
<label for="launchThr"><span data-i18n="configurationLaunchThr"></span></label>
|
||||||
<div for="launchThr" class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div>
|
<div for="launchThr" class="helpicon cf_tip" data-i18n_title="configurationLaunchThrHelp"></div>
|
||||||
|
|
|
@ -18,7 +18,15 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_data() {
|
function get_rc_data() {
|
||||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
if (SERIAL_CONFIG.ports.length == 0) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_RC, false, false, get_ports_data);
|
||||||
|
} else {
|
||||||
|
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function get_ports_data() {
|
||||||
|
MSP.send_message(MSPCodes.MSP2_CF_SERIAL_CONFIG, false, false, load_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
|
@ -33,8 +41,8 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
modeSections["Arming"] = ["ARM", "PREARM"];
|
modeSections["Arming"] = ["ARM", "PREARM"];
|
||||||
modeSections["Flight Modes"] = ["ANGLE", "HORIZON", "MANUAL"];
|
modeSections["Flight Modes"] = ["ANGLE", "HORIZON", "MANUAL"];
|
||||||
modeSections["Navigation Modes"] = ["NAV COURSE HOLD", "NAV CRUISE", "NAV POSHOLD", "NAV RTH", "NAV WP", "GCS NAV"];
|
modeSections["Navigation Modes"] = ["NAV COURSE HOLD", "NAV CRUISE", "NAV POSHOLD", "NAV RTH", "NAV WP", "GCS NAV"];
|
||||||
modeSections["Flight Mode Modifiers"] = ["NAV ALTHOLD", "HEADING HOLD", "AIR MODE", "SOARING", "SURFACE"];
|
modeSections["Flight Mode Modifiers"] = ["NAV ALTHOLD", "HEADING HOLD", "AIR MODE", "SOARING", "SURFACE", "TURN ASSIST"];
|
||||||
modeSections["Fixed Wing"] = ["AUTO TUNE", "SERVO AUTOTRIM", "AUTO LEVEL", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON", "TURN ASSIST"];
|
modeSections["Fixed Wing"] = ["AUTO TUNE", "SERVO AUTOTRIM", "AUTO LEVEL", "NAV LAUNCH", "LOITER CHANGE", "FLAPERON"];
|
||||||
modeSections["Multi-rotor"] = ["FPV ANGLE MIX", "TURTLE", "MC BRAKING", "HEADFREE", "HEADADJ"];
|
modeSections["Multi-rotor"] = ["FPV ANGLE MIX", "TURTLE", "MC BRAKING", "HEADFREE", "HEADADJ"];
|
||||||
modeSections["OSD Modes"] = ["OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3"];
|
modeSections["OSD Modes"] = ["OSD OFF", "OSD ALT 1", "OSD ALT 2", "OSD ALT 3"];
|
||||||
modeSections["FPV Camera Modes"] = ["CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3"];
|
modeSections["FPV Camera Modes"] = ["CAMSTAB", "CAMERA CONTROL 1", "CAMERA CONTROL 2", "CAMERA CONTROL 3"];
|
||||||
|
@ -203,7 +211,6 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
let modeSelectionRange = "";
|
let modeSelectionRange = "";
|
||||||
|
|
||||||
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
||||||
|
|
||||||
// Get current mode category
|
// Get current mode category
|
||||||
for (modeSelectionRange in modeSections) {
|
for (modeSelectionRange in modeSections) {
|
||||||
if (modeSections[modeSelectionRange].indexOf(AUX_CONFIG[modeIndex]) != -1) {
|
if (modeSections[modeSelectionRange].indexOf(AUX_CONFIG[modeIndex]) != -1) {
|
||||||
|
|
|
@ -301,6 +301,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||||
function () {
|
function () {
|
||||||
servoRule.setConditionId($(this).val());
|
servoRule.setConditionId($(this).val());
|
||||||
},
|
},
|
||||||
|
true,
|
||||||
true
|
true
|
||||||
);
|
);
|
||||||
|
|
||||||
|
|
|
@ -248,7 +248,7 @@
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box grey switch-indicator-container">
|
<div class="gui_box grey switch-indicator-container">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" data-i18n="osd_switch_indicator_settings"></div>
|
<div class="spacer_box_title" data-i18n="osd_switch_indicator_settings"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -502,6 +502,7 @@ OSD.DjiElements = {
|
||||||
"Timers",
|
"Timers",
|
||||||
"VTX",
|
"VTX",
|
||||||
"CRSF",
|
"CRSF",
|
||||||
|
"SwitchIndicators",
|
||||||
"GVars",
|
"GVars",
|
||||||
"PIDs",
|
"PIDs",
|
||||||
"PIDOutputs",
|
"PIDOutputs",
|
||||||
|
@ -2617,6 +2618,8 @@ OSD.GUI.updateDjiView = function(on) {
|
||||||
$(element).hide();
|
$(element).hide();
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
|
$('.switch-indicator-container').hide();
|
||||||
} else {
|
} else {
|
||||||
$(OSD.DjiElements.emptyGroups).each(function(index, groupName) {
|
$(OSD.DjiElements.emptyGroups).each(function(index, groupName) {
|
||||||
$('#osdGroup' + groupName).show();
|
$('#osdGroup' + groupName).show();
|
||||||
|
@ -2629,6 +2632,8 @@ OSD.GUI.updateDjiView = function(on) {
|
||||||
$('.settings-container, .alarms-container').find('.settings').children()
|
$('.settings-container, .alarms-container').find('.settings').children()
|
||||||
.show()
|
.show()
|
||||||
.removeClass('no-bottom');
|
.removeClass('no-bottom');
|
||||||
|
|
||||||
|
$('.switch-indicator-container').show();
|
||||||
}
|
}
|
||||||
OSD.GUI.updateDjiMessageElements($('#useCraftnameForMessages').is(':checked'));
|
OSD.GUI.updateDjiMessageElements($('#useCraftnameForMessages').is(':checked'));
|
||||||
};
|
};
|
||||||
|
|
|
@ -496,7 +496,7 @@
|
||||||
<tr>
|
<tr>
|
||||||
<th data-i18n="pidTuning_d_boost_max_at_acceleration"></th>
|
<th data-i18n="pidTuning_d_boost_max_at_acceleration"></th>
|
||||||
<td>
|
<td>
|
||||||
<div class="pidTuning_number"><input id="dBoostMaxAccel" type="number" class="rate-tpa_input" data-setting="d_boost_max_at_acceleration" data-step="0.001" /></div>
|
<div class="pidTuning_number"><input id="dBoostMaxAccel" type="number" class="rate-tpa_input" data-setting="d_boost_max_at_acceleration" /></div>
|
||||||
<div for="dBoostMaxAccel" class="helpicon cf_tip" data-i18n_title="pidTuning_d_boost_max_at_acceleration_help"></div>
|
<div for="dBoostMaxAccel" class="helpicon cf_tip" data-i18n_title="pidTuning_d_boost_max_at_acceleration_help"></div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
|
|
|
@ -40,7 +40,6 @@ TABS.programming.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function processHtml() {
|
function processHtml() {
|
||||||
|
|
||||||
LOGIC_CONDITIONS.init($('#subtab-lc'));
|
LOGIC_CONDITIONS.init($('#subtab-lc'));
|
||||||
LOGIC_CONDITIONS.render();
|
LOGIC_CONDITIONS.render();
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue