Receiver and PID tab fully implemented, enjoy
parent
d450a3f518
commit
2f9db4fa4e
|
@ -205,7 +205,7 @@ a:hover {
|
|||
}
|
||||
.tab-pid_tuning table {
|
||||
width: 100%;
|
||||
border-collapse:collapse;
|
||||
border-collapse: collapse;
|
||||
}
|
||||
.tab-pid_tuning table, .tab-pid_tuning table th, .tab-pid_tuning table td {
|
||||
padding: 5px;
|
||||
|
@ -230,8 +230,8 @@ a:hover {
|
|||
margin-top: 20px;
|
||||
|
||||
width: 120px;
|
||||
height: 60px;
|
||||
line-height: 60px;
|
||||
height: 56px;
|
||||
line-height: 56px;
|
||||
|
||||
font-size: 14px;
|
||||
color: white;
|
||||
|
@ -258,6 +258,9 @@ a:hover {
|
|||
}
|
||||
.tab-receiver {
|
||||
}
|
||||
.tab-receiver .bars {
|
||||
float: left;
|
||||
}
|
||||
.tab-receiver .bars ul {
|
||||
height: 20px;
|
||||
line-height: 20px;
|
||||
|
@ -273,7 +276,90 @@ a:hover {
|
|||
.tab-receiver .bars .meter meter {
|
||||
width: 200px;
|
||||
height: 20px;
|
||||
|
||||
border: 1px solid silver;
|
||||
}
|
||||
.tab-receiver .bars .value {
|
||||
width: 60px;
|
||||
padding-left: 20px;
|
||||
}
|
||||
}
|
||||
.tab-receiver .tunings {
|
||||
float: left;
|
||||
border: 1p xsolid red;
|
||||
}
|
||||
.tab-receiver .tunings table {
|
||||
width: 30%;
|
||||
border-collapse: collapse;
|
||||
margin-bottom: 20px;
|
||||
}
|
||||
.tab-receiver .tunings table, .tab-receiver .tunings table th, .tab-receiver .tunings table td {
|
||||
padding: 5px;
|
||||
border: 1px solid #8b8b8b;
|
||||
}
|
||||
.tab-receiver .tunings table tr:nth-child(odd) {
|
||||
background-color: #ececec;
|
||||
}
|
||||
.tab-receiver .tunings table input {
|
||||
width: 130px;
|
||||
height: 18px;
|
||||
line-height: 18px;
|
||||
|
||||
padding: 0 5px 0 5px;
|
||||
border: 1px solid silver;
|
||||
text-align: right;
|
||||
}
|
||||
.tab-receiver .info {
|
||||
display: block;
|
||||
float: right;
|
||||
|
||||
width: 220px;
|
||||
|
||||
margin-bottom: 20px;
|
||||
|
||||
padding: 5px;
|
||||
|
||||
border: 1px dotted silver;
|
||||
}
|
||||
.tab-receiver .update {
|
||||
display: block;
|
||||
float: right;
|
||||
|
||||
width: 120px;
|
||||
height: 30px;
|
||||
line-height: 30px;
|
||||
|
||||
font-size: 14px;
|
||||
color: white;
|
||||
text-align: center;
|
||||
|
||||
border: 1px solid silver;
|
||||
|
||||
background-color: #6f1515;
|
||||
}
|
||||
.tab-receiver .update:hover {
|
||||
cursor: default;
|
||||
}
|
||||
.tab-receiver .update.active {
|
||||
background-color: #0fab16;
|
||||
}
|
||||
.tab-receiver .update.active:hover {
|
||||
cursor: pointer;
|
||||
background-color: #13d81d;
|
||||
}
|
||||
.tab-receiver #RX_plot {
|
||||
margin: auto;
|
||||
margin-top: 20px;
|
||||
|
||||
width: 880px;
|
||||
height: 250px;
|
||||
}
|
||||
|
||||
/* Flotr related styles */
|
||||
.flotr-legend {
|
||||
padding: 2px;
|
||||
left: 31px;
|
||||
top: 20px;
|
||||
border: 0;
|
||||
|
||||
background-color: white;
|
||||
}
|
File diff suppressed because one or more lines are too long
|
@ -28,7 +28,7 @@ $(document).ready(function() {
|
|||
});
|
||||
|
||||
// temporary
|
||||
//$('#content').load("./tabs/pid_tuning.html", tab_initialize_pid_tuning);
|
||||
//$('#content').load("./tabs/receiver.html", tab_initialize_receiver);
|
||||
});
|
||||
|
||||
function disable_timers() {
|
||||
|
|
|
@ -308,7 +308,7 @@ function send_message(code, data) {
|
|||
}
|
||||
|
||||
chrome.serial.write(connectionId, bufferOut, function(writeInfo) {
|
||||
// used for debugging purposes (should be disabled in "stable" buildsS
|
||||
// used for debugging purposes (should be disabled in "stable" builds
|
||||
//console.log("Wrote: " + writeInfo.bytesWritten + " bytes");
|
||||
});
|
||||
}
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
<meta http-equiv="Content-Type" content="text/html; charset=utf-8" />
|
||||
<meta name="author" content="cTn" />
|
||||
<link type="text/css" rel="stylesheet" href="./css/style.css" media="all" />
|
||||
<script type="text/javascript" src="./js/flotr2.min.js"></script>
|
||||
<script type="text/javascript" src="./js/jquery-1.9.1.min.js"></script>
|
||||
<script type="text/javascript" src="./js/serial_backend.js"></script>
|
||||
<script type="text/javascript" src="./js/main.js"></script>
|
||||
|
|
|
@ -41,4 +41,36 @@
|
|||
<li class="value"></li>
|
||||
</ul>
|
||||
</div>
|
||||
<div class="tunings">
|
||||
<table class="throttle">
|
||||
<tr>
|
||||
<th>Throttle MID</th>
|
||||
<th>Throttle EXPO</th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td><input type="text" name="mid" value="" /></td>
|
||||
<td><input type="text" name="expo" value="" /></td>
|
||||
</tr>
|
||||
</table>
|
||||
<table class="rate">
|
||||
<tr>
|
||||
<th>Pitch & Roll Rate</th>
|
||||
<th>Pitch & Roll Expo</th>
|
||||
</tr>
|
||||
<tr>
|
||||
<td><input type="text" name="rate" value="" /></td>
|
||||
<td><input type="text" name="expo" value="" /></td>
|
||||
</tr>
|
||||
</table>
|
||||
<a class="update" href="#">Update</a>
|
||||
</div>
|
||||
<p class="info">
|
||||
some info text goes here
|
||||
</p>
|
||||
<p class="info">
|
||||
some info text goes here
|
||||
</p>
|
||||
<div class="clear-both"></div>
|
||||
<div id="RX_plot">
|
||||
</div>
|
||||
</div>
|
116
tabs/receiver.js
116
tabs/receiver.js
|
@ -1,8 +1,85 @@
|
|||
function tab_initialize_receiver() {
|
||||
receiver_poll = setInterval(receiverPoll, 100);
|
||||
// fill in data from RC_tuning
|
||||
$('.tunings .throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2));
|
||||
$('.tunings .throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2));
|
||||
|
||||
$('.tunings .rate input[name="rate"]').val(RC_tuning.RC_RATE.toFixed(2));
|
||||
$('.tunings .rate input[name="expo"]').val(RC_tuning.RC_EXPO.toFixed(2));
|
||||
|
||||
// Setup plot variables and plot it self
|
||||
RX_plot_data = new Array(8);
|
||||
for (var i = 0; i < 8; i++) {
|
||||
RX_plot_data[i] = new Array();
|
||||
}
|
||||
|
||||
for (var i = 0; i <= 300; i++) {
|
||||
RX_plot_data[0].push([i, 0]);
|
||||
RX_plot_data[1].push([i, 0]);
|
||||
RX_plot_data[2].push([i, 0]);
|
||||
RX_plot_data[3].push([i, 0]);
|
||||
RX_plot_data[4].push([i, 0]);
|
||||
RX_plot_data[5].push([i, 0]);
|
||||
RX_plot_data[6].push([i, 0]);
|
||||
RX_plot_data[7].push([i, 0]);
|
||||
}
|
||||
|
||||
e_RX_plot = document.getElementById("RX_plot");
|
||||
|
||||
RX_plot_options = {
|
||||
shadowSize: 0,
|
||||
yaxis : {
|
||||
max: 2200,
|
||||
min: 800
|
||||
},
|
||||
xaxis : {
|
||||
//noTicks = 0
|
||||
},
|
||||
grid : {
|
||||
backgroundColor: "#FFFFFF"
|
||||
},
|
||||
legend : {
|
||||
backgroundOpacity: 0
|
||||
}
|
||||
};
|
||||
|
||||
// enable RC data pulling
|
||||
receiver_poll = setInterval(receiverPoll, 50);
|
||||
timers.push(receiver_poll);
|
||||
|
||||
// UI Hooks
|
||||
$('.tunings input').change(function() {
|
||||
// if any of the fields changed, unlock update button
|
||||
$('a.update').addClass('active');
|
||||
});
|
||||
|
||||
$('a.update').click(function() {
|
||||
if ($(this).hasClass('active')) {
|
||||
// catch RC_tuning changes
|
||||
RC_tuning.throttle_MID = parseFloat($('.tunings .throttle input[name="mid"]').val());
|
||||
RC_tuning.throttle_EXPO = parseFloat($('.tunings .throttle input[name="expo"]').val());
|
||||
|
||||
RC_tuning.RC_RATE = parseFloat($('.tunings .rate input[name="rate"]').val());
|
||||
RC_tuning.RC_EXPO = parseFloat($('.tunings .rate input[name="expo"]').val());
|
||||
|
||||
var RC_tuning_buffer_out = new Array();
|
||||
RC_tuning_buffer_out[0] = parseInt(RC_tuning.RC_RATE * 100);
|
||||
RC_tuning_buffer_out[1] = parseInt(RC_tuning.RC_EXPO * 100);
|
||||
RC_tuning_buffer_out[2] = parseInt(RC_tuning.roll_pitch_rate * 100);
|
||||
RC_tuning_buffer_out[3] = parseInt(RC_tuning.yaw_rate * 100);
|
||||
RC_tuning_buffer_out[4] = parseInt(RC_tuning.dynamic_THR_PID * 100);
|
||||
RC_tuning_buffer_out[5] = parseInt(RC_tuning.throttle_MID * 100);
|
||||
RC_tuning_buffer_out[6] = parseInt(RC_tuning.throttle_EXPO * 100);
|
||||
|
||||
// Send over the RC_tuning changes
|
||||
send_message(MSP_codes.MSP_SET_RC_TUNING, RC_tuning_buffer_out);
|
||||
|
||||
// remove the active status
|
||||
$(this).removeClass('active');
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
var samples_i = 300;
|
||||
function receiverPoll() {
|
||||
send_message(MSP_codes.MSP_RC, MSP_codes.MSP_RC);
|
||||
|
||||
|
@ -31,4 +108,41 @@ function receiverPoll() {
|
|||
|
||||
$('.tab-receiver meter:eq(7)').val(RC.AUX4);
|
||||
$('.tab-receiver .value:eq(7)').html(RC.AUX4);
|
||||
|
||||
// update plot with latest data
|
||||
|
||||
// push latest data to the main array
|
||||
RX_plot_data[0].push([samples_i, RC.throttle]);
|
||||
RX_plot_data[1].push([samples_i, RC.pitch]);
|
||||
RX_plot_data[2].push([samples_i, RC.roll]);
|
||||
RX_plot_data[3].push([samples_i, RC.yaw]);
|
||||
RX_plot_data[4].push([samples_i, RC.AUX1]);
|
||||
RX_plot_data[5].push([samples_i, RC.AUX2]);
|
||||
RX_plot_data[6].push([samples_i, RC.AUX3]);
|
||||
RX_plot_data[7].push([samples_i, RC.AUX4]);
|
||||
|
||||
// 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();
|
||||
};
|
||||
|
||||
// redraw plot
|
||||
plot_RX = Flotr.draw(e_RX_plot, [
|
||||
{data: RX_plot_data[0], label: "THROTTLE"},
|
||||
{data: RX_plot_data[1], label: "PITCH"},
|
||||
{data: RX_plot_data[2], label: "ROLL"},
|
||||
{data: RX_plot_data[3], label: "YAW"},
|
||||
{data: RX_plot_data[4], label: "AUX1"},
|
||||
{data: RX_plot_data[5], label: "AUX2"},
|
||||
{data: RX_plot_data[6], label: "AUX3"},
|
||||
{data: RX_plot_data[7], label: "AUX4"} ], RX_plot_options);
|
||||
|
||||
samples_i++;
|
||||
}
|
Loading…
Reference in New Issue