mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-23 16:25:22 +03:00
Merge pull request #1287 from dthubereng/add_mode_logic_to_msp
Add modeLogic and mode link UI support
This commit is contained in:
commit
5de1b703aa
21 changed files with 445 additions and 32 deletions
|
@ -56,8 +56,8 @@
|
|||
}
|
||||
|
||||
.tab-auxiliary .mode .name {
|
||||
min-height: 50px;
|
||||
padding: 13px 0px;
|
||||
min-height: 80px;
|
||||
padding: 5px 0px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .mode .info {
|
||||
|
@ -77,13 +77,20 @@
|
|||
|
||||
.tab-auxiliary .mode .info .buttons {
|
||||
position: absolute;
|
||||
bottom: 14px;
|
||||
bottom: 0px;
|
||||
width: 100%;
|
||||
}
|
||||
|
||||
.tab-auxiliary .mode .info .buttons a {
|
||||
padding: 2px 5px;
|
||||
border-radius: 4px;
|
||||
cursor: pointer;
|
||||
margin: 3px;
|
||||
display: block;
|
||||
}
|
||||
|
||||
.tab-auxiliary .mode .info .buttons a:hover {
|
||||
background-color: darkgrey;
|
||||
}
|
||||
|
||||
.tab-auxiliary .ranges {
|
||||
|
@ -103,6 +110,17 @@
|
|||
padding-bottom: 5px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .link {
|
||||
position: relative;
|
||||
height: 70px;
|
||||
padding-top: 15px;
|
||||
padding-left: 15px;
|
||||
border-top: 1px solid #fff;
|
||||
border-bottom: 1px solid #cccccc;
|
||||
background-color: #ececec;
|
||||
padding-bottom: 5px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .range:first-child {
|
||||
border-top: 0px;
|
||||
}
|
||||
|
@ -111,6 +129,14 @@
|
|||
border-bottom: 0px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .link:first-child {
|
||||
border-top: 0px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .link:last-child {
|
||||
border-bottom: 0px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .range>.buttons {
|
||||
position: absolute;
|
||||
top: 0px;
|
||||
|
@ -125,15 +151,18 @@
|
|||
float: left;
|
||||
min-width: 90px;
|
||||
text-align: center;
|
||||
}
|
||||
|
||||
.tab-auxiliary .mode .range .channelInfo .limits {
|
||||
padding: 10px 0px;
|
||||
margin-top: -4px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .range .channel {
|
||||
border: 1px solid silver;
|
||||
border-radius: 3px;
|
||||
margin-bottom: 3px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .logic {
|
||||
border: 1px solid silver;
|
||||
border-radius: 3px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .range .marker {
|
||||
|
@ -152,6 +181,16 @@
|
|||
margin-top: 1px;
|
||||
}
|
||||
|
||||
.tab-auxiliary .mode .link .modeInfo {
|
||||
float: left;
|
||||
}
|
||||
|
||||
.tab-auxiliary .link .linkedTo {
|
||||
border: 1px solid silver;
|
||||
border-radius: 3px;
|
||||
margin-bottom: 3px;
|
||||
}
|
||||
|
||||
.tab-auxiliary>.buttons {
|
||||
margin-top: 10px;
|
||||
}
|
||||
|
|
|
@ -123,6 +123,9 @@ function configuration_backup(callback) {
|
|||
uniqueData.push(MSPCodes.MSP_COMPASS_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_FEATURE_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MODE_RANGES_EXTRA);
|
||||
}
|
||||
}
|
||||
|
||||
update_unique_data_list();
|
||||
|
@ -174,6 +177,9 @@ function configuration_backup(callback) {
|
|||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
configuration.BEEPER_CONFIG = jQuery.extend(true, {}, BEEPER_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
configuration.MODE_RANGES_EXTRA = jQuery.extend(true, [], MODE_RANGES_EXTRA);
|
||||
}
|
||||
|
||||
save();
|
||||
}
|
||||
|
@ -680,7 +686,7 @@ function configuration_restore(callback) {
|
|||
GUI.log(i18n.getMessage('configMigratedTo', [migratedVersion]));
|
||||
appliedMigrationsCount++;
|
||||
}
|
||||
|
||||
|
||||
if (appliedMigrationsCount > 0) {
|
||||
GUI.log(i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
|
||||
}
|
||||
|
@ -765,6 +771,23 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function upload_mode_ranges() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (configuration.MODE_RANGES_EXTRA == undefined) {
|
||||
MODE_RANGES_EXTRA = [];
|
||||
|
||||
for (var modeIndex = 0; modeIndex < MODE_RANGES.length; modeIndex++) {
|
||||
var defaultModeRangeExtra = {
|
||||
modeId: MODE_RANGES[modeIndex].modeId,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
}
|
||||
} else {
|
||||
MODE_RANGES_EXTRA = configuration.MODE_RANGES_EXTRA;
|
||||
}
|
||||
}
|
||||
|
||||
mspHelper.sendModeRanges(upload_adjustment_ranges);
|
||||
}
|
||||
|
||||
|
|
|
@ -19,6 +19,7 @@ var RC_tuning;
|
|||
var AUX_CONFIG;
|
||||
var AUX_CONFIG_IDS;
|
||||
var MODE_RANGES;
|
||||
var MODE_RANGES_EXTRA;
|
||||
var ADJUSTMENT_RANGES;
|
||||
var SERVO_CONFIG;
|
||||
var SERVO_RULES;
|
||||
|
@ -174,6 +175,7 @@ var FC = {
|
|||
AUX_CONFIG_IDS = [];
|
||||
|
||||
MODE_RANGES = [];
|
||||
MODE_RANGES_EXTRA = [];
|
||||
ADJUSTMENT_RANGES = [];
|
||||
|
||||
SERVO_CONFIG = [];
|
||||
|
|
|
@ -148,6 +148,7 @@ var MSPCodes = {
|
|||
MSP_SET_COMPASS_CONFIG: 224,
|
||||
MSP_SET_GPS_RESCUE: 225,
|
||||
|
||||
MSP_MODE_RANGES_EXTRA: 238,
|
||||
MSP_SET_ACC_TRIM: 239,
|
||||
MSP_ACC_TRIM: 240,
|
||||
MSP_SERVO_MIX_RULES: 241,
|
||||
|
|
|
@ -825,6 +825,21 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
}
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_MODE_RANGES_EXTRA:
|
||||
MODE_RANGES_EXTRA = []; // empty the array as new data is coming in
|
||||
|
||||
var modeRangeExtraCount = data.readU8();
|
||||
|
||||
for (var i = 0; i < modeRangeExtraCount; i++) {
|
||||
var modeRangeExtra = {
|
||||
id: data.readU8(),
|
||||
modeLogic: data.readU8(),
|
||||
linkedTo: data.readU8()
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
}
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_ADJUSTMENT_RANGES:
|
||||
ADJUSTMENT_RANGES = []; // empty the array as new data is coming in
|
||||
|
||||
|
@ -1975,11 +1990,17 @@ MspHelper.prototype.sendModeRanges = function(onCompleteCallback) {
|
|||
.push8((modeRange.range.start - 900) / 25)
|
||||
.push8((modeRange.range.end - 900) / 25);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
var modeRangeExtra = MODE_RANGES_EXTRA[modeRangeIndex];
|
||||
|
||||
buffer.push8(modeRangeExtra.modeLogic)
|
||||
.push8(modeRangeExtra.linkedTo);
|
||||
}
|
||||
|
||||
// prepare for next iteration
|
||||
modeRangeIndex++;
|
||||
if (modeRangeIndex == MODE_RANGES.length) {
|
||||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSPCodes.MSP_SET_MODE_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
|
|
|
@ -8,7 +8,12 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
var prevChannelsValues = null;
|
||||
|
||||
function get_mode_ranges() {
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false,
|
||||
semver.gte(CONFIG.apiVersion, "1.41.0") ? get_mode_ranges_extra : get_box_ids);
|
||||
}
|
||||
|
||||
function get_mode_ranges_extra() {
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES_EXTRA, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
function get_box_ids() {
|
||||
|
@ -45,9 +50,35 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
|
||||
$(newMode).find('.name').data('modeElement', newMode);
|
||||
$(newMode).find('a.addRange').data('modeElement', newMode);
|
||||
$(newMode).find('a.addLink').data('modeElement', newMode);
|
||||
|
||||
// hide link button for ARM
|
||||
if (modeId == 0 || semver.lt(CONFIG.apiVersion, "1.41.0")) {
|
||||
$(newMode).find('.addLink').hide();
|
||||
}
|
||||
|
||||
return newMode;
|
||||
}
|
||||
|
||||
function configureLogicList(template) {
|
||||
var logicList = $(template).find('.logic');
|
||||
var logicOptionTemplate = $(logicList).find('option');
|
||||
logicOptionTemplate.remove();
|
||||
|
||||
//add logic option(s)
|
||||
var logicOption = logicOptionTemplate.clone();
|
||||
logicOption.text(i18n.getMessage('auxiliaryModeLogicOR'));
|
||||
logicOption.val(0);
|
||||
logicList.append(logicOption);
|
||||
|
||||
if(semver.gte(CONFIG.apiVersion, "1.41.0")){
|
||||
var logicOption = logicOptionTemplate.clone();
|
||||
logicOption.text(i18n.getMessage('auxiliaryModeLogicAND'));
|
||||
logicOption.val(1);
|
||||
logicList.append(logicOption);
|
||||
}
|
||||
logicOptionTemplate.val(0);
|
||||
}
|
||||
|
||||
function configureRangeTemplate(auxChannelCount) {
|
||||
var rangeTemplate = $('#tab-auxiliary-templates .range');
|
||||
|
@ -70,10 +101,38 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
|
||||
channelOptionTemplate.val(-1);
|
||||
|
||||
configureLogicList(rangeTemplate);
|
||||
}
|
||||
|
||||
function addRangeToMode(modeElement, auxChannelIndex, range) {
|
||||
function configureLinkTemplate() {
|
||||
var linkTemplate = $('#tab-auxiliary-templates .link');
|
||||
|
||||
var linkList = $(linkTemplate).find('.linkedTo');
|
||||
var linkOptionTemplate = $(linkList).find('option');
|
||||
linkOptionTemplate.remove();
|
||||
|
||||
// set up a blank option in place of ARM
|
||||
var linkOption = linkOptionTemplate.clone();
|
||||
linkOption.text("");
|
||||
linkOption.val(0);
|
||||
linkList.append(linkOption);
|
||||
|
||||
for (var index = 1; index < AUX_CONFIG.length; index++) {
|
||||
var linkOption = linkOptionTemplate.clone();
|
||||
linkOption.text(AUX_CONFIG[index]);
|
||||
linkOption.val(AUX_CONFIG_IDS[index]); // set value to mode id
|
||||
linkList.append(linkOption);
|
||||
}
|
||||
|
||||
linkOptionTemplate.val(0);
|
||||
|
||||
configureLogicList(linkTemplate);
|
||||
}
|
||||
|
||||
function addRangeToMode(modeElement, auxChannelIndex, modeLogic, range) {
|
||||
var modeIndex = $(modeElement).data('index');
|
||||
var modeRanges = $(modeElement).find('.ranges');
|
||||
|
||||
var channel_range = {
|
||||
'min': [ 900 ],
|
||||
|
@ -85,11 +144,17 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
rangeValues = [range.start, range.end];
|
||||
}
|
||||
|
||||
var rangeIndex = $(modeElement).find('.range').length;
|
||||
var rangeIndex = modeRanges.children().length;
|
||||
|
||||
var rangeElement = $('#tab-auxiliary-templates .range').clone();
|
||||
rangeElement.attr('id', 'mode-' + modeIndex + '-range-' + rangeIndex);
|
||||
modeElement.find('.ranges').append(rangeElement);
|
||||
modeRanges.append(rangeElement);
|
||||
|
||||
if (rangeIndex == 0) {
|
||||
$(rangeElement).find('.logic').hide();
|
||||
} else if (rangeIndex == 1) {
|
||||
modeRanges.children().eq(0).find('.logic').show();
|
||||
}
|
||||
|
||||
$(rangeElement).find('.channel-slider').noUiSlider({
|
||||
start: rangeValues,
|
||||
|
@ -115,19 +180,71 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$(rangeElement).find('.deleteRange').data('rangeElement', rangeElement);
|
||||
$(rangeElement).find('.deleteRange').data('modeElement', modeElement);
|
||||
|
||||
$(rangeElement).find('a.deleteRange').click(function () {
|
||||
var modeElement = $(this).data('modeElement');
|
||||
var rangeElement = $(this).data('rangeElement');
|
||||
|
||||
rangeElement.remove();
|
||||
|
||||
var siblings = $(modeElement).find('.ranges').children();
|
||||
|
||||
if (siblings.length == 1) {
|
||||
siblings.eq(0).find('.logic').hide();
|
||||
}
|
||||
});
|
||||
|
||||
$(rangeElement).find('.channel').val(auxChannelIndex);
|
||||
$(rangeElement).find('.logic').val(modeLogic);
|
||||
}
|
||||
|
||||
function addLinkedToMode(modeElement, modeLogic, linkedTo) {
|
||||
var modeId = $(modeElement).data('id');
|
||||
var modeIndex = $(modeElement).data('index');
|
||||
var modeRanges = $(modeElement).find('.ranges');
|
||||
|
||||
var linkIndex = modeRanges.children().length;
|
||||
|
||||
var linkElement = $('#tab-auxiliary-templates .link').clone();
|
||||
linkElement.attr('id', 'mode-' + modeIndex + '-link-' + linkIndex);
|
||||
modeRanges.append(linkElement);
|
||||
|
||||
if (linkIndex == 0) {
|
||||
$(linkElement).find('.logic').hide();
|
||||
} else if (linkIndex == 1) {
|
||||
modeRanges.children().eq(0).find('.logic').show();
|
||||
}
|
||||
|
||||
// disable the option associated with this mode
|
||||
var linkSelect = $(linkElement).find('.linkedTo');
|
||||
$(linkSelect).find('option[value="' + modeId + '"]').prop('disabled',true);
|
||||
|
||||
$(linkElement).find('.deleteLink').data('linkElement', linkElement);
|
||||
$(linkElement).find('.deleteLink').data('modeElement', modeElement);
|
||||
|
||||
$(linkElement).find('a.deleteLink').click(function () {
|
||||
var modeElement = $(this).data('modeElement');
|
||||
var linkElement = $(this).data('linkElement');
|
||||
|
||||
linkElement.remove();
|
||||
|
||||
var siblings = $(modeElement).find('.ranges').children();
|
||||
|
||||
if (siblings.length == 1) {
|
||||
siblings.eq(0).find('.logic').hide();
|
||||
}
|
||||
});
|
||||
|
||||
$(linkElement).find('.linkedTo').val(linkedTo);
|
||||
$(linkElement).find('.logic').val(modeLogic);
|
||||
}
|
||||
|
||||
function process_html() {
|
||||
var auxChannelCount = RC.active_channels - 4;
|
||||
|
||||
configureRangeTemplate(auxChannelCount);
|
||||
configureLinkTemplate();
|
||||
|
||||
var modeTableBodyElement = $('.tab-auxiliary .modes tbody')
|
||||
for (var modeIndex = 0; modeIndex < AUX_CONFIG.length; modeIndex++) {
|
||||
|
@ -136,28 +253,48 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
var newMode = createMode(modeIndex, modeId);
|
||||
modeTableBodyElement.append(newMode);
|
||||
|
||||
// generate ranges from the supplied AUX names and MODE_RANGE data
|
||||
// generate ranges from the supplied AUX names and MODE_RANGES[_EXTRA] data
|
||||
// skip linked modes for now
|
||||
for (var modeRangeIndex = 0; modeRangeIndex < MODE_RANGES.length; modeRangeIndex++) {
|
||||
var modeRange = MODE_RANGES[modeRangeIndex];
|
||||
|
||||
var modeRangeExtra = {
|
||||
id: modeRange.id,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
modeRangeExtra = MODE_RANGES_EXTRA[modeRangeIndex];
|
||||
}
|
||||
|
||||
if (modeRange.id != modeId) {
|
||||
if (modeRange.id != modeId || modeRangeExtra.id != modeId) {
|
||||
continue;
|
||||
}
|
||||
|
||||
var range = modeRange.range;
|
||||
if (!(range.start < range.end)) {
|
||||
continue; // invalid!
|
||||
}
|
||||
|
||||
addRangeToMode(newMode, modeRange.auxChannelIndex, range)
|
||||
}
|
||||
|
||||
if (modeId == 0 || modeRangeExtra.linkedTo == 0) {
|
||||
var range = modeRange.range;
|
||||
if (!(range.start < range.end)) {
|
||||
continue; // invalid!
|
||||
}
|
||||
|
||||
addRangeToMode(newMode, modeRange.auxChannelIndex, modeRangeExtra.modeLogic, range)
|
||||
|
||||
} else {
|
||||
addLinkedToMode(newMode, modeRangeExtra.modeLogic, modeRangeExtra.linkedTo);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
$('a.addRange').click(function () {
|
||||
var modeElement = $(this).data('modeElement');
|
||||
//auto select AUTO option
|
||||
addRangeToMode(modeElement, -1);
|
||||
// auto select AUTO option; default to 'OR' logic
|
||||
addRangeToMode(modeElement, -1, 0);
|
||||
});
|
||||
|
||||
$('a.addLink').click(function () {
|
||||
var modeElement = $(this).data('modeElement');
|
||||
// default to 'OR' logic and no link selected
|
||||
addLinkedToMode(modeElement, 0, 0);
|
||||
});
|
||||
|
||||
// translate to user-selected language
|
||||
|
@ -172,13 +309,13 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
var requiredModesRangeCount = MODE_RANGES.length;
|
||||
|
||||
MODE_RANGES = [];
|
||||
MODE_RANGES_EXTRA = [];
|
||||
|
||||
$('.tab-auxiliary .modes .mode').each(function () {
|
||||
var modeElement = $(this);
|
||||
var modeId = modeElement.data('id');
|
||||
|
||||
$(modeElement).find('.range').each(function() {
|
||||
|
||||
var rangeValues = $(this).find('.channel-slider').val();
|
||||
var modeRange = {
|
||||
id: modeId,
|
||||
|
@ -189,6 +326,38 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
};
|
||||
MODE_RANGES.push(modeRange);
|
||||
|
||||
var modeRangeExtra = {
|
||||
id: modeId,
|
||||
modeLogic: parseInt($(this).find('.logic').val()),
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
});
|
||||
|
||||
$(modeElement).find('.link').each(function() {
|
||||
var linkedToSelection = parseInt($(this).find('.linkedTo').val());
|
||||
|
||||
if (linkedToSelection == 0) {
|
||||
$(this).remove();
|
||||
} else {
|
||||
var modeRange = {
|
||||
id: modeId,
|
||||
auxChannelIndex: 0,
|
||||
range: {
|
||||
start: 900,
|
||||
end: 900
|
||||
}
|
||||
};
|
||||
MODE_RANGES.push(modeRange);
|
||||
|
||||
var modeRangeExtra = {
|
||||
id: modeId,
|
||||
modeLogic: parseInt($(this).find('.logic').val()),
|
||||
linkedTo: linkedToSelection
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(modeRangeExtra);
|
||||
}
|
||||
});
|
||||
});
|
||||
|
||||
|
@ -202,6 +371,13 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
}
|
||||
};
|
||||
MODE_RANGES.push(defaultModeRange);
|
||||
|
||||
var defaultModeRangeExtra = {
|
||||
id: 0,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
}
|
||||
|
||||
//
|
||||
|
@ -247,7 +423,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
let hasUsedMode = false;
|
||||
for (let i = 0; i < AUX_CONFIG.length; i++) {
|
||||
let modeElement = $('#mode-' + i);
|
||||
if (modeElement.find(' .range').length == 0) {
|
||||
if (modeElement.find(' .range').length == 0 && modeElement.find(' .link').length == 0) {
|
||||
// if the mode is unused, skip it
|
||||
modeElement.removeClass('off').removeClass('on');
|
||||
continue;
|
||||
|
@ -264,7 +440,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
let hideUnused = hideUnusedModes && hasUsedMode;
|
||||
for (let i = 0; i < AUX_CONFIG.length; i++) {
|
||||
let modeElement = $('#mode-' + i);
|
||||
if (modeElement.find(' .range').length == 0) {
|
||||
if (modeElement.find(' .range').length == 0 && modeElement.find(' .link').length == 0) {
|
||||
modeElement.toggle(!hideUnused);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
<td class="info">
|
||||
<p class="name"></p>
|
||||
<div class="buttons">
|
||||
<a class="addLink" href="#" i18n="auxiliaryAddLink"></a>
|
||||
<a class="addRange" href="#" i18n="auxiliaryAddRange"></a>
|
||||
</div>
|
||||
</td>
|
||||
|
@ -44,9 +45,16 @@
|
|||
</table>
|
||||
<div class="range">
|
||||
<div class="channelInfo">
|
||||
<select class="channel">
|
||||
<option value=""></option>
|
||||
</select>
|
||||
<div class="channelName">
|
||||
<select class="channel">
|
||||
<option value=""></option>
|
||||
</select>
|
||||
</div>
|
||||
<div class="rangeLogic">
|
||||
<select class="logic">
|
||||
<option value=""></option>
|
||||
</select>
|
||||
</div>
|
||||
<div class="limits">
|
||||
<p class="lowerLimit">
|
||||
<span i18n="auxiliaryMin"></span>: <span class="lowerLimitValue"></span>
|
||||
|
@ -63,4 +71,21 @@
|
|||
<a class="deleteRange" href="#"> </a>
|
||||
</div>
|
||||
</div>
|
||||
<div class="link">
|
||||
<div class=modeInfo>
|
||||
<div class="modeLink">
|
||||
<select class="linkedTo">
|
||||
<option value=""></option>
|
||||
</select>
|
||||
</div>
|
||||
<div class="linkLogic">
|
||||
<select class="logic">
|
||||
<option value=""></option>
|
||||
</select>
|
||||
</div>
|
||||
</div>
|
||||
<div class="delete">
|
||||
<a class="deleteLink" href="#"> </a>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue