mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Support AUX1-8 on the 'Auxiliary Configuration' tab.
This commit is contained in:
parent
32c2e76784
commit
7e62e98bac
3 changed files with 98 additions and 31 deletions
18
js/msp.js
18
js/msp.js
|
@ -286,10 +286,22 @@ MSP.process_data = function(code, message_buffer, message_length) {
|
|||
// dump previous data (if there was any)
|
||||
AUX_CONFIG_values = new Array();
|
||||
|
||||
// fill in current data
|
||||
for (var i = 0; i < data.byteLength; i += 2) { // + 2 because uint16_t = 2 bytes
|
||||
AUX_CONFIG_values.push(data.getUint16(i, 1));
|
||||
var boxItems = data.byteLength / 2; // AUX 1-4, 2 bytes per boxItem
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
boxItems = data.byteLength / 4; // AUX 1-8, 2 bytes per boxItem for AUX 1-4 followed by 2 bytes per boxItem for AUX 5-8
|
||||
}
|
||||
// fill in current data
|
||||
var offset = 0;
|
||||
|
||||
for (var i = 0; offset < data.byteLength && i < boxItems; offset += 2, i ++) { // + 2 because uint16_t = 2 bytes
|
||||
AUX_CONFIG_values.push(data.getUint16(offset, 1));
|
||||
}
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
for (var i = 0; offset < data.byteLength && i < boxItems; offset += 2, i++) { // + 2 because uint16_t = 2 bytes
|
||||
AUX_CONFIG_values[i] |= (data.getUint16(offset, 1) << 16);
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
case MSP_codes.MSP_MISC: // 22 bytes
|
||||
MISC.PowerTrigger1 = data.getInt16(0, 1);
|
||||
|
|
|
@ -2,25 +2,41 @@
|
|||
<table class="boxes">
|
||||
<tr class="heads">
|
||||
<th style="width: 18%"></th>
|
||||
<th colspan="3">AUX 1</th>
|
||||
<th colspan="3">AUX 2</th>
|
||||
<th colspan="3">AUX 3</th>
|
||||
<th colspan="3">AUX 4</th>
|
||||
<th class="channel" colspan="3">AUX 1</th>
|
||||
<th class="channel" colspan="3">AUX 2</th>
|
||||
<th class="channel" colspan="3">AUX 3</th>
|
||||
<th class="channel" colspan="3">AUX 4</th>
|
||||
<th class="channel" colspan="3">AUX 5</th>
|
||||
<th class="channel" colspan="3">AUX 6</th>
|
||||
<th class="channel" colspan="3">AUX 7</th>
|
||||
<th class="channel" colspan="3">AUX 8</th>
|
||||
</tr>
|
||||
<tr class="main">
|
||||
<th i18n="auxiliaryName"></th>
|
||||
<th i18n="auxiliaryLow"></th>
|
||||
<th i18n="auxiliaryMed"></th>
|
||||
<th i18n="auxiliaryHigh"></th>
|
||||
<th i18n="auxiliaryLow"></th>
|
||||
<th i18n="auxiliaryMed"></th>
|
||||
<th i18n="auxiliaryHigh"></th>
|
||||
<th i18n="auxiliaryLow"></th>
|
||||
<th i18n="auxiliaryMed"></th>
|
||||
<th i18n="auxiliaryHigh"></th>
|
||||
<th i18n="auxiliaryLow"></th>
|
||||
<th i18n="auxiliaryMed"></th>
|
||||
<th i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
<th class="toggle" i18n="auxiliaryLow"></th>
|
||||
<th class="toggle" i18n="auxiliaryMed"></th>
|
||||
<th class="toggle" i18n="auxiliaryHigh"></th>
|
||||
</tr>
|
||||
</table>
|
||||
<a class="update" href="#" i18n="auxiliaryButtonSave"></a>
|
||||
|
|
|
@ -60,6 +60,22 @@ function tab_initialize_auxiliary_configuration() {
|
|||
box_check(AUX_CONFIG_values[i], 9) +
|
||||
box_check(AUX_CONFIG_values[i], 10) +
|
||||
box_check(AUX_CONFIG_values[i], 11) +
|
||||
|
||||
box_check(AUX_CONFIG_values[i], 16) +
|
||||
box_check(AUX_CONFIG_values[i], 17) +
|
||||
box_check(AUX_CONFIG_values[i], 18) +
|
||||
|
||||
box_check(AUX_CONFIG_values[i], 19) +
|
||||
box_check(AUX_CONFIG_values[i], 20) +
|
||||
box_check(AUX_CONFIG_values[i], 21) +
|
||||
|
||||
box_check(AUX_CONFIG_values[i], 22) +
|
||||
box_check(AUX_CONFIG_values[i], 23) +
|
||||
box_check(AUX_CONFIG_values[i], 24) +
|
||||
|
||||
box_check(AUX_CONFIG_values[i], 25) +
|
||||
box_check(AUX_CONFIG_values[i], 26) +
|
||||
box_check(AUX_CONFIG_values[i], 27) +
|
||||
'</tr>'
|
||||
);
|
||||
}
|
||||
|
@ -69,18 +85,29 @@ function tab_initialize_auxiliary_configuration() {
|
|||
// catch the input changes
|
||||
var main_needle = 0;
|
||||
var needle = 0;
|
||||
|
||||
var boxCountFor4AuxChannels = 3 * 4;
|
||||
var boxCountPerLine = boxCountFor4AuxChannels;
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
boxCountPerLine = boxCountFor4AuxChannels * 2;
|
||||
}
|
||||
|
||||
$('.boxes input').each(function() {
|
||||
var bitIndex = needle;
|
||||
if (bit_check(CONFIG.capability, 5) && needle >= boxCountFor4AuxChannels) {
|
||||
bitIndex += 4; // 0-11 bits for aux 1-4, 16-27 for aux 5-8
|
||||
}
|
||||
|
||||
if ($(this).is(':checked')) {
|
||||
AUX_CONFIG_values[main_needle] = bit_set(AUX_CONFIG_values[main_needle], needle);
|
||||
AUX_CONFIG_values[main_needle] = bit_set(AUX_CONFIG_values[main_needle], bitIndex);
|
||||
} else {
|
||||
AUX_CONFIG_values[main_needle] = bit_clear(AUX_CONFIG_values[main_needle], needle);
|
||||
AUX_CONFIG_values[main_needle] = bit_clear(AUX_CONFIG_values[main_needle], bitIndex);
|
||||
}
|
||||
|
||||
needle++;
|
||||
|
||||
if (needle >= 12) { // 4 aux * 3 checkboxes = 12 bits per line
|
||||
if (needle >= boxCountPerLine) {
|
||||
main_needle++;
|
||||
|
||||
needle = 0;
|
||||
}
|
||||
});
|
||||
|
@ -90,8 +117,14 @@ function tab_initialize_auxiliary_configuration() {
|
|||
|
||||
var needle = 0;
|
||||
for (var i = 0; i < AUX_CONFIG_values.length; i++) {
|
||||
AUX_val_buffer_out[needle++] = lowByte(AUX_CONFIG_values[i]);
|
||||
AUX_val_buffer_out[needle++] = highByte(AUX_CONFIG_values[i]);
|
||||
AUX_val_buffer_out[needle++] = lowByte(AUX_CONFIG_values[i] & 0xFFF);
|
||||
AUX_val_buffer_out[needle++] = highByte(AUX_CONFIG_values[i] & 0xFFF);
|
||||
}
|
||||
if (bit_check(CONFIG.capability, 5)) {
|
||||
for (var i = 0; i < AUX_CONFIG_values.length; i++) {
|
||||
AUX_val_buffer_out[needle++] = lowByte((AUX_CONFIG_values[i] >> 16) & 0xFFF);
|
||||
AUX_val_buffer_out[needle++] = highByte((AUX_CONFIG_values[i] >> 16) & 0xFFF);
|
||||
}
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_BOX, AUX_val_buffer_out, false, save_to_eeprom);
|
||||
|
@ -132,6 +165,12 @@ function tab_initialize_auxiliary_configuration() {
|
|||
box_highlight(RC.channels[5], 5); // aux 2
|
||||
box_highlight(RC.channels[6], 8); // aux 3
|
||||
box_highlight(RC.channels[7], 11); // aux 4
|
||||
if (RC.active_channels > 8) {
|
||||
box_highlight(RC.channels[8], 14); // aux 5
|
||||
box_highlight(RC.channels[9], 17); // aux 6
|
||||
box_highlight(RC.channels[10], 20); // aux 7
|
||||
box_highlight(RC.channels[11], 23); // aux 8
|
||||
}
|
||||
}
|
||||
|
||||
// enable data pulling
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue