lots of work on removing global variables
parent
1e0cadc039
commit
f3ea5757f7
22
eventPage.js
22
eventPage.js
|
@ -18,14 +18,14 @@ function start_app() {
|
|||
minWidth: 974,
|
||||
minHeight: 632
|
||||
}
|
||||
}, function(createdWindow) {
|
||||
createdWindow.onClosed.addListener(function() {
|
||||
}, function (createdWindow) {
|
||||
createdWindow.onClosed.addListener(function () {
|
||||
// connectionId is passed from the script side through the chrome.runtime.getBackgroundPage refference
|
||||
// allowing us to automatically close the port when application shut down
|
||||
|
||||
// save connectionId in separate variable before app_window is destroyed
|
||||
var connectionId = app_window.serial.connectionId;
|
||||
var valid_connection = app_window.configuration_received;
|
||||
var valid_connection = app_window.CONFIGURATOR.connectionValid;
|
||||
var mincommand = app_window.MISC.mincommand;
|
||||
|
||||
if (connectionId > 0 && valid_connection) {
|
||||
|
@ -53,13 +53,13 @@ function start_app() {
|
|||
|
||||
bufView[5 + 16] = checksum;
|
||||
|
||||
chrome.serial.send(connectionId, bufferOut, function(sendInfo) {
|
||||
chrome.serial.disconnect(connectionId, function(result) {
|
||||
chrome.serial.send(connectionId, bufferOut, function (sendInfo) {
|
||||
chrome.serial.disconnect(connectionId, function (result) {
|
||||
console.log('SERIAL: Connection closed - ' + result);
|
||||
});
|
||||
});
|
||||
} else if (connectionId > 0) {
|
||||
chrome.serial.disconnect(connectionId, function(result) {
|
||||
chrome.serial.disconnect(connectionId, function (result) {
|
||||
console.log('SERIAL: Connection closed - ' + result);
|
||||
});
|
||||
}
|
||||
|
@ -67,18 +67,18 @@ function start_app() {
|
|||
});
|
||||
}
|
||||
|
||||
chrome.app.runtime.onLaunched.addListener(function() {
|
||||
chrome.app.runtime.onLaunched.addListener(function () {
|
||||
start_app();
|
||||
});
|
||||
|
||||
chrome.runtime.onInstalled.addListener(function(details) {
|
||||
chrome.runtime.onInstalled.addListener(function (details) {
|
||||
if (details.reason == 'update') {
|
||||
var previousVersionArr = details.previousVersion.split('.');
|
||||
var currentVersionArr = chrome.runtime.getManifest().version.split('.');
|
||||
|
||||
// only fire up notification sequence when one of the major version numbers changed
|
||||
if (currentVersionArr[0] != previousVersionArr[0] || currentVersionArr[1] != previousVersionArr[1]) {
|
||||
chrome.storage.local.get('update_notify', function(result) {
|
||||
chrome.storage.local.get('update_notify', function (result) {
|
||||
if (typeof result.update_notify === 'undefined' || result.update_notify) {
|
||||
var manifest = chrome.runtime.getManifest();
|
||||
var options = {
|
||||
|
@ -90,7 +90,7 @@ chrome.runtime.onInstalled.addListener(function(details) {
|
|||
buttons: [{'title': chrome.i18n.getMessage('notifications_click_here_to_start_app')}]
|
||||
};
|
||||
|
||||
chrome.notifications.create('baseflight_update', options, function(notificationId) {
|
||||
chrome.notifications.create('baseflight_update', options, function (notificationId) {
|
||||
// empty
|
||||
});
|
||||
}
|
||||
|
@ -99,7 +99,7 @@ chrome.runtime.onInstalled.addListener(function(details) {
|
|||
}
|
||||
});
|
||||
|
||||
chrome.notifications.onButtonClicked.addListener(function(notificationId, buttonIndex) {
|
||||
chrome.notifications.onButtonClicked.addListener(function (notificationId, buttonIndex) {
|
||||
if (notificationId == 'baseflight_update') {
|
||||
start_app();
|
||||
}
|
||||
|
|
|
@ -47,7 +47,7 @@ function configuration_backup() {
|
|||
var now = d.getUTCFullYear() + '.' + d.getDate() + '.' + (d.getMonth() + 1) + '.' + d.getHours() + '.' + d.getMinutes();
|
||||
|
||||
// create or load the file
|
||||
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'bf_mw_backup_' + now, accepts: accepts}, function(fileEntry) {
|
||||
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'bf_mw_backup_' + now, accepts: accepts}, function (fileEntry) {
|
||||
if (!fileEntry) {
|
||||
console.log('No file selected, backup aborted.');
|
||||
|
||||
|
@ -57,14 +57,14 @@ function configuration_backup() {
|
|||
chosenFileEntry = fileEntry;
|
||||
|
||||
// echo/console log path specified
|
||||
chrome.fileSystem.getDisplayPath(chosenFileEntry, function(path) {
|
||||
chrome.fileSystem.getDisplayPath(chosenFileEntry, function (path) {
|
||||
console.log('Backup file path: ' + path);
|
||||
});
|
||||
|
||||
// change file entry from read only to read/write
|
||||
chrome.fileSystem.getWritableEntry(chosenFileEntry, function(fileEntryWritable) {
|
||||
chrome.fileSystem.getWritableEntry(chosenFileEntry, function (fileEntryWritable) {
|
||||
// check if file is writable
|
||||
chrome.fileSystem.isWritableEntry(fileEntryWritable, function(isWritable) {
|
||||
chrome.fileSystem.isWritableEntry(fileEntryWritable, function (isWritable) {
|
||||
if (isWritable) {
|
||||
chosenFileEntry = fileEntryWritable;
|
||||
|
||||
|
@ -83,13 +83,13 @@ function configuration_backup() {
|
|||
var serialized_config_object = JSON.stringify(configuration);
|
||||
var blob = new Blob([serialized_config_object], {type: 'text/plain'}); // first parameter for Blob needs to be an array
|
||||
|
||||
chosenFileEntry.createWriter(function(writer) {
|
||||
chosenFileEntry.createWriter(function (writer) {
|
||||
writer.onerror = function (e) {
|
||||
console.error(e);
|
||||
};
|
||||
|
||||
var truncated = false;
|
||||
writer.onwriteend = function() {
|
||||
writer.onwriteend = function () {
|
||||
if (!truncated) {
|
||||
// onwriteend will be fired again when truncation is finished
|
||||
truncated = true;
|
||||
|
@ -126,7 +126,7 @@ function configuration_restore() {
|
|||
}];
|
||||
|
||||
// load up the file
|
||||
chrome.fileSystem.chooseEntry({type: 'openFile', accepts: accepts}, function(fileEntry) {
|
||||
chrome.fileSystem.chooseEntry({type: 'openFile', accepts: accepts}, function (fileEntry) {
|
||||
if (!fileEntry) {
|
||||
console.log('No file selected, restore aborted.');
|
||||
|
||||
|
@ -136,15 +136,15 @@ function configuration_restore() {
|
|||
chosenFileEntry = fileEntry;
|
||||
|
||||
// echo/console log path specified
|
||||
chrome.fileSystem.getDisplayPath(chosenFileEntry, function(path) {
|
||||
chrome.fileSystem.getDisplayPath(chosenFileEntry, function (path) {
|
||||
console.log('Restore file path: ' + path);
|
||||
});
|
||||
|
||||
// read contents into variable
|
||||
chosenFileEntry.file(function(file) {
|
||||
chosenFileEntry.file(function (file) {
|
||||
var reader = new FileReader();
|
||||
|
||||
reader.onprogress = function(e) {
|
||||
reader.onprogress = function (e) {
|
||||
if (e.total > 1048576) { // 1 MB
|
||||
// dont allow reading files bigger then 1 MB
|
||||
console.log('File limit (1 MB) exceeded, aborting');
|
||||
|
@ -152,7 +152,7 @@ function configuration_restore() {
|
|||
}
|
||||
};
|
||||
|
||||
reader.onloadend = function(e) {
|
||||
reader.onloadend = function (e) {
|
||||
if (e.total != 0 && e.total == e.loaded) {
|
||||
console.log('Read SUCCESSFUL');
|
||||
|
||||
|
@ -295,9 +295,9 @@ function configuration_upload() {
|
|||
buffer_out[21] = 0; // vbatlevel_crit (unused)
|
||||
|
||||
// Send ove the new MISC
|
||||
MSP.send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, function() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_MISC, buffer_out, false, function () {
|
||||
// Save changes to EEPROM
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('eeprom_saved_ok'));
|
||||
});
|
||||
});
|
||||
|
|
|
@ -1,6 +1,12 @@
|
|||
'use strict';
|
||||
|
||||
var firmware_version_accepted = 2.3;
|
||||
var CONFIGURATOR = {
|
||||
'firmwareVersionAccepted': 2.3,
|
||||
'connectionValid': false,
|
||||
'mspPassThrough': false,
|
||||
'cliActive': false,
|
||||
'cliValid': false
|
||||
};
|
||||
|
||||
var CONFIG = {
|
||||
version: 0,
|
||||
|
|
24
js/gui.js
24
js/gui.js
|
@ -2,7 +2,7 @@
|
|||
|
||||
var tabs = {}; // filled by individual tab js file
|
||||
|
||||
var GUI_control = function() {
|
||||
var GUI_control = function () {
|
||||
this.auto_connect = false;
|
||||
this.connecting_to = false;
|
||||
this.connected_to = false;
|
||||
|
@ -29,7 +29,7 @@ var GUI_control = function() {
|
|||
// code = function reference (code to be executed)
|
||||
// interval = time interval in miliseconds
|
||||
// first = true/false if code should be ran initially before next timer interval hits
|
||||
GUI_control.prototype.interval_add = function(name, code, interval, first) {
|
||||
GUI_control.prototype.interval_add = function (name, code, interval, first) {
|
||||
var data = {'name': name, 'timer': undefined, 'code': code, 'interval': interval, 'fired': 0, 'paused': false};
|
||||
|
||||
if (first == true) {
|
||||
|
@ -50,7 +50,7 @@ GUI_control.prototype.interval_add = function(name, code, interval, first) {
|
|||
};
|
||||
|
||||
// name = string
|
||||
GUI_control.prototype.interval_remove = function(name) {
|
||||
GUI_control.prototype.interval_remove = function (name) {
|
||||
for (var i = 0; i < this.interval_array.length; i++) {
|
||||
if (this.interval_array[i].name == name) {
|
||||
clearInterval(this.interval_array[i].timer); // stop timer
|
||||
|
@ -65,7 +65,7 @@ GUI_control.prototype.interval_remove = function(name) {
|
|||
};
|
||||
|
||||
// name = string
|
||||
GUI_control.prototype.interval_pause = function(name) {
|
||||
GUI_control.prototype.interval_pause = function (name) {
|
||||
for (var i = 0; i < this.interval_array.length; i++) {
|
||||
if (this.interval_array[i].name == name) {
|
||||
clearInterval(this.interval_array[i].timer);
|
||||
|
@ -79,7 +79,7 @@ GUI_control.prototype.interval_pause = function(name) {
|
|||
};
|
||||
|
||||
// name = string
|
||||
GUI_control.prototype.interval_resume = function(name) {
|
||||
GUI_control.prototype.interval_resume = function (name) {
|
||||
for (var i = 0; i < this.interval_array.length; i++) {
|
||||
if (this.interval_array[i].name == name && this.interval_array[i].paused) {
|
||||
var obj = this.interval_array[i];
|
||||
|
@ -101,14 +101,14 @@ GUI_control.prototype.interval_resume = function(name) {
|
|||
|
||||
// input = array of timers thats meant to be kept, or nothing
|
||||
// return = returns timers killed in last call
|
||||
GUI_control.prototype.interval_kill_all = function(keep_array) {
|
||||
GUI_control.prototype.interval_kill_all = function (keep_array) {
|
||||
var self = this;
|
||||
var timers_killed = 0;
|
||||
|
||||
for (var i = (this.interval_array.length - 1); i >= 0; i--) { // reverse iteration
|
||||
var keep = false;
|
||||
if (keep_array) { // only run through the array if it exists
|
||||
keep_array.forEach(function(name) {
|
||||
keep_array.forEach(function (name) {
|
||||
if (self.interval_array[i].name == name) {
|
||||
keep = true;
|
||||
}
|
||||
|
@ -130,7 +130,7 @@ GUI_control.prototype.interval_kill_all = function(keep_array) {
|
|||
// name = string
|
||||
// code = function reference (code to be executed)
|
||||
// timeout = timeout in miliseconds
|
||||
GUI_control.prototype.timeout_add = function(name, code, timeout) {
|
||||
GUI_control.prototype.timeout_add = function (name, code, timeout) {
|
||||
var self = this;
|
||||
var data = {'name': name, 'timer': undefined, 'timeout': timeout};
|
||||
|
||||
|
@ -149,7 +149,7 @@ GUI_control.prototype.timeout_add = function(name, code, timeout) {
|
|||
};
|
||||
|
||||
// name = string
|
||||
GUI_control.prototype.timeout_remove = function(name) {
|
||||
GUI_control.prototype.timeout_remove = function (name) {
|
||||
for (var i = 0; i < this.timeout_array.length; i++) {
|
||||
if (this.timeout_array[i].name == name) {
|
||||
clearTimeout(this.timeout_array[i].timer); // stop timer
|
||||
|
@ -165,7 +165,7 @@ GUI_control.prototype.timeout_remove = function(name) {
|
|||
|
||||
// no input paremeters
|
||||
// return = returns timers killed in last call
|
||||
GUI_control.prototype.timeout_kill_all = function() {
|
||||
GUI_control.prototype.timeout_kill_all = function () {
|
||||
var timers_killed = 0;
|
||||
|
||||
for (var i = 0; i < this.timeout_array.length; i++) {
|
||||
|
@ -180,7 +180,7 @@ GUI_control.prototype.timeout_kill_all = function() {
|
|||
};
|
||||
|
||||
// message = string
|
||||
GUI_control.prototype.log = function(message) {
|
||||
GUI_control.prototype.log = function (message) {
|
||||
var command_log = $('div#log');
|
||||
var d = new Date();
|
||||
var time = ((d.getHours() < 10) ? '0' + d.getHours(): d.getHours())
|
||||
|
@ -194,7 +194,7 @@ GUI_control.prototype.log = function(message) {
|
|||
// Method is called every time a valid tab change event is received
|
||||
// callback = code to run when cleanup is finished
|
||||
// default switch doesn't require callback to be set
|
||||
GUI_control.prototype.tab_switch_cleanup = function(callback) {
|
||||
GUI_control.prototype.tab_switch_cleanup = function (callback) {
|
||||
MSP.callbacks_cleanup(); // we don't care about any old data that might or might not arrive
|
||||
GUI.interval_kill_all(); // all intervals (mostly data pulling) needs to be removed on tab switch
|
||||
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
'use strict';
|
||||
|
||||
var configuration_received = false;
|
||||
|
||||
$(document).ready(function() {
|
||||
$('div#port-picker a.connect').click(function() {
|
||||
if (GUI.connect_lock != true) { // GUI control overrides the user control
|
||||
|
@ -36,8 +34,8 @@ $(document).ready(function() {
|
|||
|
||||
MSP.disconnect_cleanup();
|
||||
PortUsage.reset();
|
||||
configuration_received = false; // reset valid config received variable (used to block tabs while not connected properly)
|
||||
MSP_pass_through = false;
|
||||
CONFIGURATOR.connectionValid = false;
|
||||
CONFIGURATOR.mspPassThrough = false;
|
||||
|
||||
// unlock port select & baud
|
||||
$('div#port-picker #port').prop('disabled', false);
|
||||
|
@ -127,10 +125,10 @@ function onOpen(openInfo) {
|
|||
|
||||
serial.onReceive.addListener(read_serial);
|
||||
|
||||
if (!MSP_pass_through) {
|
||||
if (!CONFIGURATOR.mspPassThrough) {
|
||||
// disconnect after 10 seconds with error if we don't get IDENT data
|
||||
GUI.timeout_add('connecting', function() {
|
||||
if (!configuration_received) {
|
||||
if (!CONFIGURATOR.connectionValid) {
|
||||
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
|
||||
|
||||
$('div#port-picker a.connect').click(); // disconnect
|
||||
|
@ -145,13 +143,13 @@ function onOpen(openInfo) {
|
|||
|
||||
GUI.log(chrome.i18n.getMessage('firmwareVersion', [CONFIG.version]));
|
||||
|
||||
if (CONFIG.version >= firmware_version_accepted) {
|
||||
configuration_received = true;
|
||||
if (CONFIG.version >= CONFIGURATOR.firmwareVersionAccepted) {
|
||||
CONFIGURATOR.connectionValid = true;
|
||||
|
||||
$('div#port-picker a.connect').text(chrome.i18n.getMessage('disconnect')).addClass('active');
|
||||
$('#tabs li a:first').click();
|
||||
} else {
|
||||
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [firmware_version_accepted]));
|
||||
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.firmwareVersionAccepted]));
|
||||
$('div#port-picker a.connect').click(); // disconnect
|
||||
}
|
||||
});
|
||||
|
@ -184,18 +182,18 @@ function onClosed(result) {
|
|||
}
|
||||
|
||||
function read_serial(info) {
|
||||
if (!CLI_active && !MSP_pass_through) {
|
||||
if (!CONFIGURATOR.cliActive && !CONFIGURATOR.mspPassThrough) {
|
||||
MSP.read(info);
|
||||
} else if (CLI_active) {
|
||||
handle_CLI(info);
|
||||
} else if (MSP_pass_through) { // needs to be verified, might be removed after pass_through is 100% deployed
|
||||
} else if (CONFIGURATOR.cliActive) {
|
||||
tabs.cli.read(info);
|
||||
} else if (CONFIGURATOR.mspPassThrough) {
|
||||
MSP.read(info);
|
||||
}
|
||||
}
|
||||
|
||||
function sensor_status(sensors_detected) {
|
||||
// initialize variable (if it wasn't)
|
||||
if (typeof sensor_status.previous_sensors_detected == 'undefined') {
|
||||
if (sensor_status.previous_sensors_detected === 'undefined') {
|
||||
sensor_status.previous_sensors_detected = 0;
|
||||
}
|
||||
|
||||
|
|
113
main.js
113
main.js
|
@ -50,7 +50,7 @@ $(document).ready(function () {
|
|||
tab = $(self).parent().prop('class');
|
||||
|
||||
// if there is no active connection, return
|
||||
if (!configuration_received && tab != 'tab_logging') {
|
||||
if (!CONFIGURATOR.connectionValid && tab != 'tab_logging') {
|
||||
GUI.log('You need to <strong>connect</strong> before you can view any of the tabs');
|
||||
return;
|
||||
}
|
||||
|
@ -264,113 +264,4 @@ function bytesToSize(bytes) {
|
|||
}
|
||||
|
||||
return bytes;
|
||||
}
|
||||
|
||||
/*
|
||||
function add_custom_spinners() {
|
||||
var spinner_element = '<div class="spinner"><div class="up"></div><div class="down"></div></div>';
|
||||
|
||||
$('input[type="number"]').each(function() {
|
||||
var input = $(this);
|
||||
|
||||
// only add new spinner if one doesn't already exist
|
||||
if (!input.next().hasClass('spinner')) {
|
||||
var isInt = true;
|
||||
if (input.prop('step') == '') {
|
||||
isInt = true;
|
||||
} else {
|
||||
if (input.prop('step').indexOf('.') == -1) {
|
||||
isInt = true;
|
||||
} else {
|
||||
isInt = false;
|
||||
}
|
||||
}
|
||||
|
||||
// make space for spinner
|
||||
input.width(input.width() - 16);
|
||||
|
||||
// add spinner
|
||||
input.after(spinner_element);
|
||||
|
||||
// get spinner refference
|
||||
var spinner = input.next();
|
||||
|
||||
// bind UI hooks to spinner
|
||||
$('.up', spinner).click(function() {
|
||||
up();
|
||||
});
|
||||
|
||||
$('.up', spinner).mousedown(function() {
|
||||
GUI.timeout_add('spinner', function() {
|
||||
GUI.interval_add('spinner', function() {
|
||||
up();
|
||||
}, 100, true);
|
||||
}, 250);
|
||||
});
|
||||
|
||||
$('.up', spinner).mouseup(function() {
|
||||
GUI.timeout_remove('spinner');
|
||||
GUI.interval_remove('spinner');
|
||||
});
|
||||
|
||||
$('.up', spinner).mouseleave(function() {
|
||||
GUI.timeout_remove('spinner');
|
||||
GUI.interval_remove('spinner');
|
||||
});
|
||||
|
||||
|
||||
$('.down', spinner).click(function() {
|
||||
down();
|
||||
});
|
||||
|
||||
$('.down', spinner).mousedown(function() {
|
||||
GUI.timeout_add('spinner', function() {
|
||||
GUI.interval_add('spinner', function() {
|
||||
down();
|
||||
}, 100, true);
|
||||
}, 250);
|
||||
});
|
||||
|
||||
$('.down', spinner).mouseup(function() {
|
||||
GUI.timeout_remove('spinner');
|
||||
GUI.interval_remove('spinner');
|
||||
});
|
||||
|
||||
$('.down', spinner).mouseleave(function() {
|
||||
GUI.timeout_remove('spinner');
|
||||
GUI.interval_remove('spinner');
|
||||
});
|
||||
|
||||
var up = function() {
|
||||
if (isInt) {
|
||||
var current_value = parseInt(input.val());
|
||||
input.val(current_value + 1);
|
||||
} else {
|
||||
var current_value = parseFloat(input.val());
|
||||
var step = parseFloat(input.prop('step'));
|
||||
var step_decimals = input.prop('step').length - 2;
|
||||
|
||||
input.val((current_value + step).toFixed(step_decimals));
|
||||
}
|
||||
|
||||
input.change();
|
||||
};
|
||||
|
||||
var down = function() {
|
||||
if (isInt) {
|
||||
var current_value = parseInt(input.val());
|
||||
input.val(current_value - 1);
|
||||
} else {
|
||||
var current_value = parseFloat(input.val());
|
||||
var step = parseFloat(input.prop('step'));
|
||||
var step_decimals = input.prop('step').length - 2;
|
||||
|
||||
input.val((current_value - step).toFixed(step_decimals));
|
||||
}
|
||||
|
||||
input.change();
|
||||
};
|
||||
}
|
||||
});
|
||||
}
|
||||
*/
|
||||
}
|
190
tabs/cli.js
190
tabs/cli.js
|
@ -1,9 +1,10 @@
|
|||
'use strict';
|
||||
|
||||
var CLI_active = false;
|
||||
var CLI_valid = false;
|
||||
tabs.cli = {
|
||||
'validateText': "",
|
||||
'sequenceElements': 0
|
||||
};
|
||||
|
||||
tabs.cli = {};
|
||||
tabs.cli.initialize = function(callback) {
|
||||
var self = this;
|
||||
GUI.active_tab_ref = this;
|
||||
|
@ -14,7 +15,7 @@ tabs.cli.initialize = function(callback) {
|
|||
// translate to user-selected language
|
||||
localize();
|
||||
|
||||
CLI_active = true;
|
||||
CONFIGURATOR.cliActive = true;
|
||||
|
||||
// Enter CLI mode
|
||||
var bufferOut = new ArrayBuffer(1);
|
||||
|
@ -26,7 +27,7 @@ tabs.cli.initialize = function(callback) {
|
|||
|
||||
var textarea = $('.tab-cli textarea');
|
||||
|
||||
textarea.keypress(function(event) {
|
||||
textarea.keypress(function (event) {
|
||||
if (event.which == 13) { // enter
|
||||
event.preventDefault(); // prevent the adding of new line
|
||||
|
||||
|
@ -36,7 +37,7 @@ tabs.cli.initialize = function(callback) {
|
|||
|
||||
var timeout_needle = 0;
|
||||
for (var i = 0; i < out_arr.length; i++) {
|
||||
send_slowly(out_arr, i, timeout_needle++);
|
||||
self.sendSlowly(out_arr, i, timeout_needle++);
|
||||
}
|
||||
|
||||
textarea.val('');
|
||||
|
@ -65,19 +66,100 @@ tabs.cli.history = {
|
|||
index: 0
|
||||
};
|
||||
|
||||
tabs.cli.history.add = function(str) {
|
||||
tabs.cli.history.add = function (str) {
|
||||
this.history.push(str);
|
||||
this.index = this.history.length;
|
||||
};
|
||||
tabs.cli.history.prev = function() {
|
||||
tabs.cli.history.prev = function () {
|
||||
if (this.index > 0) this.index -= 1;
|
||||
return this.history[this.index];
|
||||
};
|
||||
tabs.cli.history.next = function() {
|
||||
tabs.cli.history.next = function () {
|
||||
if (this.index < this.history.length) this.index += 1;
|
||||
return this.history[this.index - 1];
|
||||
};
|
||||
|
||||
tabs.cli.sendSlowly = function (out_arr, i, timeout_needle) {
|
||||
GUI.timeout_add('CLI_send_slowly', function () {
|
||||
var bufferOut = new ArrayBuffer(out_arr[i].length + 1);
|
||||
var bufView = new Uint8Array(bufferOut);
|
||||
|
||||
for (var c_key = 0; c_key < out_arr[i].length; c_key++) {
|
||||
bufView[c_key] = out_arr[i].charCodeAt(c_key);
|
||||
}
|
||||
|
||||
bufView[out_arr[i].length] = 0x0D; // enter (\n)
|
||||
|
||||
serial.send(bufferOut, function (writeInfo) {});
|
||||
}, timeout_needle * 5);
|
||||
};
|
||||
|
||||
tabs.cli.read = function (readInfo) {
|
||||
/* Some info about handling line feeds and carriage return
|
||||
|
||||
line feed = LF = \n = 0x0A = 10
|
||||
carriage return = CR = \r = 0x0D = 13
|
||||
|
||||
MAC only understands CR
|
||||
Linux and Unix only understand LF
|
||||
Windows understands (both) CRLF
|
||||
Chrome OS currenty unknown
|
||||
*/
|
||||
var data = new Uint8Array(readInfo.data),
|
||||
text = "";
|
||||
|
||||
for (var i = 0; i < data.length; i++) {
|
||||
if (CONFIGURATOR.cliValid) {
|
||||
if (data[i] == 27 || this.sequenceElements > 0) { // ESC + other
|
||||
this.sequenceElements++;
|
||||
|
||||
// delete previous space
|
||||
if (this.sequenceElements == 1) {
|
||||
text = text.substring(0, text.length -1);
|
||||
}
|
||||
|
||||
// Reset
|
||||
if (this.sequenceElements >= 5) {
|
||||
this.sequenceElements = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (this.sequenceElements == 0) {
|
||||
switch (data[i]) {
|
||||
case 10: // line feed
|
||||
if (GUI.operating_system != "MacOS") {
|
||||
text += "<br />";
|
||||
}
|
||||
break;
|
||||
case 13: // carriage return
|
||||
if (GUI.operating_system == "MacOS") {
|
||||
text += "<br />";
|
||||
}
|
||||
break;
|
||||
default:
|
||||
text += String.fromCharCode(data[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// try to catch part of valid CLI enter message
|
||||
this.validateText += String.fromCharCode(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
if (!CONFIGURATOR.cliValid && this.validateText.indexOf('CLI') != -1) {
|
||||
CONFIGURATOR.cliValid = true;
|
||||
this.validateText = "";
|
||||
|
||||
text = "Entering CLI Mode, type 'exit' to return, or 'help'<br /><br /># ";
|
||||
}
|
||||
|
||||
$('.tab-cli .window .wrapper').append(text);
|
||||
$('.tab-cli .window').scrollTop($('.tab-cli .window .wrapper').height());
|
||||
|
||||
// there seems to be some sort of initial rendering glitch in 33+, we will force redraw/refill
|
||||
$('.tab-cli .window .wrapper').css('webkitTransform', 'scale(1)');
|
||||
};
|
||||
|
||||
tabs.cli.cleanup = function(callback) {
|
||||
var bufferOut = new ArrayBuffer(5);
|
||||
var bufView = new Uint8Array(bufferOut);
|
||||
|
@ -94,94 +176,10 @@ tabs.cli.cleanup = function(callback) {
|
|||
// we can setup an interval asking for data lets say every 200ms, when data arrives, callback will be triggered and tab switched
|
||||
// we could probably implement this someday
|
||||
GUI.timeout_add('waiting_for_bootup', function() {
|
||||
CLI_active = false;
|
||||
CLI_valid = false;
|
||||
CONFIGURATOR.cliActive = false;
|
||||
CONFIGURATOR.cliValid = false;
|
||||
|
||||
if (callback) callback();
|
||||
}, 5000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one
|
||||
});
|
||||
};
|
||||
|
||||
function send_slowly(out_arr, i, timeout_needle) {
|
||||
GUI.timeout_add('CLI_send_slowly', function() {
|
||||
var bufferOut = new ArrayBuffer(out_arr[i].length + 1);
|
||||
var bufView = new Uint8Array(bufferOut);
|
||||
|
||||
for (var c_key = 0; c_key < out_arr[i].length; c_key++) {
|
||||
bufView[c_key] = out_arr[i].charCodeAt(c_key);
|
||||
}
|
||||
|
||||
bufView[out_arr[i].length] = 0x0D; // enter (\n)
|
||||
|
||||
serial.send(bufferOut, function(writeInfo) {});
|
||||
}, timeout_needle * 5);
|
||||
}
|
||||
|
||||
/* Some info about handling line feeds and carriage return
|
||||
|
||||
line feed = LF = \n = 0x0A = 10
|
||||
carriage return = CR = \r = 0x0D = 13
|
||||
|
||||
MAC only understands CR
|
||||
Linux and Unix only understand LF
|
||||
Windows understands (both) CRLF
|
||||
Chrome OS currenty unknown
|
||||
*/
|
||||
|
||||
var sequence_elements = 0;
|
||||
var CLI_validate_text = "";
|
||||
function handle_CLI(readInfo) {
|
||||
var data = new Uint8Array(readInfo.data);
|
||||
var text = "";
|
||||
|
||||
for (var i = 0; i < data.length; i++) {
|
||||
if (CLI_valid) {
|
||||
if (data[i] == 27 || sequence_elements > 0) { // ESC + other
|
||||
sequence_elements++;
|
||||
|
||||
// delete previous space
|
||||
if (sequence_elements == 1) {
|
||||
text = text.substring(0, text.length -1);
|
||||
}
|
||||
|
||||
// Reset
|
||||
if (sequence_elements >= 5) {
|
||||
sequence_elements = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (sequence_elements == 0) {
|
||||
switch (data[i]) {
|
||||
case 10: // line feed
|
||||
if (GUI.operating_system != "MacOS") {
|
||||
text += "<br />";
|
||||
}
|
||||
break;
|
||||
case 13: // carriage return
|
||||
if (GUI.operating_system == "MacOS") {
|
||||
text += "<br />";
|
||||
}
|
||||
break;
|
||||
default:
|
||||
text += String.fromCharCode(data[i]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// try to catch part of valid CLI enter message
|
||||
CLI_validate_text += String.fromCharCode(data[i]);
|
||||
}
|
||||
}
|
||||
|
||||
if (!CLI_valid && CLI_validate_text.indexOf('CLI') != -1) {
|
||||
CLI_valid = true;
|
||||
CLI_validate_text = "";
|
||||
|
||||
text = "Entering CLI Mode, type 'exit' to return, or 'help'<br /><br /># ";
|
||||
}
|
||||
|
||||
$('.tab-cli .window .wrapper').append(text);
|
||||
$('.tab-cli .window').scrollTop($('.tab-cli .window .wrapper').height());
|
||||
|
||||
// there seems to be some sort of initial rendering glitch in 33+, we will force redraw/refill
|
||||
$('.tab-cli .window .wrapper').css('webkitTransform', 'scale(1)');
|
||||
}
|
||||
};
|
|
@ -1,7 +1,5 @@
|
|||
'use strict';
|
||||
|
||||
var MSP_pass_through = false;
|
||||
|
||||
tabs.logging = {};
|
||||
tabs.logging.initialize = function(callback) {
|
||||
GUI.active_tab_ref = this;
|
||||
|
@ -10,7 +8,7 @@ tabs.logging.initialize = function(callback) {
|
|||
|
||||
var requested_properties = [];
|
||||
|
||||
if (configuration_received) {
|
||||
if (CONFIGURATOR.connectionValid) {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, get_motor_data);
|
||||
|
||||
var get_motor_data = function () {
|
||||
|
@ -21,7 +19,7 @@ tabs.logging.initialize = function(callback) {
|
|||
$('#content').load("./tabs/logging.html", process_html);
|
||||
}
|
||||
} else {
|
||||
MSP_pass_through = true;
|
||||
CONFIGURATOR.mspPassThrough = true;
|
||||
|
||||
// we will initialize RC.channels array and MOTOR_DATA array manually
|
||||
RC.active_channels = 8;
|
||||
|
@ -70,7 +68,7 @@ tabs.logging.initialize = function(callback) {
|
|||
}
|
||||
|
||||
// request new
|
||||
if (!MSP_pass_through) {
|
||||
if (!CONFIGURATOR.mspPassThrough) {
|
||||
for (var i = 0; i < requested_properties.length; i++, requests++) {
|
||||
MSP.send_message(MSP_codes[requested_properties[i]]);
|
||||
}
|
||||
|
@ -113,7 +111,7 @@ tabs.logging.initialize = function(callback) {
|
|||
}
|
||||
});
|
||||
|
||||
if (MSP_pass_through) {
|
||||
if (CONFIGURATOR.mspPassThrough) {
|
||||
$('a.back').show();
|
||||
|
||||
$('a.back').click(function() {
|
||||
|
@ -121,7 +119,7 @@ tabs.logging.initialize = function(callback) {
|
|||
$('a.connect').click();
|
||||
} else {
|
||||
GUI.tab_switch_cleanup(function() {
|
||||
MSP_pass_through = false;
|
||||
CONFIGURATOR.mspPassThrough = false;
|
||||
$('#tabs > ul li').removeClass('active');
|
||||
tabs.default.initialize();
|
||||
});
|
||||
|
|
Loading…
Reference in New Issue