mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
stuff rcData to array (allocating up to 32 chan)
This commit is contained in:
parent
4fc1d3ef53
commit
5f07390d45
5 changed files with 28 additions and 64 deletions
|
@ -21,15 +21,11 @@ for (var i = 0; i < 10; i++) {
|
||||||
PIDs[i] = new Array(3);
|
PIDs[i] = new Array(3);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// defaults
|
||||||
|
// roll, pitch, yaw, throttle, aux 1, ... aux n
|
||||||
var RC = {
|
var RC = {
|
||||||
roll: 0,
|
active_channels: 0,
|
||||||
pitch: 0,
|
channels: new Array(32)
|
||||||
yaw: 0,
|
|
||||||
throttle: 0,
|
|
||||||
AUX1: 0,
|
|
||||||
AUX2: 0,
|
|
||||||
AUX3: 0,
|
|
||||||
AUX4: 0
|
|
||||||
};
|
};
|
||||||
|
|
||||||
var RC_tuning = {
|
var RC_tuning = {
|
||||||
|
|
12
js/msp.js
12
js/msp.js
|
@ -209,15 +209,11 @@ MSP.process_data = function(code, message_buffer, message_length) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_RC:
|
case MSP_codes.MSP_RC:
|
||||||
RC.roll = data.getUint16(0, 1);
|
RC.active_channels = message_length / 2;
|
||||||
RC.pitch = data.getUint16(2, 1);
|
|
||||||
RC.yaw = data.getUint16(4, 1);
|
|
||||||
RC.throttle = data.getUint16(6, 1);
|
|
||||||
|
|
||||||
RC.AUX1 = data.getUint16(8, 1);
|
for (var i = 0; i < RC.active_channels; i++) {
|
||||||
RC.AUX2 = data.getUint16(10, 1);
|
RC.channels[i] = data.getUint16((i * 2), 1);
|
||||||
RC.AUX3 = data.getUint16(12, 1);
|
}
|
||||||
RC.AUX4 = data.getUint16(14, 1);
|
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_RAW_GPS:
|
case MSP_codes.MSP_RAW_GPS:
|
||||||
GPS_DATA.fix = data.getUint8(0);
|
GPS_DATA.fix = data.getUint8(0);
|
||||||
|
|
|
@ -128,10 +128,10 @@ function tab_initialize_auxiliary_configuration() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
box_highlight(RC.AUX1, 2);
|
box_highlight(RC.channels[4], 2); // aux 1
|
||||||
box_highlight(RC.AUX2, 5);
|
box_highlight(RC.channels[5], 5); // aux 2
|
||||||
box_highlight(RC.AUX3, 8);
|
box_highlight(RC.channels[6], 8); // aux 3
|
||||||
box_highlight(RC.AUX4, 11);
|
box_highlight(RC.channels[7], 11); // aux 4
|
||||||
}
|
}
|
||||||
|
|
||||||
// enable data pulling
|
// enable data pulling
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
<div class="tab-receiver">
|
<div class="tab-receiver">
|
||||||
<div class="bars">
|
<div class="bars">
|
||||||
<ul style="color: #00A8F0">
|
<ul style="color: #00A8F0">
|
||||||
<li class="name">Throttle</li>
|
<li class="name">Roll</li>
|
||||||
<li class="meter"><meter min="800" max="2200"></meter></li>
|
<li class="meter"><meter min="800" max="2200"></meter></li>
|
||||||
<li class="value"></li>
|
<li class="value"></li>
|
||||||
</ul>
|
</ul>
|
||||||
|
@ -13,13 +13,13 @@
|
||||||
</ul>
|
</ul>
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
<ul style="color: #CB4B4B">
|
<ul style="color: #CB4B4B">
|
||||||
<li class="name">Roll</li>
|
<li class="name">Yaw</li>
|
||||||
<li class="meter"><meter min="800" max="2200"></meter></li>
|
<li class="meter"><meter min="800" max="2200"></meter></li>
|
||||||
<li class="value"></li>
|
<li class="value"></li>
|
||||||
</ul>
|
</ul>
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
<ul style="color: #4DA74D">
|
<ul style="color: #4DA74D">
|
||||||
<li class="name">Yaw</li>
|
<li class="name">Throttle</li>
|
||||||
<li class="meter"><meter min="800" max="2200"></meter></li>
|
<li class="meter"><meter min="800" max="2200"></meter></li>
|
||||||
<li class="value"></li>
|
<li class="value"></li>
|
||||||
</ul>
|
</ul>
|
||||||
|
|
|
@ -153,8 +153,8 @@ function tab_initialize_receiver() {
|
||||||
});
|
});
|
||||||
|
|
||||||
// setup plot
|
// setup plot
|
||||||
var RX_plot_data = new Array(8);
|
var RX_plot_data = new Array(RC.active_channels);
|
||||||
for (var i = 0; i < 8; i++) {
|
for (var i = 0; i < RX_plot_data.length; i++) {
|
||||||
RX_plot_data[i] = [];
|
RX_plot_data[i] = [];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -173,50 +173,22 @@ function tab_initialize_receiver() {
|
||||||
}
|
}
|
||||||
|
|
||||||
function update_ui() {
|
function update_ui() {
|
||||||
meter_array[0].val(RC.throttle);
|
// update bars with latest data
|
||||||
meter_values_array[0].text('[ ' + RC.throttle + ' ]');
|
for (var i = 0; i < RC.active_channels; i++) {
|
||||||
|
meter_array[i].val(RC.channels[i]);
|
||||||
meter_array[1].val(RC.pitch);
|
meter_values_array[i].text('[ ' + RC.channels[i] + ' ]');
|
||||||
meter_values_array[1].text('[ ' + RC.pitch + ' ]');
|
}
|
||||||
|
|
||||||
meter_array[2].val(RC.roll);
|
|
||||||
meter_values_array[2].text('[ ' + RC.roll + ' ]');
|
|
||||||
|
|
||||||
meter_array[3].val(RC.yaw);
|
|
||||||
meter_values_array[3].text('[ ' + RC.yaw + ' ]');
|
|
||||||
|
|
||||||
meter_array[4].val(RC.AUX1);
|
|
||||||
meter_values_array[4].text('[ ' + RC.AUX1 + ' ]');
|
|
||||||
|
|
||||||
meter_array[5].val(RC.AUX2);
|
|
||||||
meter_values_array[5].text('[ ' + RC.AUX2 + ' ]');
|
|
||||||
|
|
||||||
meter_array[6].val(RC.AUX3);
|
|
||||||
meter_values_array[6].text('[ ' + RC.AUX3 + ' ]');
|
|
||||||
|
|
||||||
meter_array[7].val(RC.AUX4);
|
|
||||||
meter_values_array[7].text('[ ' + RC.AUX4 + ' ]');
|
|
||||||
|
|
||||||
// push latest data to the main array
|
// push latest data to the main array
|
||||||
RX_plot_data[0].push([samples, RC.throttle]);
|
for (var i = 0; i < RC.active_channels; i++) {
|
||||||
RX_plot_data[1].push([samples, RC.pitch]);
|
RX_plot_data[i].push([samples, RC.channels[i]]);
|
||||||
RX_plot_data[2].push([samples, RC.roll]);
|
}
|
||||||
RX_plot_data[3].push([samples, RC.yaw]);
|
|
||||||
RX_plot_data[4].push([samples, RC.AUX1]);
|
|
||||||
RX_plot_data[5].push([samples, RC.AUX2]);
|
|
||||||
RX_plot_data[6].push([samples, RC.AUX3]);
|
|
||||||
RX_plot_data[7].push([samples, RC.AUX4]);
|
|
||||||
|
|
||||||
// Remove old data from array
|
// Remove old data from array
|
||||||
while (RX_plot_data[0].length > 300) {
|
while (RX_plot_data[0].length > 300) {
|
||||||
RX_plot_data[0].shift();
|
for (var i = 0; i < RX_plot_data.length; i++) {
|
||||||
RX_plot_data[1].shift();
|
RX_plot_data[i].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();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update required parts of the plot
|
// update required parts of the plot
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue