prevent re-sending analytics appview on tab re-initialization, add 1500ms delay on configuration save & reboot

10.3.x-maintenance
cTn 2014-10-01 13:16:22 +02:00
parent 5cd042ae9d
commit f9ff34fb8b
13 changed files with 59 additions and 33 deletions

View File

@ -5,8 +5,10 @@ TABS.auxiliary_configuration = {};
TABS.auxiliary_configuration.initialize = function (callback) {
var self = this;
GUI.active_tab = 'auxiliary_configuration';
googleAnalytics.sendAppView('Auxiliary Configuration');
if (GUI.active_tab != 'auxiliary_configuration') {
GUI.active_tab = 'auxiliary_configuration';
googleAnalytics.sendAppView('Auxiliary Configuration');
}
function get_box_data() {
MSP.send_message(MSP_codes.MSP_BOX, false, false, get_box_ids);

View File

@ -8,8 +8,10 @@ TABS.cli = {
TABS.cli.initialize = function (callback) {
var self = this;
GUI.active_tab = 'cli';
googleAnalytics.sendAppView('CLI Page');
if (GUI.active_tab != 'cli') {
GUI.active_tab = 'cli';
googleAnalytics.sendAppView('CLI Page');
}
$('#content').load("./tabs/cli.html", function () {
// translate to user-selected language
@ -178,7 +180,7 @@ TABS.cli.cleanup = function (callback) {
// (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 could probably implement this someday
GUI.timeout_add('waiting_for_bootup', function () {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
CONFIGURATOR.cliActive = false;
CONFIGURATOR.cliValid = false;

View File

@ -5,9 +5,10 @@ TABS.configuration = {};
TABS.configuration.initialize = function (callback) {
var self = this;
GUI.active_tab = 'configuration';
googleAnalytics.sendAppView('Configuration');
if (GUI.active_tab != 'configuration') {
GUI.active_tab = 'configuration';
googleAnalytics.sendAppView('Configuration');
}
function check_compatibility() {
if (bit_check(CONFIG.capability, 30)) {
@ -283,10 +284,12 @@ TABS.configuration.initialize = function (callback) {
function reinitialize() {
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () {
GUI.log(chrome.i18n.getMessage('deviceReady'));
TABS.configuration.initialize();
});
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () {
GUI.log(chrome.i18n.getMessage('deviceReady'));
TABS.configuration.initialize();
});
}, 1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
}
MSP.send_message(MSP_codes.MSP_SET_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CONFIG), false, save_misc);

View File

@ -4,8 +4,10 @@ TABS.firmware_flasher = {};
TABS.firmware_flasher.initialize = function (callback) {
var self = this;
GUI.active_tab = 'firmware_flasher';
googleAnalytics.sendAppView('Firmware Flasher');
if (GUI.active_tab != 'firmware_flasher') {
GUI.active_tab = 'firmware_flasher';
googleAnalytics.sendAppView('Firmware Flasher');
}
var intel_hex = false, // standard intel hex in string format
parsed_hex = false; // parsed raw hex in array format

View File

@ -4,8 +4,10 @@ TABS.gps = {};
TABS.gps.initialize = function (callback) {
var self = this;
GUI.active_tab = 'gps';
googleAnalytics.sendAppView('GPS Page');
if (GUI.active_tab != 'gps') {
GUI.active_tab = 'gps';
googleAnalytics.sendAppView('GPS Page');
}
function load_html() {
$('#content').load("./tabs/gps.html", process_html);

View File

@ -4,8 +4,10 @@ TABS.landing = {};
TABS.landing.initialize = function (callback) {
var self = this;
GUI.active_tab = 'landing';
googleAnalytics.sendAppView('Landing Page');
if (GUI.active_tab != 'landing') {
GUI.active_tab = 'landing';
googleAnalytics.sendAppView('Landing Page');
}
$('#content').load("./tabs/landing.html", function () {
//check_usb_permissions(); // temporary enabled in dev branch, should be commented out untill DFU support goes live

View File

@ -4,8 +4,10 @@ TABS.logging = {};
TABS.logging.initialize = function (callback) {
var self = this;
GUI.active_tab = 'logging';
googleAnalytics.sendAppView('Logging');
if (GUI.active_tab != 'logging') {
GUI.active_tab = 'logging';
googleAnalytics.sendAppView('Logging');
}
var requested_properties = [],
samples = 0,

View File

@ -4,8 +4,10 @@ TABS.motor_outputs = {};
TABS.motor_outputs.initialize = function (callback) {
var self = this;
GUI.active_tab = 'motor_outputs';
googleAnalytics.sendAppView('Motor Outputs Page');
if (GUI.active_tab != 'motor_outputs') {
GUI.active_tab = 'motor_outputs';
googleAnalytics.sendAppView('Motor Outputs Page');
}
function get_motor_data() {
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html);

View File

@ -4,8 +4,10 @@ TABS.pid_tuning = {};
TABS.pid_tuning.initialize = function (callback) {
var self = this;
GUI.active_tab = 'pid_tuning';
googleAnalytics.sendAppView('PID Tuning');
if (GUI.active_tab != 'pid_tuning') {
GUI.active_tab = 'pid_tuning';
googleAnalytics.sendAppView('PID Tuning');
}
function get_pid_names() {
MSP.send_message(MSP_codes.MSP_PIDNAMES, false, false, get_pid_data);

View File

@ -4,9 +4,10 @@ TABS.receiver = {};
TABS.receiver.initialize = function (callback) {
var self = this;
GUI.active_tab = 'receiver';
googleAnalytics.sendAppView('Receiver Page');
if (GUI.active_tab != 'receiver') {
GUI.active_tab = 'receiver';
googleAnalytics.sendAppView('Receiver Page');
}
function get_misc_data() {
MSP.send_message(MSP_codes.MSP_MISC, false, false, get_rc_data);

View File

@ -4,8 +4,10 @@ TABS.sensors = {};
TABS.sensors.initialize = function (callback) {
var self = this;
GUI.active_tab = 'sensors';
googleAnalytics.sendAppView('Sensor Page');
if (GUI.active_tab != 'sensors') {
GUI.active_tab = 'sensors';
googleAnalytics.sendAppView('Sensor Page');
}
function initSensorData(){
for (var i = 0; i < 3; i++) {

View File

@ -10,8 +10,10 @@ TABS.servos = {};
TABS.servos.initialize = function (callback) {
var self = this;
GUI.active_tab = 'servos';
googleAnalytics.sendAppView('Servos');
if (GUI.active_tab != 'servos') {
GUI.active_tab = 'servos';
googleAnalytics.sendAppView('Servos');
}
function get_servo_conf_data() {
MSP.send_message(MSP_codes.MSP_SERVO_CONF, false, false, get_boxnames_data);

View File

@ -7,8 +7,10 @@ TABS.setup = {
TABS.setup.initialize = function (callback) {
var self = this;
GUI.active_tab = 'setup';
googleAnalytics.sendAppView('Setup');
if (GUI.active_tab != 'setup') {
GUI.active_tab = 'setup';
googleAnalytics.sendAppView('Setup');
}
function load_ident() {
MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_config);