1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

Add support for 12 channels to the receiver tab.

If the incoming data from the FC has 8 channels then only 8 are
displayed.  The message size can be used to calculate the amount of
channels, as per MultiWii protocol 2.3 and Cleanflight.
This commit is contained in:
Dominic Clifton 2014-05-14 23:55:05 +01:00
parent 4fc1d3ef53
commit 49ec225d66
5 changed files with 100 additions and 26 deletions

View file

@ -22,6 +22,7 @@ for (var i = 0; i < 10; i++) {
}
var RC = {
channelCount: 0,
roll: 0,
pitch: 0,
yaw: 0,
@ -29,7 +30,11 @@ var RC = {
AUX1: 0,
AUX2: 0,
AUX3: 0,
AUX4: 0
AUX4: 0,
AUX5: 0,
AUX6: 0,
AUX7: 0,
AUX8: 0
};
var RC_tuning = {

View file

@ -209,15 +209,24 @@ MSP.process_data = function(code, message_buffer, message_length) {
}
break;
case MSP_codes.MSP_RC:
RC.roll = data.getUint16(0, 1);
RC.pitch = data.getUint16(2, 1);
RC.yaw = data.getUint16(4, 1);
RC.throttle = data.getUint16(6, 1);
RC.AUX1 = data.getUint16(8, 1);
RC.AUX2 = data.getUint16(10, 1);
RC.AUX3 = data.getUint16(12, 1);
RC.AUX4 = data.getUint16(14, 1);
RC.channelCount = message_length / 2;
switch(RC.channelCount) {
case 12:
RC.AUX8 = data.getUint16(22, 1);
RC.AUX7 = data.getUint16(20, 1);
RC.AUX6 = data.getUint16(18, 1);
RC.AUX5 = data.getUint16(16, 1);
case 8:
RC.AUX4 = data.getUint16(14, 1);
RC.AUX3 = data.getUint16(12, 1);
RC.AUX2 = data.getUint16(10, 1);
RC.AUX1 = data.getUint16(8, 1);
RC.throttle = data.getUint16(6, 1);
RC.yaw = data.getUint16(4, 1);
RC.pitch = data.getUint16(2, 1);
RC.roll = data.getUint16(0, 1);
}
break;
case MSP_codes.MSP_RAW_GPS:
GPS_DATA.fix = data.getUint8(0);

View file

@ -24,14 +24,14 @@
.tab-receiver .bars .meter {
width: 70%;
}
.tab-receiver .bars .meter meter {
margin-top: 4px;
.tab-receiver .bars .meter meter {
margin-top: 4px;
width: 100%;
height: 14px;
width: 100%;
height: 14px;
border: 1px solid silver;
}
border: 1px solid silver;
}
.tab-receiver .bars .value {
width: 50px;
margin-left: 10px;
@ -98,6 +98,18 @@
.tab-receiver .line:nth-child(8) {
stroke: #147A66;
}
.tab-receiver .line:nth-child(9) {
stroke: #407a9e;
}
.tab-receiver .line:nth-child(10) {
stroke: #7a1445;
}
.tab-receiver .line:nth-child(11) {
stroke: #267acf;
}
.tab-receiver .line:nth-child(12) {
stroke: #7a6614;
}
.tab-receiver .throttle_curve {
margin: 0 10px 10px 0;

View file

@ -48,6 +48,30 @@
<li class="value"></li>
</ul>
<div class="clear-both"></div>
<ul style="color: #407a9">
<li class="name">AUX5</li>
<li class="meter"><meter min="800" max="2200"></meter></li>
<li class="value"></li>
</ul>
<div class="clear-both"></div>
<ul style="color: #7a1445">
<li class="name">AUX6</li>
<li class="meter"><meter min="800" max="2200"></meter></li>
<li class="value"></li>
</ul>
<div class="clear-both"></div>
<ul style="color: #267acf">
<li class="name">AUX7</li>
<li class="meter"><meter min="800" max="2200"></meter></li>
<li class="value"></li>
</ul>
<div class="clear-both"></div>
<ul style="color: #7a6614">
<li class="name">AUX8</li>
<li class="meter"><meter min="800" max="2200"></meter></li>
<li class="value"></li>
</ul>
<div class="clear-both"></div>
</div>
<div class="tunings">
<table class="throttle">

View file

@ -152,9 +152,18 @@ function tab_initialize_receiver() {
meter_values_array.push($(this));
});
// show only relevant bars and plots for channels
$('.tab-receiver .bars ul').hide();
$('.tab-receiver .line').hide();
for (var channelIndex = 0; channelIndex < RC.channelCount; channelIndex++) {
$('.tab-receiver .bars ul').eq(channelIndex).show();
$('.tab-receiver .line').eq(channelIndex).show();
}
// setup plot
var RX_plot_data = new Array(8);
for (var i = 0; i < 8; i++) {
var RX_plot_data = new Array(RC.channelCount);
for (var i = 0; i < RC.channelCount; i++) {
RX_plot_data[i] = [];
}
@ -197,6 +206,19 @@ function tab_initialize_receiver() {
meter_array[7].val(RC.AUX4);
meter_values_array[7].text('[ ' + RC.AUX4 + ' ]');
if (RC.channelCount >= 12) {
meter_array[8].val(RC.AUX5);
meter_values_array[8].text('[ ' + RC.AUX5 + ' ]');
meter_array[9].val(RC.AUX6);
meter_values_array[9].text('[ ' + RC.AUX6 + ' ]');
meter_array[10].val(RC.AUX7);
meter_values_array[10].text('[ ' + RC.AUX7 + ' ]');
meter_array[11].val(RC.AUX8);
meter_values_array[11].text('[ ' + RC.AUX8 + ' ]');
}
// push latest data to the main array
RX_plot_data[0].push([samples, RC.throttle]);
RX_plot_data[1].push([samples, RC.pitch]);
@ -207,16 +229,18 @@ function tab_initialize_receiver() {
RX_plot_data[6].push([samples, RC.AUX3]);
RX_plot_data[7].push([samples, RC.AUX4]);
if (RC.channelCount >= 12) {
RX_plot_data[8].push([samples, RC.AUX5]);
RX_plot_data[9].push([samples, RC.AUX6]);
RX_plot_data[10].push([samples, RC.AUX7]);
RX_plot_data[11].push([samples, RC.AUX8]);
}
// Remove old data from array
while (RX_plot_data[0].length > 300) {
RX_plot_data[0].shift();
RX_plot_data[1].shift();
RX_plot_data[2].shift();
RX_plot_data[3].shift();
RX_plot_data[4].shift();
RX_plot_data[5].shift();
RX_plot_data[6].shift();
RX_plot_data[7].shift();
for (var channelCount = 0; channelCount < RC.channelCount; channelCount++) {
RX_plot_data[channelCount].shift();
}
}
// update required parts of the plot