diff --git a/_locales/en/messages.json b/_locales/en/messages.json index f202d4b30a..c9e9ef72d6 100644 --- a/_locales/en/messages.json +++ b/_locales/en/messages.json @@ -51,7 +51,7 @@ "message": "GPS" }, "tab7": { - "message": "Motor/Servo Outputs" + "message": "Motor Testing" }, "tab8": { "message": "Raw Sensor Data" @@ -108,16 +108,35 @@ "statusbar_packet_error": { "message": "Packet error:" }, + "statusbar_i2c_error": { + "message": "I2C error:" + }, "statusbar_cycle_time": { "message": "Cycle Time:" }, + "please_grant_usb_permissions": { + "message": "Please click on \"Request Optional Permissions\" button to grant application required USB access" + }, + "usb_permissions_granted": { + "message": "Optional USB permissions granted" + }, + "eeprom_saved_ok": { "message": "EEPROM saved" }, + "default_optional_permissions_head": { + "message": "Optional USB Permissions" + }, + "default_optional_permissions_text": { + "message": "Due to addition of Naze32PRO to the supported hardware family, Configurator requires USB access to allow firmware flashing via DFU" + }, + "default_request_optional_permissions": { + "message": "Request Optional Permissions" + }, "defaultWelcomeText": { - "message": "This application is a configuration utility for cleanflight, a 32 bit fork of the popular open source RC flight control firmware project MultiWii.

Application supports hardware that run cleanflight exclusively (acro naze, naze, afromini, flip32, flip32+, chebuzz f3, stm32f3discovery, naze32pro, etc)

The firmware source code can be downloaded from here
The newest binary firmware image is available here
" + "message": "This application is a configuration utility for cleanflight, a 32 bit fork of the popular open source RC flight control firmware project MultiWii.

Application supports hardware that run cleanflight (acro naze, naze, afromini, flip32, flip32+, chebuzz f3, stm32f3discovery, naze32pro, etc)

The firmware source code can be downloaded from here
The newest binary firmware image is available here

Latest CP210x Drivers can be downloaded from here
" }, "defaultChangelogHead": { "message": "Configurator - Changelog" @@ -428,9 +447,6 @@ "message": "Signal Strength" }, - "motorsBarInfo": { - "message": "Bars on the left are representing raw PWM signal for ESCs.
Bars on the right are representing raw PWM signal for Servos.
" - }, "motorsMaster": { "message": "Master" }, @@ -464,9 +480,6 @@ "loggingLogSize": { "message": "Log Size:" }, - "loggingKB": { - "message": "$1 kB" - }, "loggingButtonLogFile": { "message": "Select Log File" }, @@ -476,6 +489,12 @@ "loggingStop": { "message": "Stop Logging" }, + "loggingBack": { + "message": "Leave Logging / Disconnect" + }, + "loggingErrorNotConnected": { + "message": "You need to connect first" + }, "loggingErrorLogFile": { "message": "Please select log file" }, @@ -499,7 +518,7 @@ "message": "Progress:" }, "firmwareFlasherNote": { - "message": "If you are flashing board with baseflight already flashed (updating), leave this checkbox unchecked.
If you are flashing \"bare\" board with no firmware preloaded or you have bootloader pins shorted, check this box.
" + "message": "If you are flashing board with bootloader pins shorted/connected, check No reboot sequence.
If you want configuration data to be wiped, check Full Chip Erase
" }, "firmwareFlasherNoReboot": { "message": "No reboot sequence" @@ -543,8 +562,8 @@ "firmwareFlasherFirmwareNotLoaded": { "message": "Firmware not loaded" }, - "firmwareFlasherFirmwareLoaded": { - "message": "Firmware loaded, ready for flashing" + "firmwareFlasherLocalFirmwareLoaded": { + "message": "Local Firmware loaded, ready for flashing" }, "firmwareFlasherHexCorrupted": { "message": "HEX file appears to be corrupted" diff --git a/background.js b/background.js index cc73727ec2..a4c7bbdf93 100644 --- a/background.js +++ b/background.js @@ -1,12 +1,8 @@ /* - resizable: false - Keep in mind this only disables the side/corner resizing via mouse, nothing more - maxWidth / maxHeight - is defined to prevent application reaching maximized state through window manager - - We are setting Bounds through setBounds method after window was created because on linux setting Bounds as - window.create property seemed to fail, probably because "previous" bounds was used instead according to docs. - - bounds - Size and position of the content in the window (excluding the titlebar). If an id is also specified and a window with a matching id has been shown before, the remembered bounds of the window will be used instead. + + Size calculation for innerBounds seems to be faulty, app was designed for 960x625, using arbitrary values to make innerBounds happy for now + arbitrary values do match the windows ui, how it will affect other OSs is currently unknown */ function start_app() { chrome.app.window.create('main.html', { @@ -19,6 +15,62 @@ function start_app() { // 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 mincommand = app_window.MISC.mincommand; + + if (connectionId > 0 && valid_connection) { + // code below is handmade MSP message (without pretty JS wrapper), it behaves exactly like MSP.send_message + // reset motors to default (mincommand) + var bufferOut = new ArrayBuffer(22); + var bufView = new Uint8Array(bufferOut); + var checksum = 0; + + bufView[0] = 36; // $ + bufView[1] = 77; // M + bufView[2] = 60; // < + bufView[3] = 16; // data length + bufView[4] = 214; // MSP_SET_MOTOR + + checksum = bufView[3] ^ bufView[4]; + + for (var i = 0; i < 16; i += 2) { + bufView[i + 5] = mincommand & 0x00FF; + bufView[i + 6] = mincommand >> 8; + + checksum ^= bufView[i + 5]; + checksum ^= bufView[i + 6]; + } + + bufView[5 + 16] = checksum; + + 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) { + console.log('SERIAL: Connection closed - ' + result); + }); + } + }); + }); + + /* code belowis chrome 36+ ready, till this is enforced in manifest we have to use the old version + chrome.app.window.create('main.html', { + id: 'main-window', + frame: 'chrome', + innerBounds: { + minWidth: 974, + minHeight: 632 + } + }, 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; @@ -29,6 +81,7 @@ function start_app() { } }); }); + */ } chrome.app.runtime.onLaunched.addListener(function() { diff --git a/changelog.html b/changelog.html index 91ed65cb67..e54197ecdf 100644 --- a/changelog.html +++ b/changelog.html @@ -1,3 +1,34 @@ +07.06.2014 +

+ - Servos tab updated to support Cleanflight's cleaner implementation of channel forwarding
+

+07.04.2014 - 0.45 +

+ - Configurator reached 5000+ users on 07.03.2014
+ - Updated various text notes to make things clearer
+ - UI polish
+ - Various bugfixes
+

+06.27.2014 - 0.44 +

+ - Added more scale factors in the motor testing tab
+ - If application closes without disconnecting motors should spin down
+ - Bugfixes for CLI, Motor Testing & Logging tabs
+

+06.26.2014 - 0.43 +

+ - Experimental passthrough support for logging
+ - MSP_ANALOG support for logging
+ - Allow running motors (testing) while monitoring sensors
+ - Major UI changes in Motor Testing tab
+ - Tiny cosmetic changes
+ - Initial set of UI bugfixes for Chrome 36+
+

+06.16.2014 - 0.42 +

+ - Added I2C Error indicator to status bar
+ - Optimizations & bugfixes
+

06.01.2014 - 0.41

- Configurator reached 4000+ users on 05.29.2014
diff --git a/js/data_storage.js b/js/data_storage.js index 3af5498ac1..d97b743f93 100644 --- a/js/data_storage.js +++ b/js/data_storage.js @@ -38,20 +38,18 @@ var RC_tuning = { throttle_EXPO: 0, }; -var AUX_CONFIG = new Array(); -var AUX_CONFIG_values = new Array(); +var AUX_CONFIG = []; +var AUX_CONFIG_values = []; -var SERVO_CONFIG = new Array(); +var SERVO_CONFIG = []; var SENSOR_DATA = { gyroscope: [0, 0, 0], accelerometer: [0, 0, 0], magnetometer: [0, 0, 0], altitude: 0, - kinematicsX: 0.0, - kinematicsY: 0.0, - kinematicsZ: 0.0, - debug: [0, 0, 0, 0] + kinematics: [0.0, 0.0, 0.0], + debug: [0, 0, 0, 0] }; var MOTOR_DATA = new Array(8); @@ -70,10 +68,10 @@ var GPS_DATA = { update: 0, // baseflight specific gps stuff - chn: new Array(), - svid: new Array(), - quality: new Array(), - cno: new Array() + chn: [], + svid: [], + quality: [], + cno: [] }; var ANALOG = { diff --git a/js/gui.js b/js/gui.js index 0933c3e6db..52b927c44a 100644 --- a/js/gui.js +++ b/js/gui.js @@ -4,6 +4,7 @@ var GUI_control = function() { this.connected_to = false; this.active_tab; this.operating_system; + this.optional_usb_permissions = false; // controlled by usb permissions code this.interval_array = []; this.timeout_array = []; @@ -226,38 +227,9 @@ GUI_control.prototype.tab_switch_cleanup = function(callback) { if (callback) callback(); break; case 'motor_outputs': - GUI.interval_remove('motor_pull'); - GUI.interval_remove('status_pull'); + GUI.interval_kill_all(); - // only enforce mincommand if necessary - if (MOTOR_DATA != undefined) { - var update = false; - - for (var i = 0; i < MOTOR_DATA.length; i++) { - if (MOTOR_DATA[i] > MISC.mincommand) { - update = true; - break; - } - } - - if (update) { - // send data to mcu - var buffer_out = []; - - for (var i = 0; i < 8; i++) { - buffer_out.push(lowByte(MISC.mincommand)); - buffer_out.push(highByte(MISC.mincommand)); - } - - MSP.send_message(MSP_codes.MSP_SET_MOTOR, buffer_out, false, function() { - if (callback) callback(); - }); - } else { - if (callback) callback(); - } - } else { - if (callback) callback(); - } + if (callback) callback(); break; case 'sensors': GUI.interval_kill_all(); @@ -292,7 +264,11 @@ GUI_control.prototype.tab_switch_cleanup = function(callback) { }, 5000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one }); break; + case 'logging': + GUI.interval_kill_all(); + if (callback) callback(); + break; case 'firmware_flasher': // this.interval_remove('factory_mode'); PortHandler.flush_callbacks(); @@ -302,7 +278,6 @@ GUI_control.prototype.tab_switch_cleanup = function(callback) { if (callback) callback(); break; - default: if (callback) callback(); } diff --git a/js/msp.js b/js/msp.js index e477e344f9..7f90b10de4 100644 --- a/js/msp.js +++ b/js/msp.js @@ -175,6 +175,7 @@ MSP.process_data = function(code, message_buffer, message_length) { CONFIG.profile = data.getUint8(10); sensor_status(CONFIG.activeSensors); + $('span.i2c-error').text(CONFIG.i2cError); $('span.cycle-time').text(CONFIG.cycleTime); break; case MSP_codes.MSP_RAW_IMU: @@ -232,9 +233,9 @@ MSP.process_data = function(code, message_buffer, message_length) { GPS_DATA.update = data.getUint8(4); break; case MSP_codes.MSP_ATTITUDE: - SENSOR_DATA.kinematicsX = data.getInt16(0, 1) / 10.0; - SENSOR_DATA.kinematicsY = data.getInt16(2, 1) / 10.0; - SENSOR_DATA.kinematicsZ = data.getInt16(4, 1); + SENSOR_DATA.kinematics[0] = data.getInt16(0, 1) / 10.0; // x + SENSOR_DATA.kinematics[1] = data.getInt16(2, 1) / 10.0; // y + SENSOR_DATA.kinematics[2] = data.getInt16(4, 1); // z break; case MSP_codes.MSP_ALTITUDE: SENSOR_DATA.altitude = parseFloat((data.getInt32(0, 1) / 100.0).toFixed(2)); // correct scale factor @@ -285,8 +286,7 @@ MSP.process_data = function(code, message_buffer, message_length) { } break; case MSP_codes.MSP_BOX: - // dump previous data (if there was any) - AUX_CONFIG_values = new Array(); + AUX_CONFIG_values = []; // empty the array as new data is coming in var boxItems = data.byteLength / 2; // AUX 1-4, 2 bytes per boxItem if (bit_check(CONFIG.capability, 5)) { @@ -359,8 +359,7 @@ MSP.process_data = function(code, message_buffer, message_length) { console.log(data); break; case MSP_codes.MSP_SERVO_CONF: - // drop previous data - SERVO_CONFIG = []; + SERVO_CONFIG = []; // empty the array as new data is coming in for (var i = 0; i < 56; i += 7) { var arr = { diff --git a/js/port_handler.js b/js/port_handler.js index e1efa5ce8d..f685b203eb 100644 --- a/js/port_handler.js +++ b/js/port_handler.js @@ -65,7 +65,7 @@ port_handler.prototype.check = function() { if (port == result.last_used_port) { console.log('Selecting last used port: ' + result.last_used_port); - $('div#port-picker .port select').val(result.last_used_port); + $('div#port-picker #port').val(result.last_used_port); } }); } else { @@ -98,9 +98,9 @@ port_handler.prototype.check = function() { // select / highlight new port, if connected -> select connected port if (!GUI.connected_to) { - $('div#port-picker .port select').val(new_ports[0]); + $('div#port-picker #port').val(new_ports[0]); } else { - $('div#port-picker .port select').val(GUI.connected_to); + $('div#port-picker #port').val(GUI.connected_to); } // start connect procedure (if statement is valid) @@ -131,21 +131,40 @@ port_handler.prototype.check = function() { self.initial_ports = current_ports; } + if (GUI.optional_usb_permissions) { + check_usb_devices(); + } + self.main_timeout_reference = setTimeout(function() { self.check(); }, 250); }); + + function check_usb_devices() { + chrome.usb.getDevices(usbDevices.STM32DFU, function(result) { + if (result.length) { + if (!$("div#port-picker #port [value='DFU']").length) { + $('div#port-picker #port').append(''); + $('div#port-picker #port').val('DFU'); + } + } else { + if ($("div#port-picker #port [value='DFU']").length) { + $("div#port-picker #port [value='DFU']").remove(); + } + } + }); + } }; port_handler.prototype.update_port_select = function(ports) { - $('div#port-picker .port select').html(''); // drop previous one + $('div#port-picker #port').html(''); // drop previous one if (ports.length > 0) { for (var i = 0; i < ports.length; i++) { - $('div#port-picker .port select').append($("

0
+
+ 0 +
0
diff --git a/main.js b/main.js index 37af0a8a42..7ddad3bdef 100644 --- a/main.js +++ b/main.js @@ -46,18 +46,17 @@ $(document).ready(function() { break; } - GUI.log('Are you using ESCs with SimonK firmware? Try RapidFlash, our new utility for configuring / flashing / updating firmware.'); - // Tabs var tabs = $('#tabs > ul'); $('a', tabs).click(function() { if ($(this).parent().hasClass('active') == false) { // only initialize when the tab isn't already active var self = this; var index = $(self).parent().index(); + var tab = $(self).parent().prop('class'); // if there is no active connection, return - if (configuration_received == false) { - GUI.log('You need to connect before you can view any of the tabs', 'red'); + if (!configuration_received && tab != 'tab_logging') { + GUI.log('You need to connect before you can view any of the tabs'); return; } @@ -65,9 +64,6 @@ $(document).ready(function() { // disable previously active tab highlight $('li', tabs).removeClass('active'); - // get tab class name (there should be only one class listed) - var tab = $(self).parent().prop('class'); - // Highlight selected tab $(self).parent().addClass('active'); @@ -174,7 +170,7 @@ $(document).ready(function() { $("#content").on('keydown', 'input[type="number"]', function(e) { // whitelist all that we need for numeric control if ((e.keyCode >= 96 && e.keyCode <= 105) || (e.keyCode >= 48 && e.keyCode <= 57)) { // allow numpad and standard number keypad - } else if(e.keyCode == 109 || e.keyCode == 189) { // minus on numpad and in standard keyboard + } else if (e.keyCode == 109 || e.keyCode == 189) { // minus on numpad and in standard keyboard } else if (e.keyCode == 8 || e.keyCode == 46) { // backspace and delete } else if (e.keyCode == 190 || e.keyCode == 110) { // allow and decimal point } else if ((e.keyCode >= 37 && e.keyCode <= 40) || e.keyCode == 13) { // allow arrows, enter @@ -238,6 +234,13 @@ function millitime() { return now; } +function bytesToSize(bytes) { + if (bytes < 1024) return bytes + ' Bytes'; + else if (bytes < 1048576) return(bytes / 1024).toFixed(3) + ' KB'; + else if (bytes < 1073741824) return(bytes / 1048576).toFixed(3) + ' MB'; + else return (bytes / 1073741824).toFixed(3) + ' GB'; +} + /* function add_custom_spinners() { var spinner_element = '
'; diff --git a/manifest.json b/manifest.json index 450a346200..5b1c059ae0 100644 --- a/manifest.json +++ b/manifest.json @@ -1,7 +1,7 @@ { "manifest_version": 2, "minimum_chrome_version": "33", - "version": "0.41", + "version": "0.45", "author": "Hydra", "name": "Cleanflight - Configurator", @@ -23,6 +23,7 @@ "https://*.github.com/", "https://*.githubusercontent.com/", "serial", + "usb", "storage", "fileSystem", "fileSystem.write", @@ -30,6 +31,12 @@ "notifications" ], + "optional_permissions": [ + {"usbDevices": [ + {"vendorId": 1155, "productId": 57105} + ]} + ], + "icons": { "128": "images/icon_128.png" } diff --git a/tabs/auxiliary_configuration.css b/tabs/auxiliary_configuration.css index f888318676..3a8a3c916f 100644 --- a/tabs/auxiliary_configuration.css +++ b/tabs/auxiliary_configuration.css @@ -40,12 +40,16 @@ border: 0; background-color: white; } + .tab-auxiliary_configuration .buttons { + width: calc(100% - 20px); + + position: absolute; + bottom: 10px; + } .tab-auxiliary_configuration .update { display: block; float: right; - margin-top: 10px; - height: 28px; line-height: 28px; @@ -59,7 +63,4 @@ } .tab-auxiliary_configuration .update:hover { background-color: #dedcdc; - } - .tab-auxiliary_configuration .update.success { - border: 1px solid #43c84d; } \ No newline at end of file diff --git a/tabs/auxiliary_configuration.html b/tabs/auxiliary_configuration.html index c013472c24..2ef7ddba21 100644 --- a/tabs/auxiliary_configuration.html +++ b/tabs/auxiliary_configuration.html @@ -2,42 +2,12 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
AUX 1AUX 2AUX 3AUX 4AUX 5AUX 6AUX 7AUX 8
- +
+ +
\ No newline at end of file diff --git a/tabs/auxiliary_configuration.js b/tabs/auxiliary_configuration.js index fda4045dc0..ca6d51bb81 100644 --- a/tabs/auxiliary_configuration.js +++ b/tabs/auxiliary_configuration.js @@ -1,3 +1,4 @@ +// TODO: rework box_highlight & update_ui to accept flexible amount of aux channels function tab_initialize_auxiliary_configuration() { ga_tracker.sendAppView('Auxiliary Configuration'); GUI.active_tab = 'auxiliary_configuration'; @@ -5,7 +6,11 @@ function tab_initialize_auxiliary_configuration() { MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data); function get_box_data() { - MSP.send_message(MSP_codes.MSP_BOX, false, false, load_html); + MSP.send_message(MSP_codes.MSP_BOX, false, false, get_rc_data); + } + + function get_rc_data() { + MSP.send_message(MSP_codes.MSP_RC, false, false, load_html); } function load_html() { @@ -13,71 +18,48 @@ function tab_initialize_auxiliary_configuration() { } function process_html() { + // generate heads according to RC count + var table_head = $('table.boxes .heads'); + var main_head = $('table.boxes .main'); + for (var i = 0; i < (RC.active_channels - 4); i++) { + table_head.append('AUX ' + (i + 1) + ''); + + // 3 columns per aux channel (this might be requested to change to 6 in the future, so watch out) + main_head.append('\ + \ + \ + \ + '); + } + // translate to user-selected language localize(); - function box_check(num, pos) { - if (bit_check(num, pos)) { // 1 - return ''; - } else { // 0 - return ''; - } - } - - // val = channel value - // aux_num = position of corresponding aux channel in the html table - function box_highlight(val, aux_num) { - var tr = $('table.boxes .switches'); - var pos = 0; // < 1300 - - if (val > 1300 && val < 1700) { - pos = 1; - } else if (val > 1700) { - pos = 2; - } - - $('td:nth-child(' + aux_num + '), td:nth-child(' + (aux_num + 1) + '), td:nth-child(' + (aux_num + 2) + ')', tr).css('background-color', 'transparent'); - $('td:nth-child(' + (aux_num + pos) + ')', tr).css('background-color', 'orange'); - } - // generate table from the supplied AUX names and AUX data for (var i = 0; i < AUX_CONFIG.length; i++) { - $('.boxes > tbody:last').append( - '' + - '' + AUX_CONFIG[i] + '' + - box_check(AUX_CONFIG_values[i], 0) + - box_check(AUX_CONFIG_values[i], 1) + - box_check(AUX_CONFIG_values[i], 2) + + var line = ''; + line += '' + AUX_CONFIG[i] + ''; - box_check(AUX_CONFIG_values[i], 3) + - box_check(AUX_CONFIG_values[i], 4) + - box_check(AUX_CONFIG_values[i], 5) + + var bitIndex = 0; + var chunks = 1; + if (bit_check(CONFIG.capability, 5)) { + chunks = 2; + } + var channelsPerChunk = 4; + for (var chunk = 0; chunk < chunks; chunk++) { + for (var j = 0; j < channelsPerChunk * 3; j++) { + if (bit_check(AUX_CONFIG_values[i], bitIndex++)) { + line += ''; + } else { + line += ''; + } + } + bitIndex += 16 - (4 * 3); + } + + line += ''; - box_check(AUX_CONFIG_values[i], 6) + - box_check(AUX_CONFIG_values[i], 7) + - box_check(AUX_CONFIG_values[i], 8) + - - box_check(AUX_CONFIG_values[i], 9) + - box_check(AUX_CONFIG_values[i], 10) + - box_check(AUX_CONFIG_values[i], 11) + - - box_check(AUX_CONFIG_values[i], 16) + - box_check(AUX_CONFIG_values[i], 17) + - box_check(AUX_CONFIG_values[i], 18) + - - box_check(AUX_CONFIG_values[i], 19) + - box_check(AUX_CONFIG_values[i], 20) + - box_check(AUX_CONFIG_values[i], 21) + - - box_check(AUX_CONFIG_values[i], 22) + - box_check(AUX_CONFIG_values[i], 23) + - box_check(AUX_CONFIG_values[i], 24) + - - box_check(AUX_CONFIG_values[i], 25) + - box_check(AUX_CONFIG_values[i], 26) + - box_check(AUX_CONFIG_values[i], 27) + - '' - ); + $('.boxes > tbody:last').append(line); } // UI Hooks @@ -112,18 +94,17 @@ function tab_initialize_auxiliary_configuration() { } }); - // send over the data - var AUX_val_buffer_out = new Array(); - - var needle = 0; + // send over data + // current code will only handle 4 AUX as the variable length is 16bits + var AUX_val_buffer_out = []; for (var i = 0; i < AUX_CONFIG_values.length; i++) { - AUX_val_buffer_out[needle++] = lowByte(AUX_CONFIG_values[i] & 0xFFF); - AUX_val_buffer_out[needle++] = highByte(AUX_CONFIG_values[i] & 0xFFF); + AUX_val_buffer_out.push(lowByte(AUX_CONFIG_values[i] & 0xFFF)); + AUX_val_buffer_out.push(highByte(AUX_CONFIG_values[i] & 0xFFF)); } if (bit_check(CONFIG.capability, 5)) { for (var i = 0; i < AUX_CONFIG_values.length; i++) { - AUX_val_buffer_out[needle++] = lowByte((AUX_CONFIG_values[i] >> 16) & 0xFFF); - AUX_val_buffer_out[needle++] = highByte((AUX_CONFIG_values[i] >> 16) & 0xFFF); + AUX_val_buffer_out.push(lowByte((AUX_CONFIG_values[i] >> 16) & 0xFFF)); + AUX_val_buffer_out.push(highByte((AUX_CONFIG_values[i] >> 16) & 0xFFF)); } } @@ -132,17 +113,29 @@ function tab_initialize_auxiliary_configuration() { function save_to_eeprom() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('auxiliaryEepromSaved')); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); }); } }); + // val = channel value + // aux_num = position of corresponding aux channel in the html table + var switches_e = $('table.boxes .switches'); + function box_highlight(aux_num, val) { + var pos = 0; // < 1300 + + if (val > 1300 && val < 1700) { + pos = 1; + } else if (val > 1700) { + pos = 2; + } + + var highlight_column = (aux_num * 3) + pos + 2; // +2 to skip name column and index starting on 1 instead of 0 + var erase_columns = (aux_num * 3) + 2; + + $('td:nth-child(n+' + erase_columns + '):nth-child(-n+' + (erase_columns + 2) + ')', switches_e).css('background-color', 'transparent'); + $('td:nth-child(' + highlight_column + ')', switches_e).css('background-color', 'orange'); + } + // data pulling functions used inside interval timer function get_rc_data() { MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); @@ -159,22 +152,19 @@ function tab_initialize_auxiliary_configuration() { $('td.name').eq(i).addClass('off'); } } + } - box_highlight(RC.channels[4], 2); // aux 1 - box_highlight(RC.channels[5], 5); // aux 2 - box_highlight(RC.channels[6], 8); // aux 3 - box_highlight(RC.channels[7], 11); // aux 4 - if (RC.active_channels > 8) { - box_highlight(RC.channels[8], 14); // aux 5 - box_highlight(RC.channels[9], 17); // aux 6 - box_highlight(RC.channels[10], 20); // aux 7 - box_highlight(RC.channels[11], 23); // aux 8 - } + for (var i = 0; i < (RC.active_channels - 4); i++) { + box_highlight(i, RC.channels[i + 4]); + } } + // update ui instantly on first load + update_ui(); + // enable data pulling - GUI.interval_add('aux_data_pull', get_rc_data, 50, true); + GUI.interval_add('aux_data_pull', get_rc_data, 50); // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function() { diff --git a/tabs/cli.js b/tabs/cli.js index a58a1c80c7..0b57bf083a 100644 --- a/tabs/cli.js +++ b/tabs/cli.js @@ -1,3 +1,6 @@ +var CLI_active = false; +var CLI_valid = false; + var CliHistory = function () { this.history = []; this.index = 0; diff --git a/tabs/default.css b/tabs/default.css index c4c0add047..d2b096b613 100644 --- a/tabs/default.css +++ b/tabs/default.css @@ -8,6 +8,45 @@ width: calc(40% - 10px); } +.tab-default .optional_permissions { + display: none; + + margin-bottom: 10px; + + border: 1px solid silver; +} + .tab-default .optional_permissions .title { + line-height: 20px; + + text-align: center; + font-weight: bold; + color: white; + + border-bottom: 1px solid silver; + background-color: #cd4c4c; + } + .tab-default .optional_permissions p { + padding: 5px; + } + .tab-default .optional_permissions a { + display: block; + float: left; + + height: 28px; + line-height: 28px; + + margin: 0 0 5px 5px; + padding: 0 15px 0 15px; + + text-align: center; + font-weight: bold; + + border: 1px solid silver; + background-color: #ececec; + } + .tab-default .optional_permissions a:hover { + background-color: #dedcdc; + } .welcome { margin-bottom: 10px; diff --git a/tabs/default.html b/tabs/default.html index edcd98bade..f61d01bc21 100644 --- a/tabs/default.html +++ b/tabs/default.html @@ -1,5 +1,12 @@
+
+
+

+

+ +
+
-
+
@@ -69,8 +69,15 @@
-
+
+ +
+
+
+
+
+
@@ -82,14 +89,9 @@
-
- -
-
-
-
-
-
+
+ +
\ No newline at end of file diff --git a/tabs/initial_setup.js b/tabs/initial_setup.js index cb5ce0d80f..b3e2a6cb9b 100644 --- a/tabs/initial_setup.js +++ b/tabs/initial_setup.js @@ -211,21 +211,14 @@ function tab_initialize_initial_setup() { function save_to_eeprom() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('initialSetupEepromSaved')); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); }); } }); // reset yaw button hook $('div#interactive_block > a.reset').click(function() { - yaw_fix = SENSOR_DATA.kinematicsZ * - 1.0; - console.log("YAW reset to 0"); + yaw_fix = SENSOR_DATA.kinematics[2] * - 1.0; + console.log('YAW reset to 0 deg, fix: ' + yaw_fix + ' deg'); }); $('#content .backup').click(configuration_backup); @@ -251,9 +244,9 @@ function tab_initialize_initial_setup() { // Update cube var cube = $('div#cube'); - cube.css('-webkit-transform', 'rotateY(' + ((SENSOR_DATA.kinematicsZ * -1.0) - yaw_fix) + 'deg)'); - $('#cubePITCH', cube).css('-webkit-transform', 'rotateX(' + SENSOR_DATA.kinematicsY + 'deg)'); - $('#cubeROLL', cube).css('-webkit-transform', 'rotateZ(' + SENSOR_DATA.kinematicsX + 'deg)'); + cube.css('-webkit-transform', 'rotateY(' + ((SENSOR_DATA.kinematics[2] * -1.0) - yaw_fix) + 'deg)'); + $('#cubePITCH', cube).css('-webkit-transform', 'rotateX(' + SENSOR_DATA.kinematics[1] + 'deg)'); + $('#cubeROLL', cube).css('-webkit-transform', 'rotateZ(' + SENSOR_DATA.kinematics[0] + 'deg)'); } GUI.interval_add('initial_setup_data_pull', get_analog_data, 50, true); diff --git a/tabs/logging.css b/tabs/logging.css index d393f8d608..0e752671ea 100644 --- a/tabs/logging.css +++ b/tabs/logging.css @@ -49,13 +49,16 @@ line-height: 20px; } .tab-logging .buttons { - margin-top: 10px; + width: calc(100% - 20px); + + position: absolute; + bottom: 10px; } .tab-logging .buttons a { display: block; - float: left; + float: right; - margin-right: 10px; + margin-left: 10px; height: 28px; line-height: 28px; @@ -71,3 +74,6 @@ .tab-logging .buttons a:hover { background-color: #dedcdc; } + .tab-logging .buttons .back { + display: none; + } \ No newline at end of file diff --git a/tabs/logging.html b/tabs/logging.html index 5b6c715b6c..b5cf7ef0cc 100644 --- a/tabs/logging.html +++ b/tabs/logging.html @@ -7,6 +7,7 @@
3 columns (x, y, z)
one column
7 columns
+
4 columns
8 columns by default
8 columns by default
4 columns
@@ -28,11 +29,12 @@
0
-
0 kB
+
0 Bytes
- + +
\ No newline at end of file diff --git a/tabs/logging.js b/tabs/logging.js index ea453700e3..a0bfd0c424 100644 --- a/tabs/logging.js +++ b/tabs/logging.js @@ -1,16 +1,34 @@ +var MSP_pass_through = false; + function tab_initialize_logging() { ga_tracker.sendAppView('Logging'); GUI.active_tab = 'logging'; var requested_properties = []; - MSP.send_message(MSP_codes.MSP_RC, false, false, get_motor_data); + if (configuration_received) { + MSP.send_message(MSP_codes.MSP_RC, false, false, get_motor_data); - function get_motor_data() { - MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); - } + function get_motor_data() { + MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); + } + + function load_html() { + $('#content').load("./tabs/logging.html", process_html); + } + } else { + MSP_pass_through = true; + + // we will initialize RC.channels array and MOTOR_DATA array manually + RC.active_channels = 8; + for (var i = 0; i < RC.active_channels; i++) { + RC.channels[i] = 0; + } + + for (var i = 0; i < 8; i++) { + MOTOR_DATA[i] = 0; + } - function load_html() { $('#content').load("./tabs/logging.html", process_html); } @@ -22,76 +40,92 @@ function tab_initialize_logging() { $('a.log_file').click(prepare_file); $('a.logging').click(function() { - if (fileEntry != null) { - var clicks = $(this).data('clicks'); + if (GUI.connected_to) { + if (fileEntry != null) { + var clicks = $(this).data('clicks'); - if (!clicks) { - // reset some variables before start - samples = 0; - log_buffer = []; - requested_properties = []; + if (!clicks) { + // reset some variables before start + samples = 0; + requests = 0; + log_buffer = []; + requested_properties = []; - $('.properties input:checked').each(function() { - requested_properties.push($(this).prop('name')); - }); + $('.properties input:checked').each(function() { + requested_properties.push($(this).prop('name')); + }); - if (requested_properties.length) { - // print header for the - print_head(); + if (requested_properties.length) { + // print header for the csv file + print_head(); - function poll_data() { - // save current - crunch_data(); - - // request new - for (var i = 0; i < requested_properties.length; i++) { - MSP.send_message(MSP_codes[requested_properties[i]]); - - /* this approach could be used if we want to utilize request time compensation - if (i < requested_properties.length -1) { - MSP.send_message(requested_properties[i]); - } else { - MSP.send_message(requested_properties[i], false, false, poll_data); + function poll_data() { + if (requests) { + // save current data (only after everything is initialized) + crunch_data(); + } + + // request new + if (!MSP_pass_through) { + for (var i = 0; i < requested_properties.length; i++, requests++) { + MSP.send_message(MSP_codes[requested_properties[i]]); + } } - */ } + + GUI.interval_add('log_data_pull', poll_data, parseInt($('select.speed').val()), true); // refresh rate goes here + GUI.interval_add('flush_data', function() { + if (log_buffer.length) { // only execute when there is actual data to write + if (fileWriter.readyState == 0 || fileWriter.readyState == 2) { + append_to_file(log_buffer.join('\n')); + + $('.samples').text(samples += log_buffer.length); + + log_buffer = []; + } else { + console.log('IO having trouble keeping up with the data flow'); + } + } + }, 1000); + + $('.speed').prop('disabled', true); + $(this).text(chrome.i18n.getMessage('loggingStop')); + $(this).data("clicks", !clicks); + } else { + GUI.log(chrome.i18n.getMessage('loggingErrorOneProperty')); } - - GUI.interval_add('log_data_pull', poll_data, parseInt($('select.speed').val()), true); // refresh rate goes here - GUI.interval_add('flush_data', function() { - if (log_buffer.length) { // only execute when there is actual data to write - if (fileWriter.readyState == 0 || fileWriter.readyState == 2) { - append_to_file(log_buffer.join('\n')); - - $('.samples').text(samples += log_buffer.length); - $('.size').text(chrome.i18n.getMessage('loggingKB', [(fileWriter.length / 1024).toFixed(2)])); - - log_buffer = []; - } else { - console.log('IO having trouble keeping up with the data flow'); - } - } - }, 1000); - - $('.speed').prop('disabled', true); - $(this).text(chrome.i18n.getMessage('loggingStop')); - $(this).data("clicks", !clicks); } else { - GUI.log(chrome.i18n.getMessage('loggingErrorOneProperty')); + GUI.interval_remove('log_data_pull'); + GUI.interval_remove('flush_data'); + + $('.speed').prop('disabled', false); + $(this).text(chrome.i18n.getMessage('loggingStart')); + $(this).data("clicks", !clicks); } } else { - GUI.interval_remove('log_data_pull'); - GUI.interval_remove('flush_data'); - - $('.speed').prop('disabled', false); - $(this).text(chrome.i18n.getMessage('loggingStart')); - $(this).data("clicks", !clicks); + GUI.log(chrome.i18n.getMessage('loggingErrorLogFile')); } } else { - GUI.log(chrome.i18n.getMessage('loggingErrorLogFile')); + GUI.log(chrome.i18n.getMessage('loggingErrorNotConnected')); } }); + if (MSP_pass_through) { + $('a.back').show(); + + $('a.back').click(function() { + if (GUI.connected_to) { + $('a.connect').click(); + } else { + GUI.tab_switch_cleanup(function() { + MSP_pass_through = false; + $('#tabs > ul li').removeClass('active'); + tab_initialize_default(); + }); + } + }); + } + chrome.storage.local.get('logging_file_entry', function(result) { if (result.logging_file_entry) { chrome.fileSystem.restoreEntry(result.logging_file_entry, function(entry) { @@ -102,52 +136,6 @@ function tab_initialize_logging() { }); } - var samples = 0; - var log_buffer = []; - function crunch_data() { - var sample = millitime(); - - for (var i = 0; i < requested_properties.length; i++) { - switch (requested_properties[i]) { - case 'MSP_RAW_IMU': - sample += ',' + SENSOR_DATA.gyroscope; - sample += ',' + SENSOR_DATA.accelerometer; - sample += ',' + SENSOR_DATA.magnetometer; - break; - case 'MSP_ATTITUDE': - sample += ',' + SENSOR_DATA.kinematicsX; - sample += ',' + SENSOR_DATA.kinematicsY; - sample += ',' + SENSOR_DATA.kinematicsZ; - break; - case 'MSP_ALTITUDE': - sample += ',' + SENSOR_DATA.altitude; - break; - case 'MSP_RAW_GPS': - sample += ',' + GPS_DATA.fix; - sample += ',' + GPS_DATA.numSat; - sample += ',' + (GPS_DATA.lat / 10000000); - sample += ',' + (GPS_DATA.lon / 10000000); - sample += ',' + GPS_DATA.alt; - sample += ',' + GPS_DATA.speed; - sample += ',' + GPS_DATA.ground_course; - break; - case 'MSP_RC': - for (var chan = 0; chan < RC.active_channels; chan++) { - sample += ',' + RC.channels[chan]; - } - break; - case 'MSP_MOTOR': - sample += ',' + MOTOR_DATA; - break; - case 'MSP_DEBUG': - sample += ',' + SENSOR_DATA.debug; - break; - } - } - - log_buffer.push(sample); - } - function print_head() { var head = "timestamp"; @@ -183,6 +171,12 @@ function tab_initialize_logging() { head += ',' + 'gpsSpeed'; head += ',' + 'gpsGroundCourse'; break; + case 'MSP_ANALOG': + head += ',' + 'voltage'; + head += ',' + 'amperage'; + head += ',' + 'mAhdrawn'; + head += ',' + 'rssi'; + break; case 'MSP_RC': for (var chan = 0; chan < RC.active_channels; chan++) { head += ',' + 'RC' + chan; @@ -201,7 +195,60 @@ function tab_initialize_logging() { } } - log_buffer.push(head); + append_to_file(head); + } + + var samples = 0; + var requests = 0; + var log_buffer = []; + function crunch_data() { + var sample = millitime(); + + for (var i = 0; i < requested_properties.length; i++) { + switch (requested_properties[i]) { + case 'MSP_RAW_IMU': + sample += ',' + SENSOR_DATA.gyroscope; + sample += ',' + SENSOR_DATA.accelerometer; + sample += ',' + SENSOR_DATA.magnetometer; + break; + case 'MSP_ATTITUDE': + sample += ',' + SENSOR_DATA.kinematics[0]; + sample += ',' + SENSOR_DATA.kinematics[1]; + sample += ',' + SENSOR_DATA.kinematics[2]; + break; + case 'MSP_ALTITUDE': + sample += ',' + SENSOR_DATA.altitude; + break; + case 'MSP_RAW_GPS': + sample += ',' + GPS_DATA.fix; + sample += ',' + GPS_DATA.numSat; + sample += ',' + (GPS_DATA.lat / 10000000); + sample += ',' + (GPS_DATA.lon / 10000000); + sample += ',' + GPS_DATA.alt; + sample += ',' + GPS_DATA.speed; + sample += ',' + GPS_DATA.ground_course; + break; + case 'MSP_ANALOG': + sample += ',' + ANALOG.voltage; + sample += ',' + ANALOG.amperage; + sample += ',' + ANALOG.mAhdrawn; + sample += ',' + ANALOG.rssi; + break; + case 'MSP_RC': + for (var chan = 0; chan < RC.active_channels; chan++) { + sample += ',' + RC.channels[chan]; + } + break; + case 'MSP_MOTOR': + sample += ',' + MOTOR_DATA; + break; + case 'MSP_DEBUG': + sample += ',' + SENSOR_DATA.debug; + break; + } + } + + log_buffer.push(sample); } // IO related methods @@ -233,6 +280,9 @@ function tab_initialize_logging() { // save entry for next use chrome.storage.local.set({'logging_file_entry': chrome.fileSystem.retainEntry(fileEntry)}); + // reset sample counter in UI + $('.samples').text(0); + prepare_writer(); } else { console.log('File appears to be read only, sorry.'); @@ -254,7 +304,7 @@ function tab_initialize_logging() { }; fileWriter.onwriteend = function() { - // console.log('Data written'); + $('.size').text(bytesToSize(fileWriter.length)); }; if (retaining) { @@ -262,6 +312,9 @@ function tab_initialize_logging() { GUI.log(chrome.i18n.getMessage('loggingAutomaticallyRetained', [path])); }); } + + // update log size in UI on fileWriter creation + $('.size').text(bytesToSize(fileWriter.length)); }, function(e) { // File is not readable or does not exist! console.error(e); diff --git a/tabs/motor_outputs.css b/tabs/motor_outputs.css index df065c97c9..af6e383e79 100644 --- a/tabs/motor_outputs.css +++ b/tabs/motor_outputs.css @@ -1,97 +1,190 @@ -.tab-motor_outputs { +.tab-motor_outputs .plot_control { + float: right; + + width: 158px; + + border: 1px solid silver; } - .tab-motor_outputs .left.motors { + .tab-motor_outputs .plot_control .title { + line-height: 20px; + font-weight: bold; + text-align: center; + + border-bottom: 1px solid silver; + background-color: #ececec; + } + .tab-motor_outputs .plot_control .title a:hover { + text-decoration: underline; + } + .tab-motor_outputs .plot_control dl { + padding: 5px 0 0 5px; + line-height: 22px; + } + .tab-motor_outputs .plot_control dt { float: left; - margin-right: 50px; + width: 60px; + height: 22px; + font-weight: bold; + } + .tab-motor_outputs .plot_control dd { + margin-left: 20px; + height: 22px; + } + .tab-motor_outputs .plot_control .x { + color: #00A8F0; + } + .tab-motor_outputs .plot_control .y { + color: #C0D800; + } + .tab-motor_outputs .plot_control .z { + color: #CB4B4B; + } + .tab-motor_outputs .plot_control .x, .tab-motor_outputs .plot_control .y, .tab-motor_outputs .plot_control .z { + text-align: right; + margin-right: 25px; + } +.tab-motor_outputs select { + width: 70px; + border: 1px solid silver; +} +.tab-motor_outputs svg { + float: left; + + width: calc(100% - 168px); /* - (plot control, margin)*/ + height: 140px; + + margin-bottom: 10px; +} +.tab-motor_outputs .grid .tick { + stroke: silver; + stroke-width: 1px; + shape-rendering: crispEdges; +} +.tab-motor_outputs .grid path { + stroke-width: 0; +} +.tab-motor_outputs .data .line { + stroke-width: 2px; + fill: none; +} +.tab-motor_outputs .axis path, .tab-motor_outputs .axis line { + fill: none; + stroke: #000000; + stroke-width: 1px; + shape-rendering: crispEdges; +} +.tab-motor_outputs .line:nth-child(1) { + stroke: #00A8F0; +} +.tab-motor_outputs .line:nth-child(2) { + stroke: #C0D800; +} +.tab-motor_outputs .line:nth-child(3) { + stroke: #CB4B4B; +} + +.tab-motor_outputs .left.motors { + float: left; + + width: calc(50% - 50px); +} +.tab-motor_outputs .right.servos { + float: right; + + width: 50%; +} +.tab-motor_outputs .title { + padding-bottom: 2px; + + text-align: center; + font-weight: bold; +} +.tab-motor_outputs .titles { + height: 20px; +} + .tab-motor_outputs .titles li { + float: left; + + width: calc((100% / 9) - 10px); + margin-right: 10px; + + text-align: center; + } + .tab-motor_outputs .servos .titles li { + float: right; + + width: calc((100% / 8) - 10px); + + margin: 0 0 0 10px; + } + .tab-motor_outputs .titles .active { + color: green; + } +.tab-motor_outputs .m-block { + float: left; + + width: calc((100% / 9) - 12px); + height: 100px; + + margin-right: 10px; + + border: 1px solid silver; + background-color: #e9e9e9; +} +.tab-motor_outputs .servos .m-block { + float: right; + + width: calc((100% / 8) - 12px); + + margin: 0 0 0 10px; +} +.tab-motor_outputs .indicator { + float: left; + + width: 100%; +} +.tab-motor_outputs .motor_testing { + display: none; + margin-top: 15px; +} + .tab-motor_outputs .motor_testing .left { width: calc(50% - 50px); } - .tab-motor_outputs .right.servos { - float: left; + .tab-motor_outputs .motor_testing .sliders input { + -webkit-appearance: slider-vertical; - width: 50%; + width: calc((100% / 9) - 13px); + height: 100px; + + margin-right: 10px; + } + .tab-motor_outputs .motor_testing .sliders input:first-child { + /* margin-left: 2px; */ /* seems to vary depending on chrome version O.o */ + } + .tab-motor_outputs .motor_testing .values { + margin-top: 5px; } - .tab-motor_outputs .titles { - height: 20px; - } - .tab-motor_outputs .titles li { + .tab-motor_outputs .motor_testing .values li { float: left; - width: calc((100% / 9) - 10px); /* - (margin) */ + width: calc((100% / 9) - 10px); margin-right: 10px; text-align: center; } - .tab-motor_outputs .servos .titles li { - width: calc((100% / 8) - 10px); /* - (margin) */ - } - .tab-motor_outputs .titles .active { - color: green; - } - .tab-motor_outputs .m-block { - float: left; + .tab-motor_outputs .motor_testing .notice { + float: right; - width: calc((100% / 9) - 12px); /* - (margin, border) */ - height: 160px; + width: calc(50% - 22px); - margin-right: 10px; - - border: 1px solid silver; - background-color: #e9e9e9; - } - .tab-motor_outputs .servos .m-block { - width: calc((100% / 8) - 12px); /* - (margin, border) */ - } - .tab-motor_outputs .indicator { - float: left; - - width: 100%; - } - .tab-motor_outputs p { - margin-top: 20px; padding: 5px; border: 1px dotted silver; } - .tab-motor_outputs .motor_testing { - display: none; - } - .tab-motor_outputs .motor_testing .left { - margin-right: 50px; + .tab-motor_outputs .motor_testing .notice input[type="checkbox"] { + margin-left: 5px; - width: calc(50% - 50px); - } - .tab-motor_outputs .motor_testing .sliders { - margin-top: 20px; - } - .tab-motor_outputs .motor_testing .sliders input { - -webkit-appearance: slider-vertical; - - width: calc((100% / 9) - 3px); /* - (width / 9 elements, not sure about -3 */ - } - .tab-motor_outputs .motor_testing .values { - margin-top: 5px; - } - .tab-motor_outputs .motor_testing .values li { - float: left; - - width: calc((100% / 9)); - - text-align: center; - } - .tab-motor_outputs .motor_testing .notice { - float: left; - - width: calc(50% - 12px); /* - (padding, border) */ - - margin-top: 20px; - padding: 5px; - - border: 1px dotted silver; - } - .tab-motor_outputs .motor_testing .notice input[type="checkbox"] { - margin-left: 5px; - - vertical-align: middle; - } \ No newline at end of file + vertical-align: middle; + } \ No newline at end of file diff --git a/tabs/motor_outputs.html b/tabs/motor_outputs.html index f6e1e70da1..280f407695 100644 --- a/tabs/motor_outputs.html +++ b/tabs/motor_outputs.html @@ -1,14 +1,60 @@
+
+
+
Accelerometer - [Reset]
+
+
+
+ +
+
+
+ +
+
X:
0
+
Y:
0
+
Z:
0
+
+
+ + + + + + + +
+
+
Motors
@@ -22,30 +68,29 @@
+
Servos
-
-
-
-
-
-
-
+
+
+
+
+
+
+
-

-

@@ -73,8 +118,7 @@
-
-
+
\ No newline at end of file diff --git a/tabs/motor_outputs.js b/tabs/motor_outputs.js index 91eed6b334..0187b59e87 100644 --- a/tabs/motor_outputs.js +++ b/tabs/motor_outputs.js @@ -2,6 +2,124 @@ function tab_initialize_motor_outputs() { ga_tracker.sendAppView('Motor Outputs Page'); GUI.active_tab = 'motor_outputs'; + function initSensorData() { + for (var i = 0; i < 3; i++) { + SENSOR_DATA.accelerometer[i] = 0; + } + } + + function initDataArray(length) { + var data = new Array(length); + for (var i = 0; i < length; i++) { + data[i] = new Array(); + data[i].min = -1; + data[i].max = 1; + } + return data; + } + + function addSampleToData(data, sampleNumber, sensorData) { + for (var i = 0; i < data.length; i++) { + var dataPoint = sensorData[i]; + data[i].push([sampleNumber, dataPoint]); + if (dataPoint < data[i].min) { + data[i].min = dataPoint; + } + if (dataPoint > data[i].max) { + data[i].max = dataPoint; + } + } + while (data[0].length > 300) { + for (i = 0; i < data.length; i++) { + data[i].shift(); + } + } + return sampleNumber + 1; + } + + var margin = {top: 20, right: 10, bottom: 10, left: 20}; + function updateGraphHelperSize(helpers) { + helpers.width = helpers.targetElement.width() - margin.left - margin.right; + helpers.height = helpers.targetElement.height() - margin.top - margin.bottom; + + helpers.widthScale.range([0, helpers.width]); + helpers.heightScale.range([helpers.height, 0]); + + helpers.xGrid.tickSize(-helpers.height, 0, 0); + helpers.yGrid.tickSize(-helpers.width, 0, 0); + } + + function initGraphHelpers(selector, sampleNumber, heightDomain) { + var helpers = {selector: selector, targetElement: $(selector), dynamicHeightDomain: !heightDomain}; + + helpers.widthScale = d3.scale.linear() + .clamp(true) + .domain([(sampleNumber - 299), sampleNumber]); + + helpers.heightScale = d3.scale.linear() + .clamp(true) + .domain(heightDomain || [1, -1]); + + helpers.xGrid = d3.svg.axis(); + helpers.yGrid = d3.svg.axis(); + + updateGraphHelperSize(helpers); + + helpers.xGrid + .scale(helpers.widthScale) + .orient("bottom") + .ticks(5) + .tickFormat(""); + + helpers.yGrid + .scale(helpers.heightScale) + .orient("left") + .ticks(5) + .tickFormat(""); + + helpers.xAxis = d3.svg.axis() + .scale(helpers.widthScale) + .ticks(5) + .orient("bottom") + .tickFormat(function(d) {return d;}); + + helpers.yAxis = d3.svg.axis() + .scale(helpers.heightScale) + .ticks(5) + .orient("left") + .tickFormat(function(d) {return d;}); + + helpers.line = d3.svg.line() + .x(function(d) { return helpers.widthScale(d[0]); }) + .y(function(d) { return helpers.heightScale(d[1]); }); + + return helpers; + } + + function drawGraph(graphHelpers, data, sampleNumber) { + svg = d3.select(graphHelpers.selector); + + if (graphHelpers.dynamicHeightDomain) { + var limits = []; + $.each(data, function(idx, datum) { + limits.push(datum.min); + limits.push(datum.max); + }); + graphHelpers.heightScale.domain(d3.extent(limits)); + } + graphHelpers.widthScale.domain([(sampleNumber - 299), sampleNumber]); + + svg.select(".x.grid").call(graphHelpers.xGrid); + svg.select(".y.grid").call(graphHelpers.yGrid); + svg.select(".x.axis").call(graphHelpers.xAxis); + svg.select(".y.axis").call(graphHelpers.yAxis); + + var group = svg.select("g.data"); + var lines = group.selectAll("path").data(data, function(d, i) { return i; }); + var newLines = lines.enter().append("path").attr("class", "line"); + lines.attr('d', graphHelpers.line); + } + MSP.send_message(MSP_codes.MSP_MISC, false, false, get_motor_data); function get_motor_data() { @@ -16,6 +134,97 @@ function tab_initialize_motor_outputs() { // translate to user-selected language localize(); + // Always start with default/empty sensor data array, clean slate all + initSensorData(); + + // Setup variables + var samples_accel_i = 0; + var accel_data = initDataArray(3); + var accelHelpers = initGraphHelpers('#accel', samples_accel_i, [-2, 2]); + var accel_max_read = [0, 0, 0]; + var accel_offset = [0, 0, 0]; + var accel_offset_established = false; + + var raw_data_text_ements = { + x: [], + y: [], + z: [], + }; + $('.plot_control .x, .plot_control .y, .plot_control .z').each(function() { + var el = $(this); + if (el.hasClass('x')) { + raw_data_text_ements.x.push(el); + } else if (el.hasClass('y')) { + raw_data_text_ements.y.push(el); + } else { + raw_data_text_ements.z.push(el); + } + }); + + // set refresh speeds according to configuration saved in storage + chrome.storage.local.get('motors_tab_accel_settings', function(result) { + if (result.motors_tab_accel_settings) { + $('.tab-motor_outputs select[name="accel_refresh_rate"]').val(result.motors_tab_accel_settings.rate); + $('.tab-motor_outputs select[name="accel_scale"]').val(result.motors_tab_accel_settings.scale); + + // start polling data by triggering refresh rate change event + $('.tab-motor_outputs .rate select:first').change(); + } else { + // start polling immediatly (as there is no configuration saved in the storage) + $('.tab-motor_outputs .rate select:first').change(); + } + }); + + $('.tab-motor_outputs .rate select, .tab-motor_outputs .scale select').change(function() { + var rate = parseInt($('.tab-motor_outputs select[name="accel_refresh_rate"]').val(), 10); + var scale = parseFloat($('.tab-motor_outputs select[name="accel_scale"]').val()); + + // store current/latest refresh rates in the storage + chrome.storage.local.set({'motors_tab_accel_settings': {'rate': rate, 'scale': scale}}); + + accelHelpers = initGraphHelpers('#accel', samples_accel_i, [-scale, scale]); + + // timer initialization + GUI.interval_kill_all(['motor_pull', 'status_pull']); + + GUI.interval_add('IMU_pull', function imu_data_pull() { + MSP.send_message(MSP_codes.MSP_RAW_IMU, false, false, update_accel_graph); + }, rate, true); + + function update_accel_graph() { + if (!accel_offset_established) { + for (var i = 0; i < 3; i++) { + accel_offset[i] = SENSOR_DATA.accelerometer[i] * -1; + } + + accel_offset_established = true; + } + + var accel_with_offset = [ + accel_offset[0] + SENSOR_DATA.accelerometer[0], + accel_offset[1] + SENSOR_DATA.accelerometer[1], + accel_offset[2] + SENSOR_DATA.accelerometer[2], + ]; + + updateGraphHelperSize(accelHelpers); + samples_accel_i = addSampleToData(accel_data, samples_accel_i, accel_with_offset); + drawGraph(accelHelpers, accel_data, samples_accel_i); + + raw_data_text_ements.x[0].text(accel_with_offset[0].toFixed(2) + ' (' + accel_max_read[0].toFixed(2) + ')'); + raw_data_text_ements.y[0].text(accel_with_offset[1].toFixed(2) + ' (' + accel_max_read[1].toFixed(2) + ')'); + raw_data_text_ements.z[0].text(accel_with_offset[2].toFixed(2) + ' (' + accel_max_read[2].toFixed(2) + ')'); + + for (var i = 0; i < 3; i++) { + if (Math.abs(accel_with_offset[i]) > Math.abs(accel_max_read[i])) accel_max_read[i] = accel_with_offset[i]; + } + } + }); + + $('a.reset_accel_max').click(function() { + accel_max_read = [0, 0, 0]; + accel_offset_established = false; + }); + // if CAP_DYNBALANCE is true if (bit_check(CONFIG.capability, 2)) { $('div.motor_testing').show(); @@ -70,14 +279,51 @@ function tab_initialize_motor_outputs() { $('div.sliders input').prop('disabled', true); // change all values to default - $('div.sliders input').val(1000); - $('div.values li:not(:last)').html(1000); + $('div.sliders input').val(MISC.mincommand); // trigger change event so values are sent to mcu $('div.sliders input').trigger('input'); } }); + // check if motors are already spinning + var motors_running = false; + + for (var i = 0; i < MOTOR_DATA.length; i++) { + if (MOTOR_DATA[i] > MISC.mincommand) { + motors_running = true; + break; + } + } + + if (motors_running) { + // motors are running, enable test mode and adjust sliders to current values + $('div.notice input[type="checkbox"]').click(); + + var sliders = $('div.sliders input:not(.master)'); + + var master_value = MOTOR_DATA[0]; + for (var i = 0; i < MOTOR_DATA.length; i++) { + if (MOTOR_DATA[i] > 0) { + sliders.eq(i).val(MOTOR_DATA[i]); + + if (master_value != MOTOR_DATA[i]) { + master_value = false; + } + } + } + + // only fire events when all values are set + sliders.trigger('input'); + + // slide master slider if condition is valid + if (master_value) { + $('div.sliders input.master').val(master_value); + $('div.sliders input.master').trigger('input'); + } + } + + // data pulling functions used inside interval timer function get_motor_data() { MSP.send_message(MSP_codes.MSP_MOTOR, false, false, get_servo_data); @@ -87,18 +333,20 @@ function tab_initialize_motor_outputs() { MSP.send_message(MSP_codes.MSP_SERVO, false, false, update_ui); } + var full_block_scale = MISC.maxthrottle - MISC.mincommand; function update_ui() { var block_height = $('div.m-block:first').height(); for (var i = 0; i < MOTOR_DATA.length; i++) { - var data = MOTOR_DATA[i] - 1000; - var margin_top = block_height - (data * (block_height / 1000)); - var height = (data * (block_height / 1000)); + var data = MOTOR_DATA[i] - MISC.mincommand; + var margin_top = block_height - (data * (block_height / full_block_scale)); + var height = (data * (block_height / full_block_scale)); var color = parseInt(data * 0.256); $('.motor-' + i + ' .indicator').css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgb(' + color + ',0,0)'}); } + // servo indicators are still using old (not flexible block scale), it will be changed in the future accordingly for (var i = 0; i < SERVO_DATA.length; i++) { var data = SERVO_DATA[i] - 1000; var margin_top = block_height - (data * (block_height / 1000)); @@ -113,7 +361,7 @@ function tab_initialize_motor_outputs() { GUI.interval_add('motor_pull', get_motor_data, 50, true); // status data pulled via separate timer with static speed - GUI.interval_add('status_pull', function() { + GUI.interval_add('status_pull', function get_status_data() { MSP.send_message(MSP_codes.MSP_STATUS); }, 250, true); } diff --git a/tabs/pid_tuning.css b/tabs/pid_tuning.css index 3c07263112..b6c7fc066a 100644 --- a/tabs/pid_tuning.css +++ b/tabs/pid_tuning.css @@ -40,7 +40,7 @@ width: calc(18% - 2px); /* - border*/ - border: 1px solid silver; + border: 1px solid #8b8b8b; } .tab-pid_tuning .profile .head { display: block; @@ -49,7 +49,7 @@ line-height: 20px; font-weight: bold; - border-bottom: 1px solid silver; + border-bottom: 1px solid #8b8b8b; background-color: #ececec; } .tab-pid_tuning .profile input { @@ -73,6 +73,12 @@ float: right; width: calc(40% - 10px); /* - ( "virtual" margin) */ } + .tab-pid_tuning .buttons { + width: calc(100% - 20px); + + position: absolute; + bottom: 10px; + } .tab-pid_tuning .update, .tab-pid_tuning .refresh { display: block; @@ -95,7 +101,4 @@ .tab-pid_tuning .update:hover, .tab-pid_tuning .refresh:hover { background-color: #dedcdc; - } - .tab-pid_tuning .update.success { - border: 1px solid #43c84d; } \ No newline at end of file diff --git a/tabs/pid_tuning.html b/tabs/pid_tuning.html index 4d2e81ff02..1dca82b766 100644 --- a/tabs/pid_tuning.html +++ b/tabs/pid_tuning.html @@ -55,9 +55,9 @@ - - - + + + @@ -76,11 +76,13 @@ - -
+
+ + +
\ No newline at end of file diff --git a/tabs/pid_tuning.js b/tabs/pid_tuning.js index 0d0e9cab4e..ea93a35986 100644 --- a/tabs/pid_tuning.js +++ b/tabs/pid_tuning.js @@ -141,7 +141,7 @@ function tab_initialize_pid_tuning() { $(this).val(PIDs[7][i++].toFixed(1)); break; case 1: - $(this).val(PIDs[7][i++].toFixed(2)); + $(this).val(PIDs[7][i++].toFixed(3)); break; case 2: $(this).val(PIDs[7][i++].toFixed(0)); @@ -300,13 +300,6 @@ function tab_initialize_pid_tuning() { function save_to_eeprom() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved')); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); }); } }); diff --git a/tabs/receiver.css b/tabs/receiver.css index ba48d11050..3b4aa7949f 100644 --- a/tabs/receiver.css +++ b/tabs/receiver.css @@ -12,6 +12,42 @@ .tab-receiver .bars ul { margin-bottom: 5px; } + .tab-receiver .bars ul:nth-of-type(1) { + color: #00A8F0; + } + .tab-receiver .bars ul:nth-of-type(2) { + color: #C0D800; + } + .tab-receiver .bars ul:nth-of-type(3) { + color: #f8921a; + } + .tab-receiver .bars ul:nth-of-type(4) { + color: #f02525; + } + .tab-receiver .bars ul:nth-of-type(5) { + color: #9440ED; + } + .tab-receiver .bars ul:nth-of-type(6) { + color: #45147a; + } + .tab-receiver .bars ul:nth-of-type(7) { + color: #cf7a26; + } + .tab-receiver .bars ul:nth-of-type(8) { + color: #147a66; + } + .tab-receiver .bars ul:nth-of-type(9) { + color: #0609a9; + } + .tab-receiver .bars ul:nth-of-type(10) { + color: #7a1445; + } + .tab-receiver .bars ul:nth-of-type(11) { + color: #267acf; + } + .tab-receiver .bars ul:nth-of-type(12) { + color: #7a6614; + } .tab-receiver .bars li { float: left; @@ -66,50 +102,9 @@ padding: 0 5px 0 5px; text-align: right; } - .tab-receiver #RX_plot { - margin-left: 5px; - - height: 200px; - } .tab-receiver .curves { float: right; } - .tab-receiver .line:nth-child(1) { - stroke: #00A8F0; - } - .tab-receiver .line:nth-child(2) { - stroke: #C0D800; - } - .tab-receiver .line:nth-child(3) { - stroke: #CB4B4B; - } - .tab-receiver .line:nth-child(4) { - stroke: #4DA74D; - } - .tab-receiver .line:nth-child(5) { - stroke: #9440ED; - } - .tab-receiver .line:nth-child(6) { - stroke: #45147A; - } - .tab-receiver .line:nth-child(7) { - stroke: #CF7A26; - } - .tab-receiver .line:nth-child(8) { - stroke: #147A66; - } - .tab-receiver .line:nth-child(9) { - stroke: #407a9e; - } - .tab-receiver .line:nth-child(10) { - stroke: #7a1445; - } - .tab-receiver .line:nth-child(11) { - stroke: #267acf; - } - .tab-receiver .line:nth-child(12) { - stroke: #7a6614; - } .tab-receiver .throttle_curve { margin: 0 10px 10px 0; @@ -126,6 +121,57 @@ border: 1px solid silver; } + .tab-receiver select[name="rx_refresh_rate"] { + float: right; + + border: 1px solid silver; + } + .tab-receiver #RX_plot { + width: 100%; + height: 200px; + } + .tab-receiver #RX_plot .line:nth-child(1) { + stroke: #00A8F0; + } + .tab-receiver #RX_plot .line:nth-child(2) { + stroke: #C0D800; + } + .tab-receiver #RX_plot .line:nth-child(3) { + stroke: #f8921a; + } + .tab-receiver #RX_plot .line:nth-child(4) { + stroke: #f02525; + } + .tab-receiver #RX_plot .line:nth-child(5) { + stroke: #9440ED; + } + .tab-receiver #RX_plot .line:nth-child(6) { + stroke: #45147A; + } + .tab-receiver #RX_plot .line:nth-child(7) { + stroke: #CF7A26; + } + .tab-receiver #RX_plot .line:nth-child(8) { + stroke: #147A66; + } + .tab-receiver #RX_plot .line:nth-child(9) { + stroke: #0609a9; + } + .tab-receiver #RX_plot .line:nth-child(10) { + stroke: #7a1445; + } + .tab-receiver #RX_plot .line:nth-child(11) { + stroke: #267acf; + } + .tab-receiver #RX_plot .line:nth-child(12) { + stroke: #7a6614; + } + .tab-receiver .buttons { + width: calc(100% - 20px); + + position: absolute; + bottom: 10px; + } .tab-receiver .update, .tab-receiver .refresh { display: block; @@ -151,17 +197,6 @@ .tab-receiver .refresh:hover { background-color: #dedcdc; } - .tab-receiver .update.success { - border: 1px solid #43c84d; - } - .tab-receiver select[name="rx_refresh_rate"] { - float: right; - - margin-top: 30px; - margin-right: 13px; - - border: 1px solid silver; - } /* SVG classes*/ .tab-receiver .grid .tick { diff --git a/tabs/receiver.html b/tabs/receiver.html index f90f5fc55b..28418ba8ad 100644 --- a/tabs/receiver.html +++ b/tabs/receiver.html @@ -22,8 +22,6 @@ - -
@@ -53,4 +51,8 @@ +
+ + +
diff --git a/tabs/receiver.js b/tabs/receiver.js index 0a7e7cd1a6..c44b9b50ff 100644 --- a/tabs/receiver.js +++ b/tabs/receiver.js @@ -154,13 +154,6 @@ function tab_initialize_receiver() { function save_to_eeprom() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('receiverEepromSaved')); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); }); } }); @@ -185,7 +178,7 @@ function tab_initialize_receiver() { var svg = d3.select("svg"); var RX_plot_e = $('#RX_plot'); - var margin = {top: 20, right: 20, bottom: 10, left: 40}; + var margin = {top: 20, right: 0, bottom: 10, left: 40}; var width, height, widthScale, heightScale; function update_receiver_plot_size() { width = RX_plot_e.width() - margin.left - margin.right; diff --git a/tabs/sensors.css b/tabs/sensors.css index c5738d1389..292fb713bc 100644 --- a/tabs/sensors.css +++ b/tabs/sensors.css @@ -60,6 +60,10 @@ .tab-sensors .plot_control .z { color: #CB4B4B; } + .tab-sensors .plot_control .x, .tab-sensors .plot_control .y, .tab-sensors .plot_control .z { + text-align: right; + margin-right: 25px; + } .tab-sensors select { width: 70px; border: 1px solid silver; diff --git a/tabs/sensors.js b/tabs/sensors.js index 1bca396345..23a27f5ea1 100644 --- a/tabs/sensors.js +++ b/tabs/sensors.js @@ -40,7 +40,7 @@ function tab_initialize_sensors() { return sampleNumber + 1; } - var margin = {top: 20, right: 20, bottom: 10, left: 40}; + var margin = {top: 20, right: 10, bottom: 10, left: 40}; function updateGraphHelperSize(helpers) { helpers.width = helpers.targetElement.width() - margin.left - margin.right; helpers.height = helpers.targetElement.height() - margin.top - margin.bottom; diff --git a/tabs/servos.css b/tabs/servos.css index 697e320430..bbdaa2d362 100644 --- a/tabs/servos.css +++ b/tabs/servos.css @@ -106,6 +106,12 @@ float: left; margin: 0 0 0 5px; } + .tab-servos .buttons { + width: calc(100% - 20px); + + position: absolute; + bottom: 10px; + } .tab-servos .update { display: block; float: right; @@ -125,7 +131,4 @@ } .tab-servos .update:hover { background-color: #dedcdc; - } - .tab-servos .update.success { - border: 1px solid #43c84d; } \ No newline at end of file diff --git a/tabs/servos.html b/tabs/servos.html index 1ad006a59a..887e4abcd3 100644 --- a/tabs/servos.html +++ b/tabs/servos.html @@ -31,6 +31,8 @@
- +
+ +
\ No newline at end of file diff --git a/tabs/servos.js b/tabs/servos.js index 2d5756df42..88a12b1530 100644 --- a/tabs/servos.js +++ b/tabs/servos.js @@ -188,13 +188,6 @@ function tab_initialize_servos() { // Save changes to EEPROM MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('servosEepromSave')); - - var element = $('a.update'); - element.addClass('success'); - - GUI.timeout_add('success_highlight', function() { - element.removeClass('success'); - }, 2000); }); } }