1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-16 12:55:13 +03:00

jBox Tooltip implementation using i18n_title instead of jBox:Content - reduces DOM element counts

This commit is contained in:
tricopterY 2015-12-18 13:43:05 +11:00
parent 61c80a9d4c
commit 3228625de1
5 changed files with 21 additions and 29 deletions

View file

@ -1349,6 +1349,12 @@
"failsafeChannelFallbackSettingsHelp": {
"message": "These settings are applied to invalid individual AUX channels or to all channels when entering stage 1. <strong>Note:</strong> values are saved in steps of 25usec, so small changes disappear"
},
"failsafeChannelFallbackSettingsAuto": {
"message": "<strong>Auto</strong> means Roll, Pitch and Yaw to center and Throttle low. <strong>Hold</strong> means maintain the last good value received"
},
"failsafeChannelFallbackSettingsHold": {
"message": "<strong>Hold</strong> means maintain the last good value received. <strong>Set</strong> means the value given here will be used"
},
"failsafeStageTwoSettingsTitle": {
"message": "Stage 2 - Settings"
},

View file

@ -288,7 +288,6 @@ GUI_control.prototype.content_ready = function (callback) {
$('.cf_tip').each(function() {
$(this).jBox('Tooltip', {
content: $(this).children('.cf_tooltiptext'),
delayOpen: 100,
delayClose: 100,
position: {

View file

@ -214,7 +214,10 @@
}
.tab-failsafe .channelname {
float:left;
margin-right: 3px;
width:60%;
padding-top: 2px;
}
.tab-failsafe .note {

View file

@ -39,9 +39,7 @@
<div class="gui_box grey newpane">
<div class="gui_box_titlebar">
<div class="spacer_box_title" i18n="failsafePulsrangeTitle"></div>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafePulsrangeHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafePulsrangeHelp"></div>
</div>
<div class="spacer_box">
<div class="number">
@ -59,9 +57,7 @@
<div class="gui_box grey stage1 newpane">
<div class="gui_box_titlebar">
<div class="spacer_box_title" i18n="failsafeChannelFallbackSettingsTitle"></div>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafeChannelFallbackSettingsHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafeChannelFallbackSettingsHelp"></div>
</div>
<div class="spacer_box">
<div class="activechannellist">
@ -82,9 +78,7 @@
</div>
<label for="failsafe_feature_new"><span i18n="failsafeFeatureItem"></span>
</label>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafeFeatureHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafeFeatureHelp"></div>
</div>
<div class="checkbox stage2">
<div class="numberspacer" >
@ -92,25 +86,19 @@
</div>
<label for="failsafe_kill_switch"><span i18n="failsafeKillSwitchItem"></span>
</label>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafeKillSwitchHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafeKillSwitchHelp"></div>
</div>
<div class="number stage2">
<label> <input type="number" name="failsafe_delay" min="0" max="2000" /> <span
i18n="failsafeDelayItem"></span>
</label>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafeDelayHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafeDelayHelp"></div>
</div>
<div class="number stage2">
<label> <input type="number" name="failsafe_throttle_low_delay" min="0" max="2000" /> <span
i18n="failsafeThrottleLowItem"></span>
</label>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafeThrottleLowHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafeThrottleLowHelp"></div>
</div>
<!-- radio buttons -->
<div class="subline stage2" i18n="failsafeSubTitle1"></div>
@ -133,9 +121,7 @@
<label> <input type="number" name="failsafe_off_delay" min="0" max="2000" /> <span
i18n="failsafeOffDelayItem"></span>
</label>
<div class="helpicon cf_tip">
<div class="cf_tooltiptext" i18n="failsafeOffDelayHelp"></div>
</div>
<div class="helpicon cf_tip" i18n_title="failsafeOffDelayHelp"></div>
</div>
</div>
</div>

View file

@ -126,11 +126,10 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
if (i < channelNames.length) {
fullChannels_e.append('\
<div class="number">\
<div style="width:60%; float:left;">\
<div class="channelname">\
<span>' + channelNames[i] + '</span>\
</div>\
<div class="cf_tip" style="width:25%; float:left;">\
<div class="cf_tooltiptext" style="display:none;"><strong>Auto</strong> means Roll, Pitch and Yaw to center and Throttle low. <strong>Hold</strong> means maintain the last good value received.</div>\
<div class="cf_tip" style="width:25%; float:left;" title="' + chrome.i18n.getMessage("failsafeChannelFallbackSettingsAuto") + '">\
<select class="aux_set" id="' + i + '">\
<option value="0">Auto</option>\
<option value="1">Hold</option>\
@ -142,12 +141,11 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} else {
fullChannels_e.append('\
<div class="number">\
<div style="width:60%; float:left; padding-top: 2px;">\
<div>\
<span class="channelname">' + chrome.i18n.getMessage("controlAxisAux" + (aux_index++)) + '</span>\
' + auxAssignment[aux_assignment_index++] + '\
</div>\
<div class="cf_tip" style="width:25%; float:left;">\
<div class="cf_tooltiptext" style="display:none;"><strong>Hold</strong> means maintain the last good value received. <strong>Set</strong> means the value given here will be used. </div>\
<div class="cf_tip" style="width:25%; float:left;" title="' + chrome.i18n.getMessage("failsafeChannelFallbackSettingsHold") + '">\
<select class="aux_set" id="' + i + '">\
<option value="1">Hold</option>\
<option value="2">Set</option>\