mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-14 03:49:53 +03:00
timing methods extracted to separate classes
This commit is contained in:
parent
fc11eca5c0
commit
d1fcb81017
26 changed files with 262 additions and 219 deletions
|
@ -802,7 +802,7 @@ function configuration_restore(callback) {
|
||||||
function reinitialize() {
|
function reinitialize() {
|
||||||
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||||
|
|
||||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
|
||||||
MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () {
|
||||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||||
|
|
||||||
|
|
161
js/gui.js
161
js/gui.js
|
@ -11,8 +11,6 @@ var GUI_control = function () {
|
||||||
this.active_tab;
|
this.active_tab;
|
||||||
this.tab_switch_in_progress = false;
|
this.tab_switch_in_progress = false;
|
||||||
this.operating_system;
|
this.operating_system;
|
||||||
this.interval_array = [];
|
|
||||||
this.timeout_array = [];
|
|
||||||
this.defaultAllowedTabsWhenDisconnected = [
|
this.defaultAllowedTabsWhenDisconnected = [
|
||||||
'landing',
|
'landing',
|
||||||
'firmware_flasher',
|
'firmware_flasher',
|
||||||
|
@ -51,162 +49,6 @@ var GUI_control = function () {
|
||||||
else this.operating_system = "Unknown";
|
else this.operating_system = "Unknown";
|
||||||
};
|
};
|
||||||
|
|
||||||
// Timer managing methods
|
|
||||||
|
|
||||||
// name = string
|
|
||||||
// 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) {
|
|
||||||
var data = {'name': name, 'timer': null, 'code': code, 'interval': interval, 'fired': 0, 'paused': false};
|
|
||||||
|
|
||||||
if (first == true) {
|
|
||||||
code(); // execute code
|
|
||||||
|
|
||||||
data.fired++; // increment counter
|
|
||||||
}
|
|
||||||
|
|
||||||
data.timer = setInterval(function() {
|
|
||||||
code(); // execute code
|
|
||||||
|
|
||||||
data.fired++; // increment counter
|
|
||||||
}, interval);
|
|
||||||
|
|
||||||
this.interval_array.push(data); // push to primary interval array
|
|
||||||
|
|
||||||
return data;
|
|
||||||
};
|
|
||||||
|
|
||||||
// name = string
|
|
||||||
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
|
|
||||||
|
|
||||||
this.interval_array.splice(i, 1); // remove element/object from array
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
};
|
|
||||||
|
|
||||||
// name = string
|
|
||||||
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);
|
|
||||||
this.interval_array[i].paused = true;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
};
|
|
||||||
|
|
||||||
// name = string
|
|
||||||
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];
|
|
||||||
|
|
||||||
obj.timer = setInterval(function() {
|
|
||||||
obj.code(); // execute code
|
|
||||||
|
|
||||||
obj.fired++; // increment counter
|
|
||||||
}, obj.interval);
|
|
||||||
|
|
||||||
obj.paused = false;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
};
|
|
||||||
|
|
||||||
// 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) {
|
|
||||||
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) {
|
|
||||||
if (self.interval_array[i].name == name) {
|
|
||||||
keep = true;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!keep) {
|
|
||||||
clearInterval(this.interval_array[i].timer); // stop timer
|
|
||||||
|
|
||||||
this.interval_array.splice(i, 1); // remove element/object from array
|
|
||||||
|
|
||||||
timers_killed++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return timers_killed;
|
|
||||||
};
|
|
||||||
|
|
||||||
// name = string
|
|
||||||
// code = function reference (code to be executed)
|
|
||||||
// timeout = timeout in miliseconds
|
|
||||||
GUI_control.prototype.timeout_add = function (name, code, timeout) {
|
|
||||||
var self = this;
|
|
||||||
var data = {'name': name, 'timer': null, 'timeout': timeout};
|
|
||||||
|
|
||||||
// start timer with "cleaning" callback
|
|
||||||
data.timer = setTimeout(function() {
|
|
||||||
code(); // execute code
|
|
||||||
|
|
||||||
// remove object from array
|
|
||||||
var index = self.timeout_array.indexOf(data);
|
|
||||||
if (index > -1) self.timeout_array.splice(index, 1);
|
|
||||||
}, timeout);
|
|
||||||
|
|
||||||
this.timeout_array.push(data); // push to primary timeout array
|
|
||||||
|
|
||||||
return data;
|
|
||||||
};
|
|
||||||
|
|
||||||
// name = string
|
|
||||||
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
|
|
||||||
|
|
||||||
this.timeout_array.splice(i, 1); // remove element/object from array
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
};
|
|
||||||
|
|
||||||
// no input paremeters
|
|
||||||
// return = returns timers killed in last call
|
|
||||||
GUI_control.prototype.timeout_kill_all = function () {
|
|
||||||
var timers_killed = 0;
|
|
||||||
|
|
||||||
for (var i = 0; i < this.timeout_array.length; i++) {
|
|
||||||
clearTimeout(this.timeout_array[i].timer); // stop timer
|
|
||||||
|
|
||||||
timers_killed++;
|
|
||||||
}
|
|
||||||
|
|
||||||
this.timeout_array = []; // drop objects
|
|
||||||
|
|
||||||
return timers_killed;
|
|
||||||
};
|
|
||||||
|
|
||||||
// message = string
|
// message = string
|
||||||
GUI_control.prototype.log = function (message) {
|
GUI_control.prototype.log = function (message) {
|
||||||
var command_log = $('div#log');
|
var command_log = $('div#log');
|
||||||
|
@ -233,7 +75,8 @@ GUI_control.prototype.log = function (message) {
|
||||||
// default switch doesn't require callback to be set
|
// 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
|
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
|
|
||||||
|
helper.interval.killAll();
|
||||||
|
|
||||||
if (this.active_tab) {
|
if (this.active_tab) {
|
||||||
TABS[this.active_tab].cleanup(callback);
|
TABS[this.active_tab].cleanup(callback);
|
||||||
|
|
131
js/intervals.js
Normal file
131
js/intervals.js
Normal file
|
@ -0,0 +1,131 @@
|
||||||
|
'use strict';
|
||||||
|
|
||||||
|
var helper = helper || {};
|
||||||
|
|
||||||
|
helper.interval = (function () {
|
||||||
|
|
||||||
|
var privateScope = {},
|
||||||
|
publicScope = {};
|
||||||
|
|
||||||
|
privateScope.intervals = [];
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @param {String} name
|
||||||
|
* @param {Function} code function reference (code to be executed)
|
||||||
|
* @param {int} interval time interval in milliseconds
|
||||||
|
* @param {boolean} first true/false if code should be ran initially before next timer interval hits
|
||||||
|
* @returns {{name: *, timer: null, code: *, interval: *, fired: number, paused: boolean}}
|
||||||
|
*/
|
||||||
|
publicScope.add = function (name, code, interval, first) {
|
||||||
|
var data = {
|
||||||
|
'name': name,
|
||||||
|
'timer': null,
|
||||||
|
'code': code,
|
||||||
|
'interval': interval,
|
||||||
|
'fired': 0,
|
||||||
|
'paused': false
|
||||||
|
};
|
||||||
|
|
||||||
|
if (first == true) {
|
||||||
|
code(); // execute code
|
||||||
|
data.fired++; // increment counter
|
||||||
|
}
|
||||||
|
|
||||||
|
data.timer = setInterval(function() {
|
||||||
|
code();
|
||||||
|
data.fired++;
|
||||||
|
}, interval);
|
||||||
|
|
||||||
|
privateScope.intervals.push(data);
|
||||||
|
|
||||||
|
return data;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Method removes and stop execution of interval callback
|
||||||
|
* @param {string} name
|
||||||
|
* @returns {boolean}
|
||||||
|
*/
|
||||||
|
publicScope.remove = function (name) {
|
||||||
|
for (var i = 0; i < privateScope.intervals.length; i++) {
|
||||||
|
if (privateScope.intervals[i].name == name) {
|
||||||
|
clearInterval(privateScope.intervals[i].timer); // stop timer
|
||||||
|
privateScope.intervals.splice(i, 1);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @param {string} name
|
||||||
|
* @returns {boolean}
|
||||||
|
*/
|
||||||
|
publicScope.pause = function (name) {
|
||||||
|
for (var i = 0; i < privateScope.intervals.length; i++) {
|
||||||
|
if (privateScope.intervals[i].name == name) {
|
||||||
|
clearInterval(privateScope.intervals[i].timer);
|
||||||
|
privateScope.intervals[i].paused = true;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @param {string} name
|
||||||
|
* @returns {boolean}
|
||||||
|
*/
|
||||||
|
publicScope.resume = function (name) {
|
||||||
|
for (var i = 0; i < privateScope.intervals.length; i++) {
|
||||||
|
if (privateScope.intervals[i].name == name && privateScope.intervals[i].paused) {
|
||||||
|
var obj = privateScope.intervals[i];
|
||||||
|
|
||||||
|
obj.timer = setInterval(function() {
|
||||||
|
obj.code(); // execute code
|
||||||
|
obj.fired++; // increment counter
|
||||||
|
}, obj.interval);
|
||||||
|
|
||||||
|
obj.paused = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @param {=} keep_array
|
||||||
|
* @returns {number}
|
||||||
|
*/
|
||||||
|
publicScope.killAll = function (keep_array) {
|
||||||
|
var timers_killed = 0;
|
||||||
|
|
||||||
|
for (var i = (privateScope.intervals.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) {
|
||||||
|
if (privateScope.intervals[i].name == name) {
|
||||||
|
keep = true;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!keep) {
|
||||||
|
clearInterval(privateScope.intervals[i].timer); // stop timer
|
||||||
|
privateScope.intervals.splice(i, 1); // remove element/object from array
|
||||||
|
timers_killed++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return timers_killed;
|
||||||
|
};
|
||||||
|
|
||||||
|
return publicScope;
|
||||||
|
})();
|
|
@ -112,7 +112,7 @@ PortHandler.check = function () {
|
||||||
if (GUI.auto_connect && !GUI.connecting_to && !GUI.connected_to) {
|
if (GUI.auto_connect && !GUI.connecting_to && !GUI.connected_to) {
|
||||||
// we need firmware flasher protection over here
|
// we need firmware flasher protection over here
|
||||||
if (GUI.active_tab != 'firmware_flasher') {
|
if (GUI.active_tab != 'firmware_flasher') {
|
||||||
GUI.timeout_add('auto-connect_timeout', function () {
|
helper.timeout.add('auto-connect_timeout', function () {
|
||||||
$('div#port-picker a.connect').click();
|
$('div#port-picker a.connect').click();
|
||||||
}, 100); // timeout so bus have time to initialize after being detected by the system
|
}, 100); // timeout so bus have time to initialize after being detected by the system
|
||||||
}
|
}
|
||||||
|
|
|
@ -154,7 +154,7 @@ STM32_protocol.prototype.initialize = function () {
|
||||||
self.read(info);
|
self.read(info);
|
||||||
});
|
});
|
||||||
|
|
||||||
GUI.interval_add('STM32_timeout', function () {
|
helper.interval.add('STM32_timeout', function () {
|
||||||
if (self.upload_process_alive) { // process is running
|
if (self.upload_process_alive) { // process is running
|
||||||
self.upload_process_alive = false;
|
self.upload_process_alive = false;
|
||||||
} else {
|
} else {
|
||||||
|
@ -166,7 +166,7 @@ STM32_protocol.prototype.initialize = function () {
|
||||||
googleAnalytics.sendEvent('Flashing', 'Programming', 'timeout');
|
googleAnalytics.sendEvent('Flashing', 'Programming', 'timeout');
|
||||||
|
|
||||||
// protocol got stuck, clear timer and disconnect
|
// protocol got stuck, clear timer and disconnect
|
||||||
GUI.interval_remove('STM32_timeout');
|
helper.interval.remove('STM32_timeout');
|
||||||
|
|
||||||
// exit
|
// exit
|
||||||
self.upload_procedure(99);
|
self.upload_procedure(99);
|
||||||
|
@ -361,10 +361,10 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
$('span.progressLabel').text('Contacting bootloader ...');
|
$('span.progressLabel').text('Contacting bootloader ...');
|
||||||
|
|
||||||
var send_counter = 0;
|
var send_counter = 0;
|
||||||
GUI.interval_add('stm32_initialize_mcu', function () { // 200 ms interval (just in case mcu was already initialized), we need to break the 2 bytes command requirement
|
helper.interval.add('stm32_initialize_mcu', function () { // 200 ms interval (just in case mcu was already initialized), we need to break the 2 bytes command requirement
|
||||||
self.send([0x7F], 1, function (reply) {
|
self.send([0x7F], 1, function (reply) {
|
||||||
if (reply[0] == 0x7F || reply[0] == self.status.ACK || reply[0] == self.status.NACK) {
|
if (reply[0] == 0x7F || reply[0] == self.status.ACK || reply[0] == self.status.NACK) {
|
||||||
GUI.interval_remove('stm32_initialize_mcu');
|
helper.interval.remove('stm32_initialize_mcu');
|
||||||
console.log('STM32 - Serial interface initialized on the MCU side');
|
console.log('STM32 - Serial interface initialized on the MCU side');
|
||||||
|
|
||||||
// proceed to next step
|
// proceed to next step
|
||||||
|
@ -373,7 +373,7 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
$('span.progressLabel').text('Communication with bootloader failed');
|
$('span.progressLabel').text('Communication with bootloader failed');
|
||||||
self.progress_bar_e.addClass('invalid');
|
self.progress_bar_e.addClass('invalid');
|
||||||
|
|
||||||
GUI.interval_remove('stm32_initialize_mcu');
|
helper.interval.remove('stm32_initialize_mcu');
|
||||||
|
|
||||||
// disconnect
|
// disconnect
|
||||||
self.upload_procedure(99);
|
self.upload_procedure(99);
|
||||||
|
@ -387,8 +387,8 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
$('span.progressLabel').text('No response from the bootloader, programming: FAILED');
|
$('span.progressLabel').text('No response from the bootloader, programming: FAILED');
|
||||||
self.progress_bar_e.addClass('invalid');
|
self.progress_bar_e.addClass('invalid');
|
||||||
|
|
||||||
GUI.interval_remove('stm32_initialize_mcu');
|
helper.interval.remove('stm32_initialize_mcu');
|
||||||
GUI.interval_remove('STM32_timeout');
|
helper.interval.remove('STM32_timeout');
|
||||||
|
|
||||||
// exit
|
// exit
|
||||||
self.upload_procedure(99);
|
self.upload_procedure(99);
|
||||||
|
@ -749,7 +749,7 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
break;
|
break;
|
||||||
case 99:
|
case 99:
|
||||||
// disconnect
|
// disconnect
|
||||||
GUI.interval_remove('STM32_timeout'); // stop STM32 timeout timer (everything is finished now)
|
helper.interval.remove('STM32_timeout'); // stop STM32 timeout timer (everything is finished now)
|
||||||
|
|
||||||
// close connection
|
// close connection
|
||||||
serial.disconnect(function (result) {
|
serial.disconnect(function (result) {
|
||||||
|
|
|
@ -35,7 +35,7 @@ $(document).ready(function () {
|
||||||
}, 5000);
|
}, 5000);
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
|
||||||
MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () {
|
||||||
//noinspection JSUnresolvedVariable
|
//noinspection JSUnresolvedVariable
|
||||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||||
|
@ -98,8 +98,8 @@ $(document).ready(function () {
|
||||||
|
|
||||||
serial.connect(selected_port, {bitrate: selected_baud}, onOpen);
|
serial.connect(selected_port, {bitrate: selected_baud}, onOpen);
|
||||||
} else {
|
} else {
|
||||||
GUI.timeout_kill_all();
|
helper.timeout.killAll();
|
||||||
GUI.interval_kill_all();
|
helper.interval.killAll();
|
||||||
GUI.tab_switch_cleanup();
|
GUI.tab_switch_cleanup();
|
||||||
GUI.tab_switch_in_progress = false;
|
GUI.tab_switch_in_progress = false;
|
||||||
|
|
||||||
|
@ -213,7 +213,7 @@ function onOpen(openInfo) {
|
||||||
serial.onReceive.addListener(read_serial);
|
serial.onReceive.addListener(read_serial);
|
||||||
|
|
||||||
// disconnect after 10 seconds with error if we don't get IDENT data
|
// disconnect after 10 seconds with error if we don't get IDENT data
|
||||||
GUI.timeout_add('connecting', function () {
|
helper.timeout.add('connecting', function () {
|
||||||
if (!CONFIGURATOR.connectionValid) {
|
if (!CONFIGURATOR.connectionValid) {
|
||||||
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
|
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
|
||||||
|
|
||||||
|
@ -306,7 +306,7 @@ function onOpen(openInfo) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function onConnect() {
|
function onConnect() {
|
||||||
GUI.timeout_remove('connecting'); // kill connecting timer
|
helper.timeout.remove('connecting'); // kill connecting timer
|
||||||
$('div#connectbutton a.connect_state').text(chrome.i18n.getMessage('disconnect')).addClass('active');
|
$('div#connectbutton a.connect_state').text(chrome.i18n.getMessage('disconnect')).addClass('active');
|
||||||
$('div#connectbutton a.connect').addClass('active');
|
$('div#connectbutton a.connect').addClass('active');
|
||||||
$('#tabs ul.mode-disconnected').hide();
|
$('#tabs ul.mode-disconnected').hide();
|
||||||
|
@ -488,7 +488,7 @@ function update_dataflash_global() {
|
||||||
|
|
||||||
function startLiveDataRefreshTimer() {
|
function startLiveDataRefreshTimer() {
|
||||||
// live data refresh
|
// live data refresh
|
||||||
GUI.timeout_add('data_refresh', function () { update_live_status(); }, 100);
|
helper.timeout.add('data_refresh', function () { update_live_status(); }, 100);
|
||||||
}
|
}
|
||||||
|
|
||||||
function update_live_status() {
|
function update_live_status() {
|
||||||
|
@ -566,7 +566,7 @@ function update_live_status() {
|
||||||
}
|
}
|
||||||
|
|
||||||
statuswrapper.show();
|
statuswrapper.show();
|
||||||
GUI.timeout_remove('data_refresh');
|
helper.timeout.remove('data_refresh');
|
||||||
startLiveDataRefreshTimer();
|
startLiveDataRefreshTimer();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
66
js/timeouts.js
Normal file
66
js/timeouts.js
Normal file
|
@ -0,0 +1,66 @@
|
||||||
|
'use strict';
|
||||||
|
|
||||||
|
var helper = helper || {};
|
||||||
|
|
||||||
|
helper.timeout = (function () {
|
||||||
|
|
||||||
|
var privateScope = {},
|
||||||
|
publicScope = {};
|
||||||
|
|
||||||
|
privateScope.timeouts = [];
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @param {string} name
|
||||||
|
* @param {function } code
|
||||||
|
* @param {number} timeout
|
||||||
|
* @returns {{name: *, timer: null, timeout: *}}
|
||||||
|
*/
|
||||||
|
publicScope.add = function (name, code, timeout) {
|
||||||
|
var data = {'name': name, 'timer': null, 'timeout': timeout};
|
||||||
|
|
||||||
|
// start timer with "cleaning" callback
|
||||||
|
data.timer = setTimeout(function() {
|
||||||
|
code(); // execute code
|
||||||
|
|
||||||
|
// remove object from array
|
||||||
|
var index = privateScope.timeouts.indexOf(data);
|
||||||
|
if (index > -1) privateScope.timeouts.splice(index, 1);
|
||||||
|
}, timeout);
|
||||||
|
|
||||||
|
privateScope.timeouts.push(data); // push to primary timeout array
|
||||||
|
|
||||||
|
return data;
|
||||||
|
};
|
||||||
|
|
||||||
|
publicScope.remove = function (name) {
|
||||||
|
for (var i = 0; i < privateScope.timeouts.length; i++) {
|
||||||
|
if (privateScope.timeouts[i].name == name) {
|
||||||
|
clearTimeout(privateScope.timeouts[i].timer); // stop timer
|
||||||
|
privateScope.timeouts.splice(i, 1); // remove element/object from array
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
*
|
||||||
|
* @returns {number} number of killed timeouts
|
||||||
|
*/
|
||||||
|
publicScope.killAll = function () {
|
||||||
|
var timers_killed = 0;
|
||||||
|
|
||||||
|
for (var i = 0; i < privateScope.timeouts.length; i++) {
|
||||||
|
clearTimeout(privateScope.timeouts[i].timer); // stop timer
|
||||||
|
timers_killed++;
|
||||||
|
}
|
||||||
|
|
||||||
|
privateScope.timeouts = []; // drop objects
|
||||||
|
|
||||||
|
return timers_killed;
|
||||||
|
};
|
||||||
|
|
||||||
|
return publicScope;
|
||||||
|
})();
|
|
@ -50,6 +50,8 @@
|
||||||
<script type="text/javascript" src="./js/libraries/inflection.min.js"></script>
|
<script type="text/javascript" src="./js/libraries/inflection.min.js"></script>
|
||||||
<script type="text/javascript" src="./js/libraries/bluebird.min.js"></script>
|
<script type="text/javascript" src="./js/libraries/bluebird.min.js"></script>
|
||||||
<script type="text/javascript" src="./js/injected_methods.js"></script>
|
<script type="text/javascript" src="./js/injected_methods.js"></script>
|
||||||
|
<script type="text/javascript" src="./js/intervals.js"></script>
|
||||||
|
<script type="text/javascript" src="./js/timeouts.js"></script>
|
||||||
<script type="text/javascript" src="./js/gui.js"></script>
|
<script type="text/javascript" src="./js/gui.js"></script>
|
||||||
<script type="text/javascript" src="./js/msp/MSPCodes.js"></script>
|
<script type="text/javascript" src="./js/msp/MSPCodes.js"></script>
|
||||||
<script type="text/javascript" src="./js/msp/MSPHelper.js"></script>
|
<script type="text/javascript" src="./js/msp/MSPHelper.js"></script>
|
||||||
|
|
|
@ -269,10 +269,10 @@ TABS.adjustments.initialize = function (callback) {
|
||||||
update_ui();
|
update_ui();
|
||||||
|
|
||||||
// enable data pulling
|
// enable data pulling
|
||||||
GUI.interval_add('aux_data_pull', get_rc_data, 50);
|
helper.interval.add('aux_data_pull', get_rc_data, 50);
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function () {
|
helper.interval.add('status_pull', function () {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -288,10 +288,10 @@ TABS.auxiliary.initialize = function (callback) {
|
||||||
update_ui();
|
update_ui();
|
||||||
|
|
||||||
// enable data pulling
|
// enable data pulling
|
||||||
GUI.interval_add('aux_data_pull', get_rc_data, 50);
|
helper.interval.add('aux_data_pull', get_rc_data, 50);
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function () {
|
helper.interval.add('status_pull', function () {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -55,7 +55,7 @@ TABS.cli.initialize = function (callback) {
|
||||||
// give input element user focus
|
// give input element user focus
|
||||||
textarea.focus();
|
textarea.focus();
|
||||||
|
|
||||||
GUI.timeout_add('enter_cli', function enter_cli() {
|
helper.timeout.add('enter_cli', function enter_cli() {
|
||||||
// Enter CLI mode
|
// Enter CLI mode
|
||||||
var bufferOut = new ArrayBuffer(1);
|
var bufferOut = new ArrayBuffer(1);
|
||||||
var bufView = new Uint8Array(bufferOut);
|
var bufView = new Uint8Array(bufferOut);
|
||||||
|
@ -88,7 +88,7 @@ TABS.cli.history.next = function () {
|
||||||
};
|
};
|
||||||
|
|
||||||
TABS.cli.sendSlowly = function (out_arr, i, timeout_needle) {
|
TABS.cli.sendSlowly = function (out_arr, i, timeout_needle) {
|
||||||
GUI.timeout_add('CLI_send_slowly', function () {
|
helper.timeout.add('CLI_send_slowly', function () {
|
||||||
var bufferOut = new ArrayBuffer(out_arr[i].length + 1);
|
var bufferOut = new ArrayBuffer(out_arr[i].length + 1);
|
||||||
var bufView = new Uint8Array(bufferOut);
|
var bufView = new Uint8Array(bufferOut);
|
||||||
|
|
||||||
|
@ -202,7 +202,7 @@ TABS.cli.cleanup = function (callback) {
|
||||||
// (another approach is however much more complicated):
|
// (another approach is however much more complicated):
|
||||||
// we can setup an interval asking for data lets say every 200ms, when data arrives, callback will be triggered and tab switched
|
// 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
|
// we could probably implement this someday
|
||||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
|
||||||
if (callback) callback();
|
if (callback) callback();
|
||||||
}, 1000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one
|
}, 1000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one
|
||||||
CONFIGURATOR.cliActive = false;
|
CONFIGURATOR.cliActive = false;
|
||||||
|
|
|
@ -633,14 +633,14 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
|
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
|
||||||
}
|
}
|
||||||
}, 250, true);
|
}, 250, true);
|
||||||
GUI.interval_add('config_load_analog', function () {
|
helper.interval.add('config_load_analog', function () {
|
||||||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
|
||||||
$('#batteryvoltage').val([ANALOG.voltage.toFixed(1)]);
|
$('#batteryvoltage').val([ANALOG.voltage.toFixed(1)]);
|
||||||
$('#batterycurrent').val([ANALOG.amperage.toFixed(2)]);
|
$('#batterycurrent').val([ANALOG.amperage.toFixed(2)]);
|
||||||
|
|
|
@ -359,7 +359,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -513,7 +513,7 @@ TABS.firmware_flasher.initialize = function (callback) {
|
||||||
console.log('Detected: ' + port + ' - triggering flash on connect');
|
console.log('Detected: ' + port + ' - triggering flash on connect');
|
||||||
|
|
||||||
// Trigger regular Flashing sequence
|
// Trigger regular Flashing sequence
|
||||||
GUI.timeout_add('initialization_timeout', function () {
|
helper.timeout.add('initialization_timeout', function () {
|
||||||
$('a.flash_firmware').click();
|
$('a.flash_firmware').click();
|
||||||
}, 100); // timeout so bus have time to initialize after being detected by the system
|
}, 100); // timeout so bus have time to initialize after being detected by the system
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -102,7 +102,7 @@ TABS.gps.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// enable data pulling
|
// enable data pulling
|
||||||
GUI.interval_add('gps_pull', function gps_update() {
|
helper.interval.add('gps_pull', function gps_update() {
|
||||||
// avoid usage of the GPS commands until a GPS sensor is detected for targets that are compiled without GPS support.
|
// avoid usage of the GPS commands until a GPS sensor is detected for targets that are compiled without GPS support.
|
||||||
if (!have_sensor(CONFIG.activeSensors, 'gps')) {
|
if (!have_sensor(CONFIG.activeSensors, 'gps')) {
|
||||||
//return;
|
//return;
|
||||||
|
@ -112,7 +112,7 @@ TABS.gps.initialize = function (callback) {
|
||||||
}, 75, true);
|
}, 75, true);
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -65,8 +65,8 @@ TABS.logging.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
GUI.interval_add('log_data_poll', log_data_poll, parseInt($('select.speed').val()), true); // refresh rate goes here
|
helper.interval.add('log_data_poll', log_data_poll, parseInt($('select.speed').val()), true); // refresh rate goes here
|
||||||
GUI.interval_add('write_data', function write_data() {
|
helper.interval.add('write_data', function write_data() {
|
||||||
if (log_buffer.length) { // only execute when there is actual data to write
|
if (log_buffer.length) { // only execute when there is actual data to write
|
||||||
if (fileWriter.readyState == 0 || fileWriter.readyState == 2) {
|
if (fileWriter.readyState == 0 || fileWriter.readyState == 2) {
|
||||||
append_to_file(log_buffer.join('\n'));
|
append_to_file(log_buffer.join('\n'));
|
||||||
|
@ -87,7 +87,7 @@ TABS.logging.initialize = function (callback) {
|
||||||
GUI.log(chrome.i18n.getMessage('loggingErrorOneProperty'));
|
GUI.log(chrome.i18n.getMessage('loggingErrorOneProperty'));
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
GUI.interval_kill_all();
|
helper.interval.killAll();
|
||||||
|
|
||||||
$('.speed').prop('disabled', false);
|
$('.speed').prop('disabled', false);
|
||||||
$(this).text(chrome.i18n.getMessage('loggingStart'));
|
$(this).text(chrome.i18n.getMessage('loggingStart'));
|
||||||
|
|
|
@ -142,10 +142,10 @@ TABS.modes.initialize = function (callback) {
|
||||||
update_ui();
|
update_ui();
|
||||||
|
|
||||||
// enable data pulling
|
// enable data pulling
|
||||||
GUI.interval_add('aux_data_pull', get_rc_data, 50);
|
helper.interval.add('aux_data_pull', get_rc_data, 50);
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -239,9 +239,9 @@ TABS.motors.initialize = function (callback) {
|
||||||
accelHelpers = initGraphHelpers('#accel', samples_accel_i, [-scale, scale]);
|
accelHelpers = initGraphHelpers('#accel', samples_accel_i, [-scale, scale]);
|
||||||
|
|
||||||
// timer initialization
|
// timer initialization
|
||||||
GUI.interval_kill_all(['motor_and_status_pull']);
|
helper.interval.killAll(['motor_and_status_pull']);
|
||||||
|
|
||||||
GUI.interval_add('IMU_pull', function imu_data_pull() {
|
helper.interval.add('IMU_pull', function imu_data_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_accel_graph);
|
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_accel_graph);
|
||||||
}, rate, true);
|
}, rate, true);
|
||||||
|
|
||||||
|
@ -519,7 +519,7 @@ TABS.motors.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// enable Status and Motor data pulling
|
// enable Status and Motor data pulling
|
||||||
GUI.interval_add('motor_and_status_pull', periodicUpdateHandler, 75, true);
|
helper.interval.add('motor_and_status_pull', periodicUpdateHandler, 75, true);
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
}
|
}
|
||||||
|
|
|
@ -290,7 +290,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
}, 250, true);
|
}, 250, true);
|
||||||
|
|
||||||
|
|
|
@ -222,7 +222,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
||||||
$('a.save').click(on_save_handler);
|
$('a.save').click(on_save_handler);
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -368,7 +368,7 @@ TABS.profiles.initialize = function (callback, scrollPosition) {
|
||||||
content: $('#presetApplyContent')
|
content: $('#presetApplyContent')
|
||||||
});
|
});
|
||||||
|
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -464,14 +464,14 @@ TABS.receiver.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// timer initialization
|
// timer initialization
|
||||||
GUI.interval_remove('receiver_pull');
|
helper.interval.remove('receiver_pull');
|
||||||
|
|
||||||
// enable RC data pulling
|
// enable RC data pulling
|
||||||
GUI.interval_add('receiver_pull', get_rc_data, plot_update_rate, true);
|
helper.interval.add('receiver_pull', get_rc_data, plot_update_rate, true);
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -356,29 +356,29 @@ TABS.sensors.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
// timer initialization
|
// timer initialization
|
||||||
GUI.interval_kill_all(['status_pull']);
|
helper.interval.killAll(['status_pull']);
|
||||||
|
|
||||||
// data pulling timers
|
// data pulling timers
|
||||||
if (checkboxes[0] || checkboxes[1] || checkboxes[2]) {
|
if (checkboxes[0] || checkboxes[1] || checkboxes[2]) {
|
||||||
GUI.interval_add('IMU_pull', function imu_data_pull() {
|
helper.interval.add('IMU_pull', function imu_data_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_imu_graphs);
|
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_imu_graphs);
|
||||||
}, fastest, true);
|
}, fastest, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (checkboxes[3]) {
|
if (checkboxes[3]) {
|
||||||
GUI.interval_add('altitude_pull', function altitude_data_pull() {
|
helper.interval.add('altitude_pull', function altitude_data_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_ALTITUDE, false, false, update_altitude_graph);
|
MSP.send_message(MSPCodes.MSP_ALTITUDE, false, false, update_altitude_graph);
|
||||||
}, rates.baro, true);
|
}, rates.baro, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (checkboxes[4]) {
|
if (checkboxes[4]) {
|
||||||
GUI.interval_add('sonar_pull', function sonar_data_pull() {
|
helper.interval.add('sonar_pull', function sonar_data_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_SONAR, false, false, update_sonar_graphs);
|
MSP.send_message(MSPCodes.MSP_SONAR, false, false, update_sonar_graphs);
|
||||||
}, rates.sonar, true);
|
}, rates.sonar, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (checkboxes[5]) {
|
if (checkboxes[5]) {
|
||||||
GUI.interval_add('debug_pull', function debug_data_pull() {
|
helper.interval.add('debug_pull', function debug_data_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_DEBUG, false, false, update_debug_graphs);
|
MSP.send_message(MSPCodes.MSP_DEBUG, false, false, update_debug_graphs);
|
||||||
}, rates.debug, true);
|
}, rates.debug, true);
|
||||||
}
|
}
|
||||||
|
@ -444,7 +444,7 @@ TABS.sensors.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -171,7 +171,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
$('table.directions select, table.directions input, table.fields select, table.fields input').change(function () {
|
$('table.directions select, table.directions input, table.fields select, table.fields input').change(function () {
|
||||||
if ($('div.live input').is(':checked')) {
|
if ($('div.live input').is(':checked')) {
|
||||||
// apply small delay as there seems to be some funky update business going wrong
|
// apply small delay as there seems to be some funky update business going wrong
|
||||||
GUI.timeout_add('servos_update', servos_update, 10);
|
helper.timeout.add('servos_update', servos_update, 10);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
|
@ -189,7 +189,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function () {
|
helper.interval.add('status_pull', function () {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
|
@ -70,15 +70,16 @@ TABS.setup.initialize = function (callback) {
|
||||||
|
|
||||||
// During this period MCU won't be able to process any serial commands because its locked in a for/while loop
|
// During this period MCU won't be able to process any serial commands because its locked in a for/while loop
|
||||||
// until this operation finishes, sending more commands through data_poll() will result in serial buffer overflow
|
// until this operation finishes, sending more commands through data_poll() will result in serial buffer overflow
|
||||||
GUI.interval_pause('setup_data_pull');
|
helper.interval.pause('setup_data_pull');
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_ACC_CALIBRATION, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_ACC_CALIBRATION, false, false, function () {
|
||||||
GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibStarted'));
|
GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibStarted'));
|
||||||
$('#accel_calib_running').show();
|
$('#accel_calib_running').show();
|
||||||
$('#accel_calib_rest').hide();
|
$('#accel_calib_rest').hide();
|
||||||
});
|
});
|
||||||
|
|
||||||
GUI.timeout_add('button_reset', function () {
|
helper.timeout.add('button_reset', function () {
|
||||||
GUI.interval_resume('setup_data_pull');
|
helper.interval.resume('setup_data_pull');
|
||||||
|
|
||||||
GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibEnded'));
|
GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibEnded'));
|
||||||
|
|
||||||
|
@ -101,7 +102,7 @@ TABS.setup.initialize = function (callback) {
|
||||||
$('#mag_calib_rest').hide();
|
$('#mag_calib_rest').hide();
|
||||||
});
|
});
|
||||||
|
|
||||||
GUI.timeout_add('button_reset', function () {
|
helper.timeout.add('button_reset', function () {
|
||||||
GUI.log(chrome.i18n.getMessage('initialSetupMagCalibEnded'));
|
GUI.log(chrome.i18n.getMessage('initialSetupMagCalibEnded'));
|
||||||
self.removeClass('calibrating');
|
self.removeClass('calibrating');
|
||||||
$('#mag_calib_running').hide();
|
$('#mag_calib_running').hide();
|
||||||
|
@ -206,8 +207,8 @@ TABS.setup.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
GUI.interval_add('setup_data_pull_fast', get_fast_data, 33, true); // 30 fps
|
helper.interval.add('setup_data_pull_fast', get_fast_data, 33, true); // 30 fps
|
||||||
GUI.interval_add('setup_data_pull_slow', get_slow_data, 250, true); // 4 fps
|
helper.interval.add('setup_data_pull_slow', get_slow_data, 250, true); // 4 fps
|
||||||
|
|
||||||
function updateArminFailure() {
|
function updateArminFailure() {
|
||||||
var flagNames = FC.getArmingFlags();
|
var flagNames = FC.getArmingFlags();
|
||||||
|
@ -226,7 +227,7 @@ TABS.setup.initialize = function (callback) {
|
||||||
/*
|
/*
|
||||||
* 1fps update rate will be fully enough
|
* 1fps update rate will be fully enough
|
||||||
*/
|
*/
|
||||||
GUI.interval_add('updateArminFailure', updateArminFailure, 500, true);
|
helper.interval.add('updateArminFailure', updateArminFailure, 500, true);
|
||||||
|
|
||||||
GUI.content_ready(callback);
|
GUI.content_ready(callback);
|
||||||
}
|
}
|
||||||
|
|
|
@ -92,7 +92,7 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function status_pull() {
|
helper.interval.add('status_pull', function status_pull() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue