mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-24 08:45:26 +03:00
various code improvements
This commit is contained in:
parent
706cb4c36f
commit
b68f9a15c4
4 changed files with 440 additions and 484 deletions
144
js/fc.js
144
js/fc.js
|
@ -132,7 +132,7 @@ var FC = {
|
|||
mspBaudRate: 0,
|
||||
gpsBaudRate: 0,
|
||||
gpsPassthroughBaudRate: 0,
|
||||
cliBaudRate: 0,
|
||||
cliBaudRate: 0
|
||||
};
|
||||
|
||||
SENSOR_DATA = {
|
||||
|
@ -258,7 +258,7 @@ var FC = {
|
|||
state: 0,
|
||||
filesystemLastError: 0,
|
||||
freeSizeKB: 0,
|
||||
totalSizeKB: 0,
|
||||
totalSizeKB: 0
|
||||
};
|
||||
|
||||
BLACKBOX = {
|
||||
|
@ -413,27 +413,157 @@ var FC = {
|
|||
tick: 125,
|
||||
defaultDenominator: 16,
|
||||
label: "256Hz"
|
||||
}, {
|
||||
},
|
||||
{
|
||||
tick: 1000,
|
||||
defaultDenominator: 2,
|
||||
label: "188Hz"
|
||||
}, {
|
||||
},
|
||||
{
|
||||
tick: 1000,
|
||||
defaultDenominator: 2,
|
||||
label: "98Hz"
|
||||
}, {
|
||||
},
|
||||
{
|
||||
tick: 1000,
|
||||
defaultDenominator: 2,
|
||||
label: "42Hz"
|
||||
}, {
|
||||
},
|
||||
{
|
||||
tick: 1000,
|
||||
defaultDenominator: 2,
|
||||
label: "20Hz"
|
||||
}, {
|
||||
},
|
||||
{
|
||||
tick: 1000,
|
||||
defaultDenominator: 2,
|
||||
label: "10Hz"
|
||||
}
|
||||
];
|
||||
},
|
||||
getGpsProtocols: function () {
|
||||
return [
|
||||
'NMEA',
|
||||
'UBLOX',
|
||||
'I2C-NAV',
|
||||
'DJI NAZA'
|
||||
]
|
||||
},
|
||||
getGpsBaudRates: function () {
|
||||
return [
|
||||
'115200',
|
||||
'57600',
|
||||
'38400',
|
||||
'19200',
|
||||
'9600'
|
||||
];
|
||||
},
|
||||
getGpsSbasProviders: function () {
|
||||
return [
|
||||
'Autodetect',
|
||||
'European EGNOS',
|
||||
'North American WAAS',
|
||||
'Japanese MSAS',
|
||||
'Indian GAGAN',
|
||||
'Disabled'
|
||||
];
|
||||
},
|
||||
getSerialRxTypes: function () {
|
||||
return [
|
||||
'SPEKTRUM1024',
|
||||
'SPEKTRUM2048',
|
||||
'SBUS',
|
||||
'SUMD',
|
||||
'SUMH',
|
||||
'XBUS_MODE_B',
|
||||
'XBUS_MODE_B_RJ01',
|
||||
'IBUS'
|
||||
];
|
||||
},
|
||||
getNrf24ProtocolTypes: function () {
|
||||
return [
|
||||
'V202 250Kbps',
|
||||
'V202 1Mbps',
|
||||
'Syma X',
|
||||
'Syma X5C',
|
||||
'Cheerson CX10',
|
||||
'Cheerson CX10A',
|
||||
'JJRC H8_3D',
|
||||
'iNav Reference protocol'
|
||||
];
|
||||
},
|
||||
getSensorAlignments: function () {
|
||||
return [
|
||||
'CW 0°',
|
||||
'CW 90°',
|
||||
'CW 180°',
|
||||
'CW 270°',
|
||||
'CW 0° flip',
|
||||
'CW 90° flip',
|
||||
'CW 180° flip',
|
||||
'CW 270° flip'
|
||||
];
|
||||
},
|
||||
getEscProtocols: function () {
|
||||
return {
|
||||
0: {
|
||||
name: "STANDARD",
|
||||
defaultRate: 400,
|
||||
rates: {
|
||||
50: "50Hz",
|
||||
400: "400Hz"
|
||||
}
|
||||
},
|
||||
1: {
|
||||
name: "ONESHOT125",
|
||||
defaultRate: 1000,
|
||||
rates: {
|
||||
400: "400Hz",
|
||||
1000: "1kHz",
|
||||
2000: "2kHz"
|
||||
}
|
||||
},
|
||||
2: {
|
||||
name: "ONESHOT42",
|
||||
defaultRate: 2000,
|
||||
rates: {
|
||||
400: "400Hz",
|
||||
1000: "1kHz",
|
||||
2000: "2kHz",
|
||||
4000: "4kHz",
|
||||
8000: "8kHz"
|
||||
}
|
||||
},
|
||||
3: {
|
||||
name: "MULTISHOT",
|
||||
defaultRate: 2000,
|
||||
rates: {
|
||||
400: "400Hz",
|
||||
1000: "1kHz",
|
||||
2000: "2kHz",
|
||||
4000: "4kHz",
|
||||
8000: "8kHz"
|
||||
}
|
||||
},
|
||||
4: {
|
||||
name: "BRUSHED",
|
||||
defaultRate: 8000,
|
||||
rates: {
|
||||
8000: "8kHz",
|
||||
16000: "16kHz",
|
||||
32000: "32kHz"
|
||||
}
|
||||
}
|
||||
};
|
||||
},
|
||||
getServoRates: function () {
|
||||
return {
|
||||
50: "50Hz",
|
||||
60: "60Hz",
|
||||
100: "100Hz",
|
||||
200: "200Hz",
|
||||
400: "400Hz"
|
||||
};
|
||||
}
|
||||
|
||||
};
|
||||
|
|
|
@ -9,28 +9,42 @@ function localize() {
|
|||
return chrome.i18n.getMessage(messageID);
|
||||
};
|
||||
|
||||
$('[i18n]:not(.i18n-replaced').each(function() {
|
||||
$('[i18n]:not(.i18n-replaced)').each(function() {
|
||||
var element = $(this);
|
||||
|
||||
element.html(translate(element.attr('i18n')));
|
||||
element.addClass('i18n-replaced');
|
||||
});
|
||||
|
||||
$('[i18n_title]:not(.i18n_title-replaced').each(function() {
|
||||
$('[data-i18n]:not(.i18n-replaced)').each(function() {
|
||||
var element = $(this);
|
||||
|
||||
element.html(translate(element.data('i18n')));
|
||||
element.addClass('i18n-replaced');
|
||||
});
|
||||
|
||||
$('[i18n_title]:not(.i18n_title-replaced)').each(function() {
|
||||
var element = $(this);
|
||||
|
||||
element.attr('title', translate(element.attr('i18n_title')));
|
||||
element.addClass('i18n_title-replaced');
|
||||
});
|
||||
|
||||
$('[i18n_value]:not(.i18n_value-replaced').each(function() {
|
||||
$('[data-i18n_title]:not(.i18n_title-replaced)').each(function() {
|
||||
var element = $(this);
|
||||
|
||||
element.attr('title', translate(element.data('i18n_title')));
|
||||
element.addClass('i18n_title-replaced');
|
||||
});
|
||||
|
||||
$('[i18n_value]:not(.i18n_value-replaced)').each(function() {
|
||||
var element = $(this);
|
||||
|
||||
element.val(translate(element.attr('i18n_value')));
|
||||
element.addClass('i18n_value-replaced');
|
||||
});
|
||||
|
||||
$('[i18n_placeholder]:not(.i18n_placeholder-replaced').each(function() {
|
||||
$('[i18n_placeholder]:not(.i18n_placeholder-replaced)').each(function() {
|
||||
var element = $(this);
|
||||
|
||||
element.attr('placeholder', translate(element.attr('i18n_placeholder')));
|
||||
|
|
|
@ -1,18 +1,18 @@
|
|||
<div class="tab-configuration toolbar_fixed_bottom">
|
||||
<div class="content_wrapper">
|
||||
<div class="tab_title" i18n="tabConfiguration">Configuration</div>
|
||||
<div class="tab_title" data-i18n="tabConfiguration">Configuration</div>
|
||||
<div class="cf_doc_version_bt">
|
||||
<a id="button-documentation" href="https://github.com/iNavFlight/inav/releases" target="_blank"></a>
|
||||
</div>
|
||||
<div class="note" style="margin-bottom: 20px;">
|
||||
<div class="note_spacer">
|
||||
<p i18n="configurationFeaturesHelp"></p>
|
||||
<p data-i18n="configurationFeaturesHelp"></p>
|
||||
</div>
|
||||
</div>
|
||||
<div class="leftWrapper mixer">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationMixer"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationMixer"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<div class="mixerPreview half">
|
||||
|
@ -29,7 +29,7 @@
|
|||
<div class="rightWrapper motorstop">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationEscFeatures"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationEscFeatures"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
|
||||
|
@ -43,14 +43,14 @@
|
|||
<div class="select">
|
||||
<select name="esc-protocol" id="esc-protocol"></select>
|
||||
<label for="esc-protocol"> <span class="freelabel"
|
||||
i18n="escProtocol"></span></label>
|
||||
<div class="helpicon cf_tip" i18n_title="escProtocolHelp"></div>
|
||||
data-i18n="escProtocol"></span></label>
|
||||
<div class="helpicon cf_tip" data-i18n_title="escProtocolHelp"></div>
|
||||
</div>
|
||||
<div class="select">
|
||||
<select name="esc-rate" id="esc-rate"></select>
|
||||
<label for="esc-refresh-rate"> <span class="freelabel"
|
||||
i18n="escRefreshRate"></span></label>
|
||||
<div class="helpicon cf_tip" i18n_title="escRefreshRatelHelp"></div>
|
||||
<label for="esc-rate"> <span class="freelabel"
|
||||
data-i18n="escRefreshRate"></span></label>
|
||||
<div class="helpicon cf_tip" data-i18n_title="escRefreshRatelHelp"></div>
|
||||
</div>
|
||||
<div class="clear-both"></div>
|
||||
</div>
|
||||
|
@ -59,8 +59,8 @@
|
|||
<div class="select">
|
||||
<select name="servo-rate" id="servo-rate"></select>
|
||||
<label for="servo-rate"> <span class="freelabel"
|
||||
i18n="servoRefreshRate"></span></label>
|
||||
<div class="helpicon cf_tip" i18n_title="servoRefreshRatelHelp"></div>
|
||||
data-i18n="servoRefreshRate"></span></label>
|
||||
<div class="helpicon cf_tip" data-i18n_title="servoRefreshRatelHelp"></div>
|
||||
</div>
|
||||
<div class="clear-both"></div>
|
||||
</div>
|
||||
|
@ -75,10 +75,10 @@
|
|||
<div class="disarm">
|
||||
<div class="checkbox">
|
||||
<div style="float: left; height: 20px; margin-right: 15px; margin-left: 3px;">
|
||||
<input type="checkbox" name="disarmkillswitch" class="toggle" />
|
||||
<input type="checkbox" id="disarmkillswitch" name="disarmkillswitch" class="toggle" />
|
||||
</div>
|
||||
<label for="disarmkillswitch"> <span class="freelabel"
|
||||
i18n="configurationDisarmKillSwitch"></span>
|
||||
data-i18n="configurationDisarmKillSwitch"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number disarmdelay" style="display: none; margin-bottom: 5px;">
|
||||
|
@ -86,7 +86,7 @@
|
|||
<div class="numberspacer">
|
||||
<input type="number" name="autodisarmdelay" min="0" max="60" />
|
||||
</div>
|
||||
<span i18n="configurationAutoDisarmDelay"></span>
|
||||
<span data-i18n="configurationAutoDisarmDelay"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -96,7 +96,7 @@
|
|||
<div class="numberspacer">
|
||||
<input type="number" name="minthrottle" min="0" max="2000" />
|
||||
</div>
|
||||
<span i18n="configurationThrottleMinimum"></span>
|
||||
<span data-i18n="configurationThrottleMinimum"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
|
@ -104,7 +104,7 @@
|
|||
<div class="numberspacer">
|
||||
<input type="number" name="midthrottle" min="0" max="2000" />
|
||||
</div>
|
||||
<span i18n="configurationThrottleMid"></span>
|
||||
<span data-i18n="configurationThrottleMid"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
|
@ -112,7 +112,7 @@
|
|||
<div class="numberspacer">
|
||||
<input type="number" name="maxthrottle" min="0" max="2000" />
|
||||
</div>
|
||||
<span i18n="configurationThrottleMaximum"></span>
|
||||
<span data-i18n="configurationThrottleMaximum"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
|
@ -120,7 +120,7 @@
|
|||
<div class="numberspacer">
|
||||
<input type="number" name="mincommand" min="0" max="2000" />
|
||||
</div>
|
||||
<span i18n="configurationThrottleMinimumCommand"></span>
|
||||
<span data-i18n="configurationThrottleMinimumCommand"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -130,26 +130,26 @@
|
|||
<div class="leftWrapper board">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationBoardAlignment"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="configHelp2"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationBoardAlignment"></div>
|
||||
<div class="helpicon cf_tip" data-i18n_title="configHelp2"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<div class="board_align_content">
|
||||
<div class="number">
|
||||
<label> <input type="number" name="board_align_roll" step="0.1" min="-180" max="360" /> <span
|
||||
i18n="configurationBoardAlignmentRoll"></span>
|
||||
data-i18n="configurationBoardAlignmentRoll"></span>
|
||||
</label>
|
||||
<div class="alignicon roll"></div>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="board_align_pitch" step="0.1" min="-180" max="360" />
|
||||
<span i18n="configurationBoardAlignmentPitch"></span>
|
||||
<span data-i18n="configurationBoardAlignmentPitch"></span>
|
||||
</label>
|
||||
<div class="alignicon pitch"></div>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="board_align_yaw" step="0.1" min="-180" max="360" /> <span
|
||||
i18n="configurationBoardAlignmentYaw"></span>
|
||||
data-i18n="configurationBoardAlignmentYaw"></span>
|
||||
</label>
|
||||
<div class="alignicon yaw"></div>
|
||||
</div>
|
||||
|
@ -157,7 +157,7 @@
|
|||
<div class="sensoralignment">
|
||||
<div class="select">
|
||||
<label>
|
||||
<span i18n="configurationSensorAlignmentGyro"></span>
|
||||
<span data-i18n="configurationSensorAlignmentGyro"></span>
|
||||
<select class="gyroalign">
|
||||
<option value="0">Default</option>
|
||||
<!-- list generated here -->
|
||||
|
@ -166,7 +166,7 @@
|
|||
</div>
|
||||
<div class="select">
|
||||
<label>
|
||||
<span i18n="configurationSensorAlignmentAcc"></span>
|
||||
<span data-i18n="configurationSensorAlignmentAcc"></span>
|
||||
<select class="accalign">
|
||||
<option value="0">Default</option>
|
||||
<!-- list generated here -->
|
||||
|
@ -175,7 +175,7 @@
|
|||
</div>
|
||||
<div class="select">
|
||||
<label>
|
||||
<span i18n="configurationSensorAlignmentMag"></span>
|
||||
<span data-i18n="configurationSensorAlignmentMag"></span>
|
||||
<select class="magalign">
|
||||
<option value="0">Default</option>
|
||||
<!-- list generated here -->
|
||||
|
@ -189,7 +189,7 @@
|
|||
<div class="rightWrapper system">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationSystem"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationSystem"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
|
||||
|
@ -197,7 +197,7 @@
|
|||
<div class="numberspacer">
|
||||
<input type="checkbox" id="gyro-sync-checkbox" class="toggle" />
|
||||
</div>
|
||||
<label> <span i18n="configurationGyroSyncTitle"></span>
|
||||
<label> <span data-i18n="configurationGyroSyncTitle"></span>
|
||||
</label>
|
||||
</div>
|
||||
|
||||
|
@ -205,13 +205,13 @@
|
|||
|
||||
<div class="select requires-v1_4">
|
||||
<select id="gyro-lpf"></select>
|
||||
<label for="gyro-lpf"> <span i18n="configurationGyroLpfTitle"></span></label>
|
||||
<label for="gyro-lpf"> <span data-i18n="configurationGyroLpfTitle"></span></label>
|
||||
</div>
|
||||
|
||||
<div class="select">
|
||||
<select id="looptime"></select>
|
||||
<label for="looptime"> <span
|
||||
i18n="configurationLoopTime"></span>
|
||||
data-i18n="configurationLoopTime"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -221,15 +221,15 @@
|
|||
<div class="leftWrapper">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationReceiver"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationReceiver"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<table cellpadding="0" cellspacing="0">
|
||||
<thead>
|
||||
<tr>
|
||||
<th i18n="configurationFeatureEnabled"></th>
|
||||
<th i18n="configurationFeatureDescription"></th>
|
||||
<th i18n="configurationFeatureName"></th>
|
||||
<th data-i18n="configurationFeatureEnabled"></th>
|
||||
<th data-i18n="configurationFeatureDescription"></th>
|
||||
<th data-i18n="configurationFeatureName"></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody class="features rxMode">
|
||||
|
@ -240,12 +240,12 @@
|
|||
</div>
|
||||
<div class="gui_box grey rxprovider">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationSerialRX"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationSerialRX"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<div class="note">
|
||||
<div class="note_spacer">
|
||||
<p i18n="configurationSerialRXHelp"></p>
|
||||
<p data-i18n="configurationSerialRXHelp"></p>
|
||||
</div>
|
||||
</div>
|
||||
<select class="serialRX" size="8">
|
||||
|
@ -255,7 +255,7 @@
|
|||
</div>
|
||||
<div class="gui_box grey nrf24provider">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationNrf24Protocol"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationNrf24Protocol"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<select class="nrf24Protocol" size="8">
|
||||
|
@ -267,15 +267,15 @@
|
|||
<div class="rightWrapper current voltage">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationBatteryVoltage"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationBatteryVoltage"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<table cellpadding="0" cellspacing="0">
|
||||
<thead>
|
||||
<tr>
|
||||
<th i18n="configurationFeatureEnabled"></th>
|
||||
<th i18n="configurationFeatureDescription"></th>
|
||||
<th i18n="configurationFeatureName"></th>
|
||||
<th data-i18n="configurationFeatureEnabled"></th>
|
||||
<th data-i18n="configurationFeatureDescription"></th>
|
||||
<th data-i18n="configurationFeatureName"></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody class="features batteryVoltage">
|
||||
|
@ -284,42 +284,42 @@
|
|||
</table>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="mincellvoltage" step="0.1" min="1" max="5" /> <span
|
||||
i18n="configurationBatteryMinimum"></span>
|
||||
data-i18n="configurationBatteryMinimum"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="maxcellvoltage" step="0.1" min="1" max="5" /> <span
|
||||
i18n="configurationBatteryMaximum"></span>
|
||||
data-i18n="configurationBatteryMaximum"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="warningcellvoltage" step="0.1" min="1" max="5" /> <span
|
||||
i18n="configurationBatteryWarning"></span>
|
||||
data-i18n="configurationBatteryWarning"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="voltagescale" step="1" min="10" max="255" /> <span
|
||||
i18n="configurationBatteryScale"></span>
|
||||
data-i18n="configurationBatteryScale"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="text" name="batteryvoltage" readonly class="disabled" /> <span
|
||||
i18n="configurationBatteryVoltage"></span>
|
||||
data-i18n="configurationBatteryVoltage"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationCurrent"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationCurrent"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<table cellpadding="0" cellspacing="0">
|
||||
<thead>
|
||||
<tr>
|
||||
<th i18n="configurationFeatureEnabled"></th>
|
||||
<th i18n="configurationFeatureDescription"></th>
|
||||
<th i18n="configurationFeatureName"></th>
|
||||
<th data-i18n="configurationFeatureEnabled"></th>
|
||||
<th data-i18n="configurationFeatureDescription"></th>
|
||||
<th data-i18n="configurationFeatureName"></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody class="features batteryCurrent">
|
||||
|
@ -328,23 +328,24 @@
|
|||
</table>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="currentscale" step="1" min="-1000" max="1000" /> <span
|
||||
i18n="configurationCurrentScale"></span>
|
||||
data-i18n="configurationCurrentScale"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="currentoffset" step="1" min="0" max="3300" /> <span
|
||||
i18n="configurationCurrentOffset"></span>
|
||||
data-i18n="configurationCurrentOffset"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="text" name="batterycurrent" readonly class="disabled" /> <span
|
||||
i18n="configurationBatteryCurrent"></span>
|
||||
data-i18n="configurationBatteryCurrent"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="checkbox">
|
||||
<div class="numberspacer">
|
||||
<input type="checkbox" name="multiwiicurrentoutput" class="toggle" />
|
||||
</div>
|
||||
<label> <span i18n="configurationBatteryMultiwiiCurrent"></span>
|
||||
<label> <span data-i18n="configurationBatteryMultiwiiCurrent"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -354,20 +355,20 @@
|
|||
<div class="leftWrapper gps">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationGPS"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationGPS"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<div class="note">
|
||||
<div class="note_spacer">
|
||||
<p i18n="configurationGPSHelp"></p>
|
||||
<p data-i18n="configurationGPSHelp"></p>
|
||||
</div>
|
||||
</div>
|
||||
<table cellpadding="0" cellspacing="0">
|
||||
<thead>
|
||||
<tr>
|
||||
<th i18n="configurationFeatureEnabled"></th>
|
||||
<th i18n="configurationFeatureDescription"></th>
|
||||
<th i18n="configurationFeatureName"></th>
|
||||
<th data-i18n="configurationFeatureEnabled"></th>
|
||||
<th data-i18n="configurationFeatureDescription"></th>
|
||||
<th data-i18n="configurationFeatureName"></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody class="features gps">
|
||||
|
@ -378,23 +379,17 @@
|
|||
<select class="gps_protocol">
|
||||
<!-- list generated here -->
|
||||
</select>
|
||||
<span i18n="configurationGPSProtocol"></span>
|
||||
</div>
|
||||
<div class="line">
|
||||
<select class="gps_baudrate">
|
||||
<!-- list generated here -->
|
||||
</select>
|
||||
<span i18n="configurationGPSBaudrate"></span>
|
||||
<span data-i18n="configurationGPSProtocol"></span>
|
||||
</div>
|
||||
<div class="line">
|
||||
<select class="gps_ubx_sbas">
|
||||
<!-- list generated here -->
|
||||
</select>
|
||||
<span i18n="configurationGPSubxSbas"></span>
|
||||
<span data-i18n="configurationGPSubxSbas"></span>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="mag_declination" step="0.1" min="-180" max="180" />
|
||||
<span i18n="configurationMagDeclination"></span>
|
||||
<span data-i18n="configurationMagDeclination"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -403,15 +398,15 @@
|
|||
<div class="rightWrapper other">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationFeatures"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationFeatures"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<table cellpadding="0" cellspacing="0">
|
||||
<thead>
|
||||
<tr>
|
||||
<th i18n="configurationFeatureEnabled"></th>
|
||||
<th i18n="configurationFeatureDescription"></th>
|
||||
<th i18n="configurationFeatureName"></th>
|
||||
<th data-i18n="configurationFeatureEnabled"></th>
|
||||
<th data-i18n="configurationFeatureDescription"></th>
|
||||
<th data-i18n="configurationFeatureName"></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody class="features other" id="noline">
|
||||
|
@ -424,16 +419,16 @@
|
|||
<div class="leftWrapper rssi">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configurationRSSI"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="configurationRSSIHelp"></div>
|
||||
<div class="spacer_box_title" data-i18n="configurationRSSI"></div>
|
||||
<div class="helpicon cf_tip" data-i18n_title="configurationRSSIHelp"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<table cellpadding="0" cellspacing="0">
|
||||
<thead>
|
||||
<tr>
|
||||
<th i18n="configurationFeatureEnabled"></th>
|
||||
<th i18n="configurationFeatureDescription"></th>
|
||||
<th i18n="configurationFeatureName"></th>
|
||||
<th data-i18n="configurationFeatureEnabled"></th>
|
||||
<th data-i18n="configurationFeatureDescription"></th>
|
||||
<th data-i18n="configurationFeatureName"></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody class="features rssi">
|
||||
|
@ -446,27 +441,27 @@
|
|||
<div class="rightWrapper 3d">
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box_titlebar">
|
||||
<div class="spacer_box_title" i18n="configuration3d"></div>
|
||||
<div class="spacer_box_title" data-i18n="configuration3d"></div>
|
||||
</div>
|
||||
<div class="spacer_box">
|
||||
<div class="number">
|
||||
<label> <input type="number" name="3ddeadbandlow" step="1" min="1425" max="1500" /> <span
|
||||
i18n="configuration3dDeadbandLow"></span>
|
||||
data-i18n="configuration3dDeadbandLow"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="3ddeadbandhigh" step="1" min="1500" max="1575" /> <span
|
||||
i18n="configuration3dDeadbandHigh"></span>
|
||||
data-i18n="configuration3dDeadbandHigh"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number">
|
||||
<label> <input type="number" name="3dneutral" step="1" min="1475" max="1525" /> <span
|
||||
i18n="configuration3dNeutral"></span>
|
||||
data-i18n="configuration3dNeutral"></span>
|
||||
</label>
|
||||
</div>
|
||||
<div class="number 3ddeadbandthrottle" >
|
||||
<label> <input type="number" name="3ddeadbandthrottle" step="1" min="0" max="1000" /> <span
|
||||
i18n="configuration3dDeadbandThrottle"></span>
|
||||
data-i18n="configuration3dDeadbandThrottle"></span>
|
||||
</label>
|
||||
</div>
|
||||
</div>
|
||||
|
@ -476,7 +471,7 @@
|
|||
</div>
|
||||
<div class="content_toolbar">
|
||||
<div class="btn save_btn">
|
||||
<a class="save" href="#" i18n="configurationButtonSave"></a>
|
||||
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
|
|
@ -3,7 +3,6 @@
|
|||
TABS.configuration = {};
|
||||
|
||||
TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||
var self = this;
|
||||
|
||||
if (GUI.active_tab != 'configuration') {
|
||||
GUI.active_tab = 'configuration';
|
||||
|
@ -11,20 +10,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_serial_config);
|
||||
}
|
||||
|
||||
function load_serial_config() {
|
||||
var next_callback = load_rc_map;
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function load_rc_map() {
|
||||
MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_misc);
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_misc);
|
||||
}
|
||||
|
||||
function load_misc() {
|
||||
|
@ -32,21 +18,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_arming_config() {
|
||||
var next_callback = load_loop_time;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_ARMING_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_ARMING_CONFIG, false, false, load_loop_time);
|
||||
}
|
||||
|
||||
function load_loop_time() {
|
||||
var next_callback = load_rx_config;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_LOOP_TIME, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_LOOP_TIME, false, false, load_rx_config);
|
||||
}
|
||||
|
||||
function load_rx_config() {
|
||||
|
@ -59,21 +35,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_3d() {
|
||||
var next_callback = load_sensor_alignment;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_3D, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_3D, false, false, load_sensor_alignment);
|
||||
}
|
||||
|
||||
function load_sensor_alignment() {
|
||||
var next_callback = loadAdvancedConfig;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SENSOR_ALIGNMENT, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SENSOR_ALIGNMENT, false, false, loadAdvancedConfig);
|
||||
}
|
||||
|
||||
function loadAdvancedConfig() {
|
||||
|
@ -110,13 +76,15 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function process_html() {
|
||||
|
||||
var i;
|
||||
|
||||
var mixer_list_e = $('select.mixerList');
|
||||
for (var i = 0; i < mixerList.length; i++) {
|
||||
for (i = 0; i < mixerList.length; i++) {
|
||||
mixer_list_e.append('<option value="' + (i + 1) + '">' + mixerList[i].name + '</option>');
|
||||
}
|
||||
|
||||
mixer_list_e.change(function () {
|
||||
var val = parseInt($(this).val());
|
||||
var val = parseInt($(this).val(), 10);
|
||||
|
||||
BF_CONFIG.mixerConfiguration = val;
|
||||
|
||||
|
@ -132,7 +100,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
var radioGroups = [];
|
||||
|
||||
var features_e = $('.features');
|
||||
for (var i = 0; i < features.length; i++) {
|
||||
for (i = 0; i < features.length; i++) {
|
||||
var row_e;
|
||||
|
||||
var feature_tip_html = '';
|
||||
|
@ -153,7 +121,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
+ i
|
||||
+ '">'
|
||||
+ features[i].name
|
||||
+ '</label></td><td><span i18n="feature' + features[i].name + '"></span>'
|
||||
+ '</label></td><td><span data-i18n="feature' + features[i].name + '"></span>'
|
||||
+ feature_tip_html + '</td></tr>');
|
||||
radioGroups.push(features[i].group);
|
||||
} else {
|
||||
|
@ -167,7 +135,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
+ i
|
||||
+ '">'
|
||||
+ features[i].name
|
||||
+ '</label></td><td><span i18n="feature' + features[i].name + '"></span>'
|
||||
+ '</label></td><td><span data-i18n="feature' + features[i].name + '"></span>'
|
||||
+ feature_tip_html + '</td></tr>');
|
||||
|
||||
var feature_e = row_e.find('input.feature');
|
||||
|
@ -186,7 +154,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
// translate to user-selected language
|
||||
localize();
|
||||
|
||||
for (var i = 0; i < radioGroups.length; i++) {
|
||||
for (i = 0; i < radioGroups.length; i++) {
|
||||
var group = radioGroups[i];
|
||||
var controls_e = $('input[name="' + group + '"].feature');
|
||||
|
||||
|
@ -200,25 +168,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
|
||||
var alignments = [
|
||||
'CW 0°',
|
||||
'CW 90°',
|
||||
'CW 180°',
|
||||
'CW 270°',
|
||||
'CW 0° flip',
|
||||
'CW 90° flip',
|
||||
'CW 180° flip',
|
||||
'CW 270° flip'
|
||||
];
|
||||
var alignments = FC.getSensorAlignments();
|
||||
|
||||
var orientation_gyro_e = $('select.gyroalign');
|
||||
var orientation_acc_e = $('select.accalign');
|
||||
var orientation_mag_e = $('select.magalign');
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||
$('.tab-configuration .sensoralignment').hide();
|
||||
} else {
|
||||
for (var i = 0; i < alignments.length; i++) {
|
||||
for (i = 0; i < alignments.length; i++) {
|
||||
orientation_gyro_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
|
||||
orientation_acc_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
|
||||
orientation_mag_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
|
||||
|
@ -226,36 +182,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
orientation_gyro_e.val(SENSOR_ALIGNMENT.align_gyro);
|
||||
orientation_acc_e.val(SENSOR_ALIGNMENT.align_acc);
|
||||
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
|
||||
}
|
||||
|
||||
|
||||
// generate GPS
|
||||
var gpsProtocols = [
|
||||
'NMEA',
|
||||
'UBLOX',
|
||||
'I2C-NAV',
|
||||
'DJI NAZA',
|
||||
];
|
||||
|
||||
var gpsBaudRates = [
|
||||
'115200',
|
||||
'57600',
|
||||
'38400',
|
||||
'19200',
|
||||
'9600'
|
||||
];
|
||||
|
||||
var gpsSbas = [
|
||||
'Autodetect',
|
||||
'European EGNOS',
|
||||
'North American WAAS',
|
||||
'Japanese MSAS',
|
||||
'Indian GAGAN',
|
||||
'Disabled',
|
||||
];
|
||||
var gpsProtocols = FC.getGpsProtocols();
|
||||
var gpsSbas = FC.getGpsSbasProviders();
|
||||
|
||||
var gps_protocol_e = $('select.gps_protocol');
|
||||
for (var i = 0; i < gpsProtocols.length; i++) {
|
||||
for (i = 0; i < gpsProtocols.length; i++) {
|
||||
gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>');
|
||||
}
|
||||
|
||||
|
@ -265,24 +198,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
gps_protocol_e.val(MISC.gps_type);
|
||||
|
||||
|
||||
var gps_baudrate_e = $('select.gps_baudrate');
|
||||
for (var i = 0; i < gpsBaudRates.length; i++) {
|
||||
gps_baudrate_e.append('<option value="' + gpsBaudRates[i] + '">' + gpsBaudRates[i] + '</option>');
|
||||
}
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
gps_baudrate_e.change(function () {
|
||||
SERIAL_CONFIG.gpsBaudRate = parseInt($(this).val());
|
||||
});
|
||||
gps_baudrate_e.val(SERIAL_CONFIG.gpsBaudRate);
|
||||
} else {
|
||||
gps_baudrate_e.prop("disabled", true);
|
||||
gps_baudrate_e.parent().hide();
|
||||
}
|
||||
|
||||
var gps_ubx_sbas_e = $('select.gps_ubx_sbas');
|
||||
for (var i = 0; i < gpsSbas.length; i++) {
|
||||
for (i = 0; i < gpsSbas.length; i++) {
|
||||
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
|
||||
}
|
||||
|
||||
|
@ -294,20 +211,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
|
||||
// generate serial RX
|
||||
var serialRXtypes = [
|
||||
'SPEKTRUM1024',
|
||||
'SPEKTRUM2048',
|
||||
'SBUS',
|
||||
'SUMD',
|
||||
'SUMH',
|
||||
'XBUS_MODE_B',
|
||||
'XBUS_MODE_B_RJ01',
|
||||
'IBUS'
|
||||
];
|
||||
var serialRxTypes = FC.getSerialRxTypes();
|
||||
|
||||
var serialRX_e = $('select.serialRX');
|
||||
for (var i = 0; i < serialRXtypes.length; i++) {
|
||||
serialRX_e.append('<option value="' + i + '">' + serialRXtypes[i] + '</option>');
|
||||
for (i = 0; i < serialRxTypes.length; i++) {
|
||||
serialRX_e.append('<option value="' + i + '">' + serialRxTypes[i] + '</option>');
|
||||
}
|
||||
|
||||
serialRX_e.change(function () {
|
||||
|
@ -320,22 +228,14 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
// for some odd reason chrome 38+ changes scroll according to the touched select element
|
||||
// i am guessing this is a bug, since this wasn't happening on 37
|
||||
// code below is a temporary fix, which we will be able to remove in the future (hopefully)
|
||||
//noinspection JSValidateTypes
|
||||
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
||||
|
||||
var nrf24Protocoltypes = [
|
||||
'V202 250Kbps',
|
||||
'V202 1Mbps',
|
||||
'Syma X',
|
||||
'Syma X5C',
|
||||
'Cheerson CX10',
|
||||
'Cheerson CX10A',
|
||||
'JJRC H8_3D',
|
||||
'iNav Reference protocol'
|
||||
];
|
||||
var nrf24ProtocolTypes = FC.getNrf24ProtocolTypes();
|
||||
|
||||
var nrf24Protocol_e = $('select.nrf24Protocol');
|
||||
for (var i = 0; i < nrf24Protocoltypes.length; i++) {
|
||||
nrf24Protocol_e.append('<option value="' + i + '">' + nrf24Protocoltypes[i] + '</option>');
|
||||
for (i = 0; i < nrf24ProtocolTypes.length; i++) {
|
||||
nrf24Protocol_e.append('<option value="' + i + '">' + nrf24ProtocolTypes[i] + '</option>');
|
||||
}
|
||||
|
||||
nrf24Protocol_e.change(function () {
|
||||
|
@ -355,15 +255,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$('input[name="mag_declination"]').val(MISC.mag_declination);
|
||||
|
||||
//fill motor disarm params and FC loop time
|
||||
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
$('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay);
|
||||
$('input[name="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch);
|
||||
$('div.disarm').show();
|
||||
if(bit_check(BF_CONFIG.features, 4))//MOTOR_STOP
|
||||
if(bit_check(BF_CONFIG.features, 4)) {//MOTOR_STOP
|
||||
$('div.disarmdelay').show();
|
||||
else
|
||||
} else {
|
||||
$('div.disarmdelay').hide();
|
||||
|
||||
}
|
||||
|
||||
// fill throttle
|
||||
|
@ -383,64 +281,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
|
||||
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput);
|
||||
|
||||
var escProtocols = {
|
||||
0: {
|
||||
name: "STANDARD",
|
||||
defaultRate: 400,
|
||||
rates: {
|
||||
50: "50Hz",
|
||||
400: "400Hz"
|
||||
}
|
||||
},
|
||||
1: {
|
||||
name: "ONESHOT125",
|
||||
defaultRate: 1000,
|
||||
rates: {
|
||||
400: "400Hz",
|
||||
1000: "1kHz",
|
||||
2000: "2kHz"
|
||||
}
|
||||
},
|
||||
2: {
|
||||
name: "ONESHOT42",
|
||||
defaultRate: 2000,
|
||||
rates: {
|
||||
400: "400Hz",
|
||||
1000: "1kHz",
|
||||
2000: "2kHz",
|
||||
4000: "4kHz",
|
||||
8000: "8kHz"
|
||||
}
|
||||
},
|
||||
3: {
|
||||
name: "MULTISHOT",
|
||||
defaultRate: 2000,
|
||||
rates: {
|
||||
400: "400Hz",
|
||||
1000: "1kHz",
|
||||
2000: "2kHz",
|
||||
4000: "4kHz",
|
||||
8000: "8kHz"
|
||||
}
|
||||
},
|
||||
4: {
|
||||
name: "BRUSHED",
|
||||
defaultRate: 8000,
|
||||
rates: {
|
||||
8000: "8kHz",
|
||||
16000: "16kHz",
|
||||
32000: "32kHz"
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
var servoRates = {
|
||||
50: "50Hz",
|
||||
60: "60Hz",
|
||||
100: "100Hz",
|
||||
200: "200Hz",
|
||||
400: "400Hz"
|
||||
};
|
||||
var escProtocols = FC.getEscProtocols();
|
||||
var servoRates = FC.getServoRates();
|
||||
|
||||
function buildMotorRates() {
|
||||
var protocolData = escProtocols[ADVANCED_CONFIG.motorPwmProtocol];
|
||||
|
@ -466,7 +308,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
var $escProtocol = $('#esc-protocol');
|
||||
var $escRate = $('#esc-rate');
|
||||
for (var i in escProtocols) {
|
||||
for (i in escProtocols) {
|
||||
if (escProtocols.hasOwnProperty(i)) {
|
||||
var protocolData = escProtocols[i];
|
||||
$escProtocol.append('<option value="' + i + '">' + protocolData.name + '</option>');
|
||||
|
@ -492,7 +334,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
var $servoRate = $('#servo-rate');
|
||||
|
||||
for (var i in servoRates) {
|
||||
for (i in servoRates) {
|
||||
if (servoRates.hasOwnProperty(i)) {
|
||||
$servoRate.append('<option value="' + i + '">' + servoRates[i] + '</option>');
|
||||
}
|
||||
|
@ -521,7 +363,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
var $gyroLpf = $("#gyro-lpf"),
|
||||
$gyroSync = $("#gyro-sync-checkbox");
|
||||
|
||||
for (var i in gyroLpfValues) {
|
||||
for (i in gyroLpfValues) {
|
||||
if (gyroLpfValues.hasOwnProperty(i)) {
|
||||
$gyroLpf.append('<option value="' + i + '">' + gyroLpfValues[i].label + '</option>');
|
||||
}
|
||||
|
@ -544,7 +386,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$looptime.change();
|
||||
});
|
||||
|
||||
$gyroLpf.change()
|
||||
$gyroLpf.change();
|
||||
$looptime.val(FC_CONFIG.loopTime);
|
||||
|
||||
$looptime.change(function () {
|
||||
|
@ -574,7 +416,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$(".requires-v1_4").show();
|
||||
} else {
|
||||
var looptimeOptions = looptimes[125];
|
||||
for (var i in looptimeOptions.looptimes) {
|
||||
for (i in looptimeOptions.looptimes) {
|
||||
if (looptimeOptions.looptimes.hasOwnProperty(i)) {
|
||||
$looptime.append('<option value="' + i + '">' + looptimeOptions.looptimes[i] + '</option>');
|
||||
}
|
||||
|
@ -587,10 +429,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
$(".requires-v1_4").hide();
|
||||
}
|
||||
|
||||
//fill 3D
|
||||
if (semver.lt(CONFIG.apiVersion, "1.14.0")) {
|
||||
$('.tab-configuration .3d').hide();
|
||||
} else {
|
||||
|
||||
$('input[name="3ddeadbandlow"]').val(_3D.deadband3d_low);
|
||||
$('input[name="3ddeadbandhigh"]').val(_3D.deadband3d_high);
|
||||
$('input[name="3dneutral"]').val(_3D.neutral3d);
|
||||
|
@ -599,7 +438,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
} else {
|
||||
$('.3ddeadbandthrottle').hide();
|
||||
}
|
||||
}
|
||||
|
||||
$('input[type="checkbox"].feature', features_e).change(function () {
|
||||
var element = $(this),
|
||||
|
@ -647,11 +485,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val());
|
||||
|
||||
// motor disarm
|
||||
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
|
||||
ARMING_CONFIG.disarm_kill_switch = ~~$('input[name="disarmkillswitch"]').is(':checked'); // ~~ boolean to decimal conversion
|
||||
}
|
||||
|
||||
MISC.minthrottle = parseInt($('input[name="minthrottle"]').val());
|
||||
MISC.midrc = parseInt($('input[name="midthrottle"]').val());
|
||||
|
@ -681,12 +516,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
// track feature usage
|
||||
if (FC.isFeatureEnabled('RX_SERIAL', features)) {
|
||||
googleAnalytics.sendEvent('Setting', 'SerialRxProvider', serialRXtypes[RX_CONFIG.serialrx_provider]);
|
||||
googleAnalytics.sendEvent('Setting', 'SerialRxProvider', serialRxTypes[RX_CONFIG.serialrx_provider]);
|
||||
}
|
||||
|
||||
// track feature usage
|
||||
if (FC.isFeatureEnabled('RX_NRF24', features)) {
|
||||
googleAnalytics.sendEvent('Setting', 'nrf24Protocol', nrf24Protocoltypes[RX_CONFIG.nrf24rx_protocol]);
|
||||
googleAnalytics.sendEvent('Setting', 'nrf24Protocol', nrf24ProtocolTypes[RX_CONFIG.nrf24rx_protocol]);
|
||||
}
|
||||
|
||||
if (FC.isFeatureEnabled('GPS', features)) {
|
||||
|
@ -705,40 +540,20 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
function save_serial_config() {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc);
|
||||
} else {
|
||||
save_misc();
|
||||
}
|
||||
}
|
||||
|
||||
function save_misc() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_3d);
|
||||
}
|
||||
|
||||
function save_3d() {
|
||||
var next_callback = save_sensor_alignment;
|
||||
if(semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_3D, MSP.crunch(MSP_codes.MSP_SET_3D), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_3D, MSP.crunch(MSP_codes.MSP_SET_3D), false, save_sensor_alignment);
|
||||
}
|
||||
|
||||
function save_sensor_alignment() {
|
||||
var next_callback = save_acc_trim;
|
||||
if(semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_SENSOR_ALIGNMENT, MSP.crunch(MSP_codes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_SENSOR_ALIGNMENT, MSP.crunch(MSP_codes.MSP_SET_SENSOR_ALIGNMENT), false, save_acc_trim);
|
||||
}
|
||||
|
||||
function save_acc_trim() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_ACC_TRIM, MSP.crunch(MSP_codes.MSP_SET_ACC_TRIM), false
|
||||
, semver.gte(CONFIG.apiVersion, "1.8.0") ? save_arming_config : save_to_eeprom);
|
||||
MSP.send_message(MSP_codes.MSP_SET_ACC_TRIM, MSP.crunch(MSP_codes.MSP_SET_ACC_TRIM), false, save_arming_config);
|
||||
}
|
||||
|
||||
function save_arming_config() {
|
||||
|
@ -800,14 +615,16 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () {
|
||||
//noinspection JSUnresolvedVariable
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
//noinspection JSValidateTypes
|
||||
TABS.configuration.initialize(false, $('#content').scrollTop());
|
||||
});
|
||||
},1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
|
||||
}
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_serial_config);
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_misc);
|
||||
});
|
||||
|
||||
// status data pulled via separate timer with static speed
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue