Merge remote-tracking branch 'multiwii/master'

Conflicts:
	_locales/en/messages.json
	tabs/auxiliary_configuration.html
	tabs/auxiliary_configuration.js
	tabs/receiver.css
10.3.x-maintenance
Dominic Clifton 2014-07-07 19:45:33 +01:00
commit 58f933e92c
45 changed files with 1819 additions and 632 deletions

View File

@ -51,7 +51,7 @@
"message": "GPS" "message": "GPS"
}, },
"tab7": { "tab7": {
"message": "Motor/Servo Outputs" "message": "Motor Testing"
}, },
"tab8": { "tab8": {
"message": "Raw Sensor Data" "message": "Raw Sensor Data"
@ -108,16 +108,35 @@
"statusbar_packet_error": { "statusbar_packet_error": {
"message": "Packet error:" "message": "Packet error:"
}, },
"statusbar_i2c_error": {
"message": "I2C error:"
},
"statusbar_cycle_time": { "statusbar_cycle_time": {
"message": "Cycle Time:" "message": "Cycle Time:"
}, },
"please_grant_usb_permissions": {
"message": "Please click on <strong>\"Request Optional Permissions\"</strong> button to grant application <strong style=\"color: red\">required</strong> <strong>USB</strong> access"
},
"usb_permissions_granted": {
"message": "Optional <strong>USB</strong> permissions <strong style=\"color: green\">granted</strong>"
},
"eeprom_saved_ok": { "eeprom_saved_ok": {
"message": "EEPROM <span style=\"color: green\">saved</span>" "message": "EEPROM <span style=\"color: green\">saved</span>"
}, },
"default_optional_permissions_head": {
"message": "Optional USB Permissions"
},
"default_optional_permissions_text": {
"message": "Due to addition of <strong>Naze32PRO</strong> to the supported hardware family, Configurator <strong style=\"color: red\">requires</strong> USB access to allow firmware flashing via DFU"
},
"default_request_optional_permissions": {
"message": "Request Optional Permissions"
},
"defaultWelcomeText": { "defaultWelcomeText": {
"message": "This application is a configuration utility for cleanflight, a 32 bit fork of the popular open source RC flight control firmware project <a href=\"http://www.multiwii.org/\" title=\"www.multiwii.org\" target=\"_blank\">MultiWii</a>.<br /><br />Application supports hardware that run cleanflight <strong>exclusively</strong> (acro naze, naze, afromini, flip32, flip32+, chebuzz f3, stm32f3discovery, naze32pro, etc)<br /><br />The firmware source code can be downloaded from <a href=\"https://github.com/hydra/cleanflight\" title=\"www.github.com\" target=\"_blank\">here</a><br />The newest binary firmware image is available <a href=\"https://github.com/hydra/cleanflight/tree/master/obj\" title=\"www.github.com\" target=\"_blank\">here</a><br />" "message": "This application is a configuration utility for cleanflight, a 32 bit fork of the popular open source RC flight control firmware project <a href=\"http://www.multiwii.org/\" title=\"www.multiwii.org\" target=\"_blank\">MultiWii</a>.<br /><br />Application supports hardware that run cleanflight (acro naze, naze, afromini, flip32, flip32+, chebuzz f3, stm32f3discovery, naze32pro, etc)<br /><br />The firmware source code can be downloaded from <a href=\"https://github.com/hydra/cleanflight\" title=\"www.github.com\" target=\"_blank\">here</a><br />The newest binary firmware image is available <a href=\"https://github.com/hydra/cleanflight/tree/master/obj\" title=\"www.github.com\" target=\"_blank\">here</a><br /><br />Latest <strong>CP210x Drivers</strong> can be downloaded from <a href=\"http://www.silabs.com/products/mcu/pages/usbtouartbridgevcpdrivers.aspx\" title=\"http://www.silabs.com/\" target=\"_blank\">here</a><br />"
}, },
"defaultChangelogHead": { "defaultChangelogHead": {
"message": "Configurator - Changelog" "message": "Configurator - Changelog"
@ -428,9 +447,6 @@
"message": "Signal Strength" "message": "Signal Strength"
}, },
"motorsBarInfo": {
"message": "Bars on the <strong>left</strong> are representing raw PWM signal for <strong>ESCs</strong>.<br />Bars on the <strong>right</strong> are representing raw PWM signal for <strong>Servos</strong>.<br />"
},
"motorsMaster": { "motorsMaster": {
"message": "Master" "message": "Master"
}, },
@ -464,9 +480,6 @@
"loggingLogSize": { "loggingLogSize": {
"message": "Log Size:" "message": "Log Size:"
}, },
"loggingKB": {
"message": "$1 kB"
},
"loggingButtonLogFile": { "loggingButtonLogFile": {
"message": "Select Log File" "message": "Select Log File"
}, },
@ -476,6 +489,12 @@
"loggingStop": { "loggingStop": {
"message": "Stop Logging" "message": "Stop Logging"
}, },
"loggingBack": {
"message": "Leave Logging / Disconnect"
},
"loggingErrorNotConnected": {
"message": "You need to <strong>connect</strong> first"
},
"loggingErrorLogFile": { "loggingErrorLogFile": {
"message": "Please select log file" "message": "Please select log file"
}, },
@ -499,7 +518,7 @@
"message": "Progress:" "message": "Progress:"
}, },
"firmwareFlasherNote": { "firmwareFlasherNote": {
"message": "If you are flashing board with <strong>baseflight</strong> already flashed (updating), leave this checkbox unchecked.<br />If you are flashing \"<strong>bare</strong>\" board with no firmware preloaded or you have bootloader pins <strong>shorted</strong>, check this box.<br />" "message": "If you are flashing board with bootloader pins <strong>shorted/connected</strong>, check <strong>No reboot sequence</strong>.<br />If you want configuration data to be wiped, check <strong>Full Chip Erase</strong><br />"
}, },
"firmwareFlasherNoReboot": { "firmwareFlasherNoReboot": {
"message": "No reboot sequence" "message": "No reboot sequence"
@ -543,8 +562,8 @@
"firmwareFlasherFirmwareNotLoaded": { "firmwareFlasherFirmwareNotLoaded": {
"message": "<span style=\"color: red\">Firmware not loaded</span>" "message": "<span style=\"color: red\">Firmware not loaded</span>"
}, },
"firmwareFlasherFirmwareLoaded": { "firmwareFlasherLocalFirmwareLoaded": {
"message": "<span style=\"color: green\">Firmware loaded, ready for flashing</span>" "message": "<span style=\"color: green\">Local Firmware loaded, ready for flashing</span>"
}, },
"firmwareFlasherHexCorrupted": { "firmwareFlasherHexCorrupted": {
"message": "<span style=\"color: red\">HEX file appears to be corrupted</span>" "message": "<span style=\"color: red\">HEX file appears to be corrupted</span>"

View File

@ -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. 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() { function start_app() {
chrome.app.window.create('main.html', { 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 // connectionId is passed from the script side through the chrome.runtime.getBackgroundPage refference
// allowing us to automatically close the port when application shut down // 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 // save connectionId in separate variable before app_window is destroyed
var connectionId = app_window.serial.connectionId; var connectionId = app_window.serial.connectionId;
@ -29,6 +81,7 @@ function start_app() {
} }
}); });
}); });
*/
} }
chrome.app.runtime.onLaunched.addListener(function() { chrome.app.runtime.onLaunched.addListener(function() {

View File

@ -1,3 +1,34 @@
<span>07.06.2014</span>
<p>
- Servos tab updated to support Cleanflight's cleaner implementation of channel forwarding<br />
</p>
<span>07.04.2014 - 0.45</span>
<p>
- Configurator reached 5000+ users on 07.03.2014<br />
- Updated various text notes to make things clearer<br />
- UI polish<br />
- Various bugfixes<br />
</p>
<span>06.27.2014 - 0.44</span>
<p>
- Added more scale factors in the motor testing tab<br />
- If application closes without disconnecting motors should spin down<br />
- Bugfixes for CLI, Motor Testing &amp; Logging tabs<br />
</p>
<span>06.26.2014 - 0.43</span>
<p>
- Experimental passthrough support for logging<br />
- MSP_ANALOG support for logging<br />
- Allow running motors (testing) while monitoring sensors<br />
- Major UI changes in Motor Testing tab<br />
- Tiny cosmetic changes<br />
- Initial set of UI bugfixes for Chrome 36+<br />
</p>
<span>06.16.2014 - 0.42</span>
<p>
- Added I2C Error indicator to status bar<br />
- Optimizations &amp; bugfixes<br />
</p>
<span>06.01.2014 - 0.41</span> <span>06.01.2014 - 0.41</span>
<p> <p>
- Configurator reached 4000+ users on 05.29.2014<br /> - Configurator reached 4000+ users on 05.29.2014<br />

View File

@ -38,20 +38,18 @@ var RC_tuning = {
throttle_EXPO: 0, throttle_EXPO: 0,
}; };
var AUX_CONFIG = new Array(); var AUX_CONFIG = [];
var AUX_CONFIG_values = new Array(); var AUX_CONFIG_values = [];
var SERVO_CONFIG = new Array(); var SERVO_CONFIG = [];
var SENSOR_DATA = { var SENSOR_DATA = {
gyroscope: [0, 0, 0], gyroscope: [0, 0, 0],
accelerometer: [0, 0, 0], accelerometer: [0, 0, 0],
magnetometer: [0, 0, 0], magnetometer: [0, 0, 0],
altitude: 0, altitude: 0,
kinematicsX: 0.0, kinematics: [0.0, 0.0, 0.0],
kinematicsY: 0.0, debug: [0, 0, 0, 0]
kinematicsZ: 0.0,
debug: [0, 0, 0, 0]
}; };
var MOTOR_DATA = new Array(8); var MOTOR_DATA = new Array(8);
@ -70,10 +68,10 @@ var GPS_DATA = {
update: 0, update: 0,
// baseflight specific gps stuff // baseflight specific gps stuff
chn: new Array(), chn: [],
svid: new Array(), svid: [],
quality: new Array(), quality: [],
cno: new Array() cno: []
}; };
var ANALOG = { var ANALOG = {

View File

@ -4,6 +4,7 @@ var GUI_control = function() {
this.connected_to = false; this.connected_to = false;
this.active_tab; this.active_tab;
this.operating_system; this.operating_system;
this.optional_usb_permissions = false; // controlled by usb permissions code
this.interval_array = []; this.interval_array = [];
this.timeout_array = []; this.timeout_array = [];
@ -226,38 +227,9 @@ GUI_control.prototype.tab_switch_cleanup = function(callback) {
if (callback) callback(); if (callback) callback();
break; break;
case 'motor_outputs': case 'motor_outputs':
GUI.interval_remove('motor_pull'); GUI.interval_kill_all();
GUI.interval_remove('status_pull');
// only enforce mincommand if necessary if (callback) callback();
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();
}
break; break;
case 'sensors': case 'sensors':
GUI.interval_kill_all(); 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 }, 5000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one
}); });
break; break;
case 'logging':
GUI.interval_kill_all();
if (callback) callback();
break;
case 'firmware_flasher': case 'firmware_flasher':
// this.interval_remove('factory_mode'); // this.interval_remove('factory_mode');
PortHandler.flush_callbacks(); PortHandler.flush_callbacks();
@ -302,7 +278,6 @@ GUI_control.prototype.tab_switch_cleanup = function(callback) {
if (callback) callback(); if (callback) callback();
break; break;
default: default:
if (callback) callback(); if (callback) callback();
} }

View File

@ -175,6 +175,7 @@ MSP.process_data = function(code, message_buffer, message_length) {
CONFIG.profile = data.getUint8(10); CONFIG.profile = data.getUint8(10);
sensor_status(CONFIG.activeSensors); sensor_status(CONFIG.activeSensors);
$('span.i2c-error').text(CONFIG.i2cError);
$('span.cycle-time').text(CONFIG.cycleTime); $('span.cycle-time').text(CONFIG.cycleTime);
break; break;
case MSP_codes.MSP_RAW_IMU: 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); GPS_DATA.update = data.getUint8(4);
break; break;
case MSP_codes.MSP_ATTITUDE: case MSP_codes.MSP_ATTITUDE:
SENSOR_DATA.kinematicsX = data.getInt16(0, 1) / 10.0; SENSOR_DATA.kinematics[0] = data.getInt16(0, 1) / 10.0; // x
SENSOR_DATA.kinematicsY = data.getInt16(2, 1) / 10.0; SENSOR_DATA.kinematics[1] = data.getInt16(2, 1) / 10.0; // y
SENSOR_DATA.kinematicsZ = data.getInt16(4, 1); SENSOR_DATA.kinematics[2] = data.getInt16(4, 1); // z
break; break;
case MSP_codes.MSP_ALTITUDE: case MSP_codes.MSP_ALTITUDE:
SENSOR_DATA.altitude = parseFloat((data.getInt32(0, 1) / 100.0).toFixed(2)); // correct scale factor 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; break;
case MSP_codes.MSP_BOX: case MSP_codes.MSP_BOX:
// dump previous data (if there was any) AUX_CONFIG_values = []; // empty the array as new data is coming in
AUX_CONFIG_values = new Array();
var boxItems = data.byteLength / 2; // AUX 1-4, 2 bytes per boxItem var boxItems = data.byteLength / 2; // AUX 1-4, 2 bytes per boxItem
if (bit_check(CONFIG.capability, 5)) { if (bit_check(CONFIG.capability, 5)) {
@ -359,8 +359,7 @@ MSP.process_data = function(code, message_buffer, message_length) {
console.log(data); console.log(data);
break; break;
case MSP_codes.MSP_SERVO_CONF: case MSP_codes.MSP_SERVO_CONF:
// drop previous data SERVO_CONFIG = []; // empty the array as new data is coming in
SERVO_CONFIG = [];
for (var i = 0; i < 56; i += 7) { for (var i = 0; i < 56; i += 7) {
var arr = { var arr = {

View File

@ -65,7 +65,7 @@ port_handler.prototype.check = function() {
if (port == result.last_used_port) { if (port == result.last_used_port) {
console.log('Selecting last used 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 { } else {
@ -98,9 +98,9 @@ port_handler.prototype.check = function() {
// select / highlight new port, if connected -> select connected port // select / highlight new port, if connected -> select connected port
if (!GUI.connected_to) { if (!GUI.connected_to) {
$('div#port-picker .port select').val(new_ports[0]); $('div#port-picker #port').val(new_ports[0]);
} else { } 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) // start connect procedure (if statement is valid)
@ -131,21 +131,40 @@ port_handler.prototype.check = function() {
self.initial_ports = current_ports; self.initial_ports = current_ports;
} }
if (GUI.optional_usb_permissions) {
check_usb_devices();
}
self.main_timeout_reference = setTimeout(function() { self.main_timeout_reference = setTimeout(function() {
self.check(); self.check();
}, 250); }, 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('<option value="DFU">DFU</option>');
$('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) { 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) { if (ports.length > 0) {
for (var i = 0; i < ports.length; i++) { for (var i = 0; i < ports.length; i++) {
$('div#port-picker .port select').append($("<option/>", {value: ports[i], text: ports[i]})); $('div#port-picker #port').append($("<option/>", {value: ports[i], text: ports[i]}));
} }
} else { } else {
$('div#port-picker .port select').append($("<option/>", {value: 0, text: 'No Ports'})); $('div#port-picker #port').append($("<option/>", {value: 0, text: 'No Ports'}));
} }
}; };

View File

@ -1,8 +1,8 @@
var serial = { var serial = {
connectionId: -1, connectionId: -1,
bitrate: 0, bitrate: 0,
bytes_received: 0, bytes_received: 0,
bytes_sent: 0, bytes_sent: 0,
transmitting: false, transmitting: false,
output_buffer: [], output_buffer: [],
@ -21,12 +21,54 @@ var serial = {
self.bytes_received += info.data.byteLength; self.bytes_received += info.data.byteLength;
}); });
self.onReceiveError.addListener(function watch_for_on_receive_errors(info) {
console.error(info);
ga_tracker.sendEvent('Error', 'Serial', info.error);
switch (info.error) {
case 'system_error': // we might be able to recover from this one
chrome.serial.setPaused(self.connectionId, false, get_status);
function get_status() {
self.getInfo(crunch_status);
}
function crunch_status(info) {
if (!info.paused) {
console.log('SERIAL: Connection recovered from last onReceiveError');
ga_tracker.sendEvent('Error', 'Serial', 'recovered');
} else {
console.log('SERIAL: Connection did not recover from last onReceiveError, disconnecting');
GUI.log('Unrecoverable <span style="color: red">failure</span> of serial connection, disconnecting...');
ga_tracker.sendEvent('Error', 'Serial', 'unrecoverable');
if (GUI.connected_to || GUI.connecting_to) {
$('a.connect').click();
} else {
self.disconnect();
}
}
}
break;
case 'timeout':
// TODO
break;
case 'device_lost':
// TODO
break;
case 'disconnected':
// TODO
break;
}
});
console.log('SERIAL: Connection opened with ID: ' + connectionInfo.connectionId + ', Baud: ' + connectionInfo.bitrate); console.log('SERIAL: Connection opened with ID: ' + connectionInfo.connectionId + ', Baud: ' + connectionInfo.bitrate);
callback(connectionInfo); if (callback) callback(connectionInfo);
} else { } else {
console.log('SERIAL: Failed to open serial port'); console.log('SERIAL: Failed to open serial port');
callback(false); ga_tracker.sendEvent('Error', 'Serial', 'FailedToOpen');
if (callback) callback(false);
} }
}); });
}, },
@ -40,11 +82,16 @@ var serial = {
self.onReceive.removeListener(self.onReceive.listeners[i]); self.onReceive.removeListener(self.onReceive.listeners[i]);
} }
for (var i = (self.onReceiveError.listeners.length - 1); i >= 0; i--) {
self.onReceiveError.removeListener(self.onReceiveError.listeners[i]);
}
chrome.serial.disconnect(this.connectionId, function(result) { chrome.serial.disconnect(this.connectionId, function(result) {
if (result) { if (result) {
console.log('SERIAL: Connection with ID: ' + self.connectionId + ' closed'); console.log('SERIAL: Connection with ID: ' + self.connectionId + ' closed');
} else { } else {
console.log('SERIAL: Failed to close connection with ID: ' + self.connectionId + ' closed'); console.log('SERIAL: Failed to close connection with ID: ' + self.connectionId + ' closed');
ga_tracker.sendEvent('Error', 'Serial', 'FailedToClose');
} }
console.log('SERIAL: Statistics - Sent: ' + self.bytes_sent + ' bytes, Received: ' + self.bytes_received + ' bytes'); console.log('SERIAL: Statistics - Sent: ' + self.bytes_sent + ' bytes, Received: ' + self.bytes_received + ' bytes');
@ -52,7 +99,7 @@ var serial = {
self.connectionId = -1; self.connectionId = -1;
self.bitrate = 0; self.bitrate = 0;
callback(result); if (callback) callback(result);
}); });
}, },
getDevices: function(callback) { getDevices: function(callback) {
@ -65,6 +112,9 @@ var serial = {
callback(devices); callback(devices);
}); });
}, },
getInfo: function(callback) {
chrome.serial.getInfo(this.connectionId, callback);
},
setControlSignals: function(signals, callback) { setControlSignals: function(signals, callback) {
chrome.serial.setControlSignals(this.connectionId, signals, callback); chrome.serial.setControlSignals(this.connectionId, signals, callback);
}, },
@ -124,6 +174,25 @@ var serial = {
} }
} }
}, },
onReceiveError: {
listeners: [],
addListener: function(function_reference) {
var listener = chrome.serial.onReceiveError.addListener(function_reference);
this.listeners.push(function_reference);
},
removeListener: function(function_reference) {
for (var i = (this.listeners.length - 1); i >= 0; i--) {
if (this.listeners[i] == function_reference) {
chrome.serial.onReceiveError.removeListener(function_reference);
this.listeners.splice(i, 1);
break;
}
}
}
},
empty_output_buffer: function() { empty_output_buffer: function() {
this.output_buffer = []; this.output_buffer = [];
this.transmitting = false; this.transmitting = false;

View File

@ -1,16 +1,14 @@
var configuration_received = false; var configuration_received = false;
var CLI_active = false;
var CLI_valid = false;
$(document).ready(function() { $(document).ready(function() {
$('div#port-picker a.connect').click(function() { $('div#port-picker a.connect').click(function() {
if (GUI.connect_lock != true) { // GUI control overrides the user control if (GUI.connect_lock != true) { // GUI control overrides the user control
var clicks = $(this).data('clicks'); var clicks = $(this).data('clicks');
var selected_port = String($('div#port-picker .port select').val()); var selected_port = String($('div#port-picker #port').val());
var selected_baud = parseInt($('div#port-picker #baud').val()); var selected_baud = parseInt($('div#port-picker #baud').val());
if (selected_port != '0') { if (selected_port != '0' && selected_port != 'DFU') {
if (!clicks) { if (!clicks) {
console.log('Connecting to: ' + selected_port); console.log('Connecting to: ' + selected_port);
GUI.connecting_to = selected_port; GUI.connecting_to = selected_port;
@ -21,23 +19,22 @@ $(document).ready(function() {
serial.connect(selected_port, {bitrate: selected_baud}, onOpen); serial.connect(selected_port, {bitrate: selected_baud}, onOpen);
} else { } else {
// Disable any active "data pulling" timer GUI.timeout_kill_all();
GUI.interval_kill_all(); GUI.interval_kill_all();
GUI.tab_switch_cleanup(); GUI.tab_switch_cleanup();
GUI.timeout_remove('connecting');
serial.disconnect(onClosed); serial.disconnect(onClosed);
GUI.connected_to = false; GUI.connected_to = false;
// Reset various UI elements // Reset various UI elements
$('.software-version').html('0.0'); $('span.i2c-error').text(0);
$('span.cycle-time').html('0'); $('span.cycle-time').text(0);
MSP.disconnect_cleanup(); MSP.disconnect_cleanup();
PortUsage.reset(); PortUsage.reset();
configuration_received = false; // reset valid config received variable (used to block tabs while not connected properly) configuration_received = false; // reset valid config received variable (used to block tabs while not connected properly)
MSP_pass_through = false;
// unlock port select & baud // unlock port select & baud
$('div#port-picker #port').prop('disabled', false); $('div#port-picker #port').prop('disabled', false);
@ -127,34 +124,39 @@ 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 if (!MSP_pass_through) {
GUI.timeout_add('connecting', function() { // disconnect after 10 seconds with error if we don't get IDENT data
if (!configuration_received) { GUI.timeout_add('connecting', function() {
GUI.log(chrome.i18n.getMessage('noConfigurationReceived')); if (!configuration_received) {
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
$('div#port-picker a.connect').click(); // disconnect
}
}, 10000);
// request configuration data
MSP.send_message(MSP_codes.MSP_UID, false, false, function() {
GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function() {
GUI.timeout_remove('connecting'); // kill connecting timer
GUI.log(chrome.i18n.getMessage('firmwareVersion', [CONFIG.version]));
if (CONFIG.version >= firmware_version_accepted) {
configuration_received = true;
$('div#port-picker a.connect').text(chrome.i18n.getMessage('disconnect')).addClass('active');
$('#tabs li a:first').click();
} else {
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [firmware_version_accepted]));
$('div#port-picker a.connect').click(); // disconnect $('div#port-picker a.connect').click(); // disconnect
} }
}, 10000);
// request configuration data
MSP.send_message(MSP_codes.MSP_UID, false, false, function() {
GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function() {
GUI.timeout_remove('connecting'); // kill connecting timer
GUI.log(chrome.i18n.getMessage('firmwareVersion', [CONFIG.version]));
if (CONFIG.version >= firmware_version_accepted) {
configuration_received = true;
$('div#port-picker a.connect').text(chrome.i18n.getMessage('disconnect')).addClass('active');
$('#tabs li a:first').click();
} else {
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [firmware_version_accepted]));
$('div#port-picker a.connect').click(); // disconnect
}
});
}); });
}); } else {
$('div#port-picker a.connect').text(chrome.i18n.getMessage('disconnect')).addClass('active');
GUI.log('Connection opened in <strong>pass-through</strong> mode');
}
} else { } else {
console.log('Failed to open serial port'); console.log('Failed to open serial port');
GUI.log(chrome.i18n.getMessage('serialPortOpenFail')); GUI.log(chrome.i18n.getMessage('serialPortOpenFail'));
@ -179,10 +181,12 @@ function onClosed(result) {
} }
function read_serial(info) { function read_serial(info) {
if (!CLI_active) { if (!CLI_active && !MSP_pass_through) {
MSP.read(info); MSP.read(info);
} else { } else if (CLI_active) {
handle_CLI(info); handle_CLI(info);
} else if (MSP_pass_through) { // needs to be verified, might be removed after pass_through is 100% deployed
MSP.read(info);
} }
} }

View File

@ -42,17 +42,12 @@ var STM32_protocol = function() {
this.page_size = 0; this.page_size = 0;
}; };
// string = string .. duh
STM32_protocol.prototype.GUI_status = function(string) {
$('span.status').html(string);
};
// no input parameters // no input parameters
STM32_protocol.prototype.connect = function(hex) { STM32_protocol.prototype.connect = function(hex) {
var self = this; var self = this;
self.hex = hex; self.hex = hex;
var selected_port = String($('div#port-picker .port select').val()); var selected_port = String($('div#port-picker #port').val());
var baud = parseInt($('div#port-picker #baud').val()); var baud = parseInt($('div#port-picker #baud').val());
if (selected_port != '0') { if (selected_port != '0') {
@ -61,11 +56,7 @@ STM32_protocol.prototype.connect = function(hex) {
switch (GUI.operating_system) { switch (GUI.operating_system) {
case 'Windows': case 'Windows':
flashing_bitrate = 921600;
break;
case 'MacOS': case 'MacOS':
flashing_bitrate = 921600;
break;
case 'ChromeOS': case 'ChromeOS':
case 'Linux': case 'Linux':
case 'UNIX': case 'UNIX':
@ -122,7 +113,7 @@ STM32_protocol.prototype.connect = function(hex) {
} }
} else { } else {
console.log('Please select valid serial port'); console.log('Please select valid serial port');
STM32.GUI_status('<span style="color: red">Please select valid serial port</span>'); GUI.log('<span style="color: red">Please select valid serial port</span>');
} }
}; };
@ -151,7 +142,8 @@ STM32_protocol.prototype.initialize = function() {
self.upload_process_alive = false; self.upload_process_alive = false;
} else { } else {
console.log('STM32 - timed out, programming failed ...'); console.log('STM32 - timed out, programming failed ...');
STM32.GUI_status('STM32 - timed out, programming: <strong style="color: red">FAILED</strong>'); GUI.log('STM32 - timed out, programming: <strong style="color: red">FAILED</strong>');
ga_tracker.sendEvent('Flashing', 'Programming', 'timeout');
// protocol got stuck, clear timer and disconnect // protocol got stuck, clear timer and disconnect
GUI.interval_remove('STM32_timeout'); GUI.interval_remove('STM32_timeout');
@ -159,7 +151,7 @@ STM32_protocol.prototype.initialize = function() {
// exit // exit
self.upload_procedure(99); self.upload_procedure(99);
} }
}, 1000); }, 2000);
self.upload_procedure(1); self.upload_procedure(1);
}; };
@ -230,7 +222,7 @@ STM32_protocol.prototype.send = function(Array, bytes_to_read, callback) {
STM32_protocol.prototype.verify_response = function(val, data) { STM32_protocol.prototype.verify_response = function(val, data) {
if (val != data[0]) { if (val != data[0]) {
console.log('STM32 Communication failed, wrong response, expected: ' + val + ' received: ' + data[0]); console.log('STM32 Communication failed, wrong response, expected: ' + val + ' received: ' + data[0]);
STM32.GUI_status('STM32 Communication <span style="color: red">failed</span>, wrong response, expected: ' + val + ' received: ' + data[0]); GUI.log('STM32 Communication <span style="color: red">failed</span>, wrong response, expected: ' + val + ' received: ' + data[0]);
// disconnect // disconnect
this.upload_procedure(99); this.upload_procedure(99);
@ -338,6 +330,8 @@ STM32_protocol.prototype.upload_procedure = function(step) {
switch (step) { switch (step) {
case 1: case 1:
// initialize serial interface on the MCU side, auto baud rate settings // initialize serial interface on the MCU side, auto baud rate settings
GUI.log('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 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
self.send([0x7F], 1, function(reply) { self.send([0x7F], 1, function(reply) {
@ -349,7 +343,7 @@ STM32_protocol.prototype.upload_procedure = function(step) {
self.upload_procedure(2); self.upload_procedure(2);
} else { } else {
GUI.interval_remove('stm32_initialize_mcu'); GUI.interval_remove('stm32_initialize_mcu');
STM32.GUI_status('STM32 Communication with bootloader <span style="color: red">failed</span>'); GUI.log('Communication with bootloader <span style="color: red">failed</span>');
// disconnect // disconnect
self.upload_procedure(99); self.upload_procedure(99);
@ -396,10 +390,11 @@ STM32_protocol.prototype.upload_procedure = function(step) {
break; break;
case 4: case 4:
// erase memory // erase memory
GUI.log('Erasing ...');
if (!$('input.erase_chip').is(':checked')) { if (!$('input.erase_chip').is(':checked')) {
// EXPERIMENTAL // EXPERIMENTAL
console.log('Executing local erase (only needed pages)'); console.log('Executing local erase (only needed pages)');
STM32.GUI_status('Erasing');
self.send([self.command.erase, 0xBC], 1, function(reply) { // 0x43 ^ 0xFF self.send([self.command.erase, 0xBC], 1, function(reply) { // 0x43 ^ 0xFF
if (self.verify_response(self.status.ACK, reply)) { if (self.verify_response(self.status.ACK, reply)) {
@ -419,9 +414,6 @@ STM32_protocol.prototype.upload_procedure = function(step) {
self.send(buff, 1, function(reply) { self.send(buff, 1, function(reply) {
if (self.verify_response(self.status.ACK, reply)) { if (self.verify_response(self.status.ACK, reply)) {
console.log('Erasing: done'); console.log('Erasing: done');
console.log('Writing data ...');
STM32.GUI_status('<span style="color: green">Flashing ...</span>');
// proceed to next step // proceed to next step
self.upload_procedure(5); self.upload_procedure(5);
} }
@ -430,16 +422,12 @@ STM32_protocol.prototype.upload_procedure = function(step) {
}); });
} else { } else {
console.log('Executing global chip erase'); console.log('Executing global chip erase');
STM32.GUI_status('Erasing');
self.send([self.command.erase, 0xBC], 1, function(reply) { // 0x43 ^ 0xFF self.send([self.command.erase, 0xBC], 1, function(reply) { // 0x43 ^ 0xFF
if (self.verify_response(self.status.ACK, reply)) { if (self.verify_response(self.status.ACK, reply)) {
self.send([0xFF, 0x00], 1, function(reply) { self.send([0xFF, 0x00], 1, function(reply) {
if (self.verify_response(self.status.ACK, reply)) { if (self.verify_response(self.status.ACK, reply)) {
console.log('Erasing: done'); console.log('Erasing: done');
console.log('Writing data ...');
STM32.GUI_status('<span style="color: green">Flashing ...</span>');
// proceed to next step // proceed to next step
self.upload_procedure(5); self.upload_procedure(5);
} }
@ -450,6 +438,9 @@ STM32_protocol.prototype.upload_procedure = function(step) {
break; break;
case 5: case 5:
// upload // upload
console.log('Writing data ...');
GUI.log('Flashing ...');
var blocks = self.hex.data.length - 1; var blocks = self.hex.data.length - 1;
var flashing_block = 0; var flashing_block = 0;
var address = self.hex.data[flashing_block].address; var address = self.hex.data[flashing_block].address;
@ -484,7 +475,7 @@ STM32_protocol.prototype.upload_procedure = function(step) {
array_out[array_out.length - 1] = checksum; // checksum (last byte in the array_out array) array_out[array_out.length - 1] = checksum; // checksum (last byte in the array_out array)
address += bytes_to_write; address += bytes_to_write;
bytes_flashed_total += bytes_to_write bytes_flashed_total += bytes_to_write;
self.send(array_out, 1, function(reply) { self.send(array_out, 1, function(reply) {
if (self.verify_response(self.status.ACK, reply)) { if (self.verify_response(self.status.ACK, reply)) {
@ -511,8 +502,6 @@ STM32_protocol.prototype.upload_procedure = function(step) {
} else { } else {
// all blocks flashed // all blocks flashed
console.log('Writing: done'); console.log('Writing: done');
console.log('Verifying data ...');
STM32.GUI_status('<span style="color: green">Verifying ...</span>');
// proceed to next step // proceed to next step
self.upload_procedure(6); self.upload_procedure(6);
@ -525,6 +514,9 @@ STM32_protocol.prototype.upload_procedure = function(step) {
break; break;
case 6: case 6:
// verify // verify
console.log('Verifying data ...');
GUI.log('Verifying ...');
var blocks = self.hex.data.length - 1; var blocks = self.hex.data.length - 1;
var reading_block = 0; var reading_block = 0;
var address = self.hex.data[reading_block].address; var address = self.hex.data[reading_block].address;
@ -596,7 +588,8 @@ STM32_protocol.prototype.upload_procedure = function(step) {
if (verify) { if (verify) {
console.log('Programming: SUCCESSFUL'); console.log('Programming: SUCCESSFUL');
STM32.GUI_status('Programming: <strong style="color: green">SUCCESSFUL</strong>'); GUI.log('Programming: <strong style="color: green">SUCCESSFUL</strong>');
ga_tracker.sendEvent('Flashing', 'Programming', 'success');
// update progress bar // update progress bar
self.progress_bar_e.addClass('valid'); self.progress_bar_e.addClass('valid');
@ -605,7 +598,8 @@ STM32_protocol.prototype.upload_procedure = function(step) {
self.upload_procedure(7); self.upload_procedure(7);
} else { } else {
console.log('Programming: FAILED'); console.log('Programming: FAILED');
STM32.GUI_status('Programming: <strong style="color: red">FAILED</strong>'); GUI.log('Programming: <strong style="color: red">FAILED</strong>');
ga_tracker.sendEvent('Flashing', 'Programming', 'fail');
// update progress bar // update progress bar
self.progress_bar_e.addClass('invalid'); self.progress_bar_e.addClass('invalid');

475
js/stm32dfu.js Normal file
View File

@ -0,0 +1,475 @@
/*
USB DFU uses:
control transfers for communicating
recipient is interface
request type is class
Descriptors seems to be broken in current chrome.usb API implementation (writing this while using canary 37.0.2040.0
General rule to remember is that DFU doesn't like running specific operations while the device isn't in idle state
that being said, it seems that certain level of CLRSTATUS is required before running another type of operation for
example switching from DNLOAD to UPLOAD, etc, clearning the state so device is in dfuIDLE is highly recommended.
*/
var STM32DFU_protocol = function() {
this.hex; // ref
this.verify_hex;
this.handle = null; // connection handle
this.request = {
DETACH: 0x00, // OUT, Requests the device to leave DFU mode and enter the application.
DNLOAD: 0x01, // OUT, Requests data transfer from Host to the device in order to load them into device internal Flash. Includes also erase commands
UPLOAD: 0x02, // IN, Requests data transfer from device to Host in order to load content of device internal Flash into a Host file.
GETSTATUS: 0x03, // IN, Requests device to send status report to the Host (including status resulting from the last request execution and the state the device will enter immediately after this request).
CLRSTATUS: 0x04, // OUT, Requests device to clear error status and move to next step
GETSTATE: 0x05, // IN, Requests the device to send only the state it will enter immediately after this request.
ABORT: 0x06 // OUT, Requests device to exit the current state/operation and enter idle state immediately.
};
this.status = {
OK: 0x00, // No error condition is present.
errTARGET: 0x01, // File is not targeted for use by this device.
errFILE: 0x02, // File is for this device but fails some vendor-specific verification test
errWRITE: 0x03, // Device is unable to write memory.
errERASE: 0x04, // Memory erase function failed.
errCHECK_ERASED: 0x05, // Memory erase check failed.
errPROG: 0x06, // Program memory function failed.
errVERIFY: 0x07, // Programmed memory failed verification.
errADDRESS: 0x08, // Cannot program memory due to received address that is out of range.
errNOTDONE: 0x09, // Received DFU_DNLOAD with wLength = 0, but device does not think it has all of the data yet.
errFIRMWARE: 0x0A, // Device's firmware is corrupt. It cannot return to run-time (non-DFU) operations.
errVENDOR: 0x0B, // iString indicates a vendor-specific error.
errUSBR: 0x0C, // Device detected unexpected USB reset signaling.
errPOR: 0x0D, // Device detected unexpected power on reset.
errUNKNOWN: 0x0E, // Something went wrong, but the device does not know what it was.
errSTALLEDPKT: 0x0F // Device stalled an unexpected request.
};
this.state = {
appIDLE: 0, // Device is running its normal application.
appDETACH: 1, // Device is running its normal application, has received the DFU_DETACH request, and is waiting for a USB reset.
dfuIDLE: 2, // Device is operating in the DFU mode and is waiting for requests.
dfuDNLOAD_SYNC: 3, // Device has received a block and is waiting for the host to solicit the status via DFU_GETSTATUS.
dfuDNBUSY: 4, // Device is programming a control-write block into its nonvolatile memories.
dfuDNLOAD_IDLE: 5, // Device is processing a download operation. Expecting DFU_DNLOAD requests.
dfuMANIFEST_SYNC: 6, // Device has received the final block of firmware from the host and is waiting for receipt of DFU_GETSTATUS to begin the Manifestation phase; or device has completed the Manifestation phase and is waiting for receipt of DFU_GETSTATUS.
dfuMANIFEST: 7, // Device is in the Manifestation phase. (Not all devices will be able to respond to DFU_GETSTATUS when in this state.)
dfuMANIFEST_WAIT_RESET: 8, // Device has programmed its memories and is waiting for a USB reset or a power on reset. (Devices that must enter this state clear bitManifestationTolerant to 0.)
dfuUPLOAD_IDLE: 9, // The device is processing an upload operation. Expecting DFU_UPLOAD requests.
dfuERROR: 10 // An error has occurred. Awaiting the DFU_CLRSTATUS request.
};
};
STM32DFU_protocol.prototype.connect = function(hex) {
var self = this;
self.hex = hex;
// reset and set some variables before we start
self.upload_time_start = microtime();
self.verify_hex = [];
// reset progress bar to initial state
self.progress_bar_e = $('.progress');
self.progress_bar_e.val(0);
self.progress_bar_e.removeClass('valid invalid');
chrome.usb.getDevices(usbDevices.STM32DFU, function(result) {
if (result.length) {
console.log('USB DFU detected with ID: ' + result[0].device);
self.openDevice(result[0]);
} else {
// TODO: throw some error
}
});
};
STM32DFU_protocol.prototype.openDevice = function(device) {
var self = this;
chrome.usb.openDevice(device, function(handle) {
self.handle = handle;
console.log('Device opened with Handle ID: ' + handle.handle);
self.claimInterface(0);
});
};
STM32DFU_protocol.prototype.closeDevice = function() {
var self = this;
chrome.usb.closeDevice(this.handle, function closed() {
console.log('Device closed with Handle ID: ' + self.handle.handle);
self.handle = null;
});
};
STM32DFU_protocol.prototype.claimInterface = function(interfaceNumber) {
var self = this;
chrome.usb.claimInterface(this.handle, interfaceNumber, function claimed() {
console.log('Claimed interface: ' + interfaceNumber);
self.upload_procedure(1);
});
};
STM32DFU_protocol.prototype.releaseInterface = function(interfaceNumber) {
var self = this;
chrome.usb.releaseInterface(this.handle, interfaceNumber, function released() {
console.log('Released interface: ' + interfaceNumber);
self.closeDevice();
});
};
STM32DFU_protocol.prototype.resetDevice = function(callback) {
chrome.usb.resetDevice(this.handle, function(result) {
console.log('Reset Device: ' + result);
if (callback) callback();
});
};
STM32DFU_protocol.prototype.controlTransfer = function(direction, request, value, interface, length, data, callback) {
if (direction == 'in') {
// data is ignored
chrome.usb.controlTransfer(this.handle, {
'direction': 'in',
'recipient': 'interface',
'requestType': 'class',
'request': request,
'value': value,
'index': interface,
'length': length
}, function(result) {
if (result.resultCode) console.log(result.resultCode);
var buf = new Uint8Array(result.data);
callback(buf, result.resultCode);
});
} else {
// length is ignored
if (data) {
var arrayBuf = new ArrayBuffer(data.length);
var arrayBufView = new Uint8Array(arrayBuf);
arrayBufView.set(data);
} else {
var arrayBuf = new ArrayBuffer(0);
}
chrome.usb.controlTransfer(this.handle, {
'direction': 'out',
'recipient': 'interface',
'requestType': 'class',
'request': request,
'value': value,
'index': interface,
'data': arrayBuf
}, function(result) {
if (result.resultCode) console.log(result.resultCode);
callback(result);
});
}
};
// routine calling DFU_CLRSTATUS until device is in dfuIDLE state
STM32DFU_protocol.prototype.clearStatus = function(callback) {
var self = this;
function check_status() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuIDLE) {
callback(data);
} else {
var delay = data[1] | (data[2] << 8) | (data[3] << 16);
setTimeout(clear_status, delay);
}
});
}
function clear_status() {
self.controlTransfer('out', self.request.CLRSTATUS, 0, 0, 0, 0, check_status);
}
check_status();
};
STM32DFU_protocol.prototype.loadAddress = function(address, callback) {
var self = this;
self.controlTransfer('out', self.request.DNLOAD, 0, 0, 0, [0x21, address, (address >> 8), (address >> 16), (address >> 24)], function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuDNBUSY) {
var delay = data[1] | (data[2] << 8) | (data[3] << 16);
setTimeout(function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuDNLOAD_IDLE) {
callback(data);
} else {
console.log('Failed to execure address load');
self.upload_procedure(99);
}
});
}, delay);
} else {
console.log('Failed to request address load');
self.upload_procedure(99);
}
});
});
};
// first_array = usually hex_to_flash array
// second_array = usually verify_hex array
// result = true/false
STM32DFU_protocol.prototype.verify_flash = function(first_array, second_array) {
for (var i = 0; i < first_array.length; i++) {
if (first_array[i] != second_array[i]) {
console.log('Verification failed on byte: ' + i + ' expected: 0x' + first_array[i].toString(16) + ' received: 0x' + second_array[i].toString(16));
return false;
}
}
console.log('Verification successful, matching: ' + first_array.length + ' bytes');
return true;
};
STM32DFU_protocol.prototype.upload_procedure = function(step) {
var self = this;
switch (step) {
case 1:
self.clearStatus(function() {
self.upload_procedure(2);
});
break;
case 2:
// full chip erase
console.log('Executing global chip erase');
GUI.log('Erasing ...');
self.controlTransfer('out', self.request.DNLOAD, 0, 0, 0, [0x41], function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuDNBUSY) { // completely normal
var delay = data[1] | (data[2] << 8) | (data[3] << 16);
setTimeout(function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuDNLOAD_IDLE) {
self.upload_procedure(4);
} else {
console.log('Failed to execute global chip erase');
self.upload_procedure(99);
}
});
}, delay);
} else {
console.log('Failed to initiate global chip erase');
self.upload_procedure(99);
}
});
});
break;
case 4:
// upload
// we dont need to clear the state as we are already using DFU_DNLOAD
console.log('Writing data ...');
GUI.log('Flashing ...');
var blocks = self.hex.data.length - 1;
var flashing_block = 0;
var address = self.hex.data[flashing_block].address;
var bytes_flashed = 0;
var bytes_flashed_total = 0; // used for progress bar
var wBlockNum = 2; // required by DFU
// start
self.loadAddress(address, write);
function write() {
if (bytes_flashed < self.hex.data[flashing_block].bytes) {
var bytes_to_write = ((bytes_flashed + 2048) <= self.hex.data[flashing_block].bytes) ? 2048 : (self.hex.data[flashing_block].bytes - bytes_flashed);
var data_to_flash = self.hex.data[flashing_block].data.slice(bytes_flashed, bytes_flashed + bytes_to_write);
address += bytes_to_write;
bytes_flashed += bytes_to_write;
bytes_flashed_total += bytes_to_write;
self.controlTransfer('out', self.request.DNLOAD, wBlockNum++, 0, 0, data_to_flash, function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuDNBUSY) {
var delay = data[1] | (data[2] << 8) | (data[3] << 16);
setTimeout(function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
if (data[4] == self.state.dfuDNLOAD_IDLE) {
// update progress bar
self.progress_bar_e.val(bytes_flashed_total / (self.hex.bytes_total * 2) * 100);
// flash another page
write();
} else {
console.log('Failed to write ' + bytes_to_write + 'bytes to 0x' + address.toString(16));
self.upload_procedure(99);
}
});
}, delay);
} else {
console.log('Failed to initiate write ' + bytes_to_write + 'bytes to 0x' + address.toString(16));
self.upload_procedure(99);
}
});
})
} else {
if (flashing_block < blocks) {
// move to another block
flashing_block++;
address = self.hex.data[flashing_block].address;
bytes_flashed = 0;
wBlockNum = 2;
self.loadAddress(address, write);
} else {
// all blocks flashed
console.log('Writing: done');
// proceed to next step
self.upload_procedure(5);
}
}
}
break;
case 5:
// verify
console.log('Verifying data ...');
GUI.log('Verifying ...');
var blocks = self.hex.data.length - 1;
var reading_block = 0;
var address = self.hex.data[reading_block].address;
var bytes_verified = 0;
var bytes_verified_total = 0; // used for progress bar
var wBlockNum = 2; // required by DFU
// initialize arrays
for (var i = 0; i <= blocks; i++) {
self.verify_hex.push([]);
}
// start
self.clearStatus(function() {
self.loadAddress(address, function() {
self.clearStatus(read);
});
});
function read() {
if (bytes_verified < self.hex.data[reading_block].bytes) {
var bytes_to_read = ((bytes_verified + 2048) <= self.hex.data[reading_block].bytes) ? 2048 : (self.hex.data[reading_block].bytes - bytes_verified);
self.controlTransfer('in', self.request.UPLOAD, wBlockNum++, 0, bytes_to_read, 0, function(data, code) {
for (var i = 0; i < data.length; i++) {
self.verify_hex[reading_block].push(data[i]);
}
address += bytes_to_read;
bytes_verified += bytes_to_read;
bytes_verified_total += bytes_to_read;
// update progress bar
self.progress_bar_e.val((self.hex.bytes_total + bytes_verified_total) / (self.hex.bytes_total * 2) * 100);
// verify another page
read();
});
} else {
if (reading_block < blocks) {
// move to another block
reading_block++;
address = self.hex.data[reading_block].address;
bytes_verified = 0;
wBlockNum = 2;
self.clearStatus(function() {
self.loadAddress(address, function() {
self.clearStatus(read);
});
});
} else {
// all blocks read, verify
var verify = true;
for (var i = 0; i <= blocks; i++) {
verify = self.verify_flash(self.hex.data[i].data, self.verify_hex[i]);
if (!verify) break;
}
if (verify) {
console.log('Programming: SUCCESSFUL');
GUI.log('Programming: <strong style="color: green">SUCCESSFUL</strong>');
ga_tracker.sendEvent('Flashing', 'Programming', 'success');
// update progress bar
self.progress_bar_e.addClass('valid');
// proceed to next step
self.upload_procedure(6);
} else {
console.log('Programming: FAILED');
GUI.log('Programming: <strong style="color: red">FAILED</strong>');
ga_tracker.sendEvent('Flashing', 'Programming', 'fail');
// update progress bar
self.progress_bar_e.addClass('invalid');
// disconnect
self.upload_procedure(99);
}
}
}
}
break;
case 6:
// jump to application code
var address = self.hex.data[0].address;
self.clearStatus(function() {
self.loadAddress(address, leave);
});
function leave() {
self.controlTransfer('out', self.request.DNLOAD, 0, 0, 0, 0, function() {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function(data) {
self.upload_procedure(99);
});
});
}
// start
clear_before_leave();
break;
case 99:
// cleanup
console.log('Script finished after: ' + (microtime() - self.upload_time_start).toFixed(4) + ' seconds');
self.releaseInterface(0);
break;
}
};
// initialize object
var STM32DFU = new STM32DFU_protocol();

32
js/usb.js Normal file
View File

@ -0,0 +1,32 @@
var usbDevices = {
STM32DFU: {'vendorId': 1155, 'productId': 57105}
};
var usbPermissions = {permissions: [{'usbDevices': [usbDevices.STM32DFU]}]};
function check_usb_permissions(callback) {
chrome.permissions.contains(usbPermissions, function(result) {
if (result) {
GUI.optional_usb_permissions = true;
} else {
console.log('Optional USB permissions: missing');
GUI.log(chrome.i18n.getMessage('please_grant_usb_permissions'));
// display optional usb permissions request box
$('div.optional_permissions').show();
// UI hooks
document.getElementById("requestOptionalPermissions").addEventListener('click', function() {
chrome.permissions.request(usbPermissions, function(result) {
if (result) {
GUI.log(chrome.i18n.getMessage('usb_permissions_granted'));
$('div.optional_permissions').hide();
GUI.optional_usb_permissions = true;
}
});
});
}
if (callback) callback();
});
}

View File

@ -25,6 +25,7 @@
<script type="text/javascript" src="./js/port_handler.js"></script> <script type="text/javascript" src="./js/port_handler.js"></script>
<script type="text/javascript" src="./js/port_usage.js"></script> <script type="text/javascript" src="./js/port_usage.js"></script>
<script type="text/javascript" src="./js/serial.js"></script> <script type="text/javascript" src="./js/serial.js"></script>
<script type="text/javascript" src="./js/usb.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/request_balancer.js"></script> <script type="text/javascript" src="./js/request_balancer.js"></script>
<script type="text/javascript" src="./js/serial_backend.js"></script> <script type="text/javascript" src="./js/serial_backend.js"></script>
@ -32,6 +33,7 @@
<script type="text/javascript" src="./js/msp.js"></script> <script type="text/javascript" src="./js/msp.js"></script>
<script type="text/javascript" src="./js/backup_restore.js"></script> <script type="text/javascript" src="./js/backup_restore.js"></script>
<script type="text/javascript" src="./js/stm32.js"></script> <script type="text/javascript" src="./js/stm32.js"></script>
<script type="text/javascript" src="./js/stm32dfu.js"></script>
<script type="text/javascript" src="./js/localization.js"></script> <script type="text/javascript" src="./js/localization.js"></script>
<script type="text/javascript" src="./main.js"></script> <script type="text/javascript" src="./main.js"></script>
@ -121,6 +123,9 @@
<div> <div>
<span i18n="statusbar_packet_error"></span> <span class="packet-error">0</span> <span i18n="statusbar_packet_error"></span> <span class="packet-error">0</span>
</div> </div>
<div>
<span i18n="statusbar_i2c_error"></span> <span class="i2c-error">0</span>
</div>
<div> <div>
<span i18n="statusbar_cycle_time"></span> <span class="cycle-time">0</span> <span i18n="statusbar_cycle_time"></span> <span class="cycle-time">0</span>
</div> </div>

19
main.js
View File

@ -46,18 +46,17 @@ $(document).ready(function() {
break; break;
} }
GUI.log('Are you using ESCs with SimonK firmware? Try <a href="https://chrome.google.com/webstore/detail/rapidflash/gehadojofkekobiohnefkabgimeniglh" target="_blank">RapidFlash</a>, our new utility for configuring / flashing / updating firmware.');
// Tabs // Tabs
var tabs = $('#tabs > ul'); var tabs = $('#tabs > ul');
$('a', tabs).click(function() { $('a', tabs).click(function() {
if ($(this).parent().hasClass('active') == false) { // only initialize when the tab isn't already active if ($(this).parent().hasClass('active') == false) { // only initialize when the tab isn't already active
var self = this; var self = this;
var index = $(self).parent().index(); var index = $(self).parent().index();
var tab = $(self).parent().prop('class');
// if there is no active connection, return // if there is no active connection, return
if (configuration_received == false) { if (!configuration_received && tab != 'tab_logging') {
GUI.log('You need to connect before you can view any of the tabs', 'red'); GUI.log('You need to <strong>connect</strong> before you can view any of the tabs');
return; return;
} }
@ -65,9 +64,6 @@ $(document).ready(function() {
// disable previously active tab highlight // disable previously active tab highlight
$('li', tabs).removeClass('active'); $('li', tabs).removeClass('active');
// get tab class name (there should be only one class listed)
var tab = $(self).parent().prop('class');
// Highlight selected tab // Highlight selected tab
$(self).parent().addClass('active'); $(self).parent().addClass('active');
@ -174,7 +170,7 @@ $(document).ready(function() {
$("#content").on('keydown', 'input[type="number"]', function(e) { $("#content").on('keydown', 'input[type="number"]', function(e) {
// whitelist all that we need for numeric control // 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 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 == 8 || e.keyCode == 46) { // backspace and delete
} else if (e.keyCode == 190 || e.keyCode == 110) { // allow and decimal point } 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 } else if ((e.keyCode >= 37 && e.keyCode <= 40) || e.keyCode == 13) { // allow arrows, enter
@ -238,6 +234,13 @@ function millitime() {
return now; 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() { function add_custom_spinners() {
var spinner_element = '<div class="spinner"><div class="up"></div><div class="down"></div></div>'; var spinner_element = '<div class="spinner"><div class="up"></div><div class="down"></div></div>';

View File

@ -1,7 +1,7 @@
{ {
"manifest_version": 2, "manifest_version": 2,
"minimum_chrome_version": "33", "minimum_chrome_version": "33",
"version": "0.41", "version": "0.45",
"author": "Hydra", "author": "Hydra",
"name": "Cleanflight - Configurator", "name": "Cleanflight - Configurator",
@ -23,6 +23,7 @@
"https://*.github.com/", "https://*.github.com/",
"https://*.githubusercontent.com/", "https://*.githubusercontent.com/",
"serial", "serial",
"usb",
"storage", "storage",
"fileSystem", "fileSystem",
"fileSystem.write", "fileSystem.write",
@ -30,6 +31,12 @@
"notifications" "notifications"
], ],
"optional_permissions": [
{"usbDevices": [
{"vendorId": 1155, "productId": 57105}
]}
],
"icons": { "icons": {
"128": "images/icon_128.png" "128": "images/icon_128.png"
} }

View File

@ -40,12 +40,16 @@
border: 0; border: 0;
background-color: white; background-color: white;
} }
.tab-auxiliary_configuration .buttons {
width: calc(100% - 20px);
position: absolute;
bottom: 10px;
}
.tab-auxiliary_configuration .update { .tab-auxiliary_configuration .update {
display: block; display: block;
float: right; float: right;
margin-top: 10px;
height: 28px; height: 28px;
line-height: 28px; line-height: 28px;
@ -59,7 +63,4 @@
} }
.tab-auxiliary_configuration .update:hover { .tab-auxiliary_configuration .update:hover {
background-color: #dedcdc; background-color: #dedcdc;
}
.tab-auxiliary_configuration .update.success {
border: 1px solid #43c84d;
} }

View File

@ -2,42 +2,12 @@
<table class="boxes"> <table class="boxes">
<tr class="heads"> <tr class="heads">
<th style="width: 18%"></th> <th style="width: 18%"></th>
<th class="channel" colspan="3">AUX 1</th>
<th class="channel" colspan="3">AUX 2</th>
<th class="channel" colspan="3">AUX 3</th>
<th class="channel" colspan="3">AUX 4</th>
<th class="channel" colspan="3">AUX 5</th>
<th class="channel" colspan="3">AUX 6</th>
<th class="channel" colspan="3">AUX 7</th>
<th class="channel" colspan="3">AUX 8</th>
</tr> </tr>
<tr class="main"> <tr class="main">
<th i18n="auxiliaryName"></th> <th i18n="auxiliaryName"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
<th class="toggle" i18n="auxiliaryLow"></th>
<th class="toggle" i18n="auxiliaryMed"></th>
<th class="toggle" i18n="auxiliaryHigh"></th>
</tr> </tr>
</table> </table>
<a class="update" href="#" i18n="auxiliaryButtonSave"></a> <div class="buttons">
<a class="update" href="#" i18n="auxiliaryButtonSave"></a>
</div>
</div> </div>

View File

@ -1,3 +1,4 @@
// TODO: rework box_highlight & update_ui to accept flexible amount of aux channels
function tab_initialize_auxiliary_configuration() { function tab_initialize_auxiliary_configuration() {
ga_tracker.sendAppView('Auxiliary Configuration'); ga_tracker.sendAppView('Auxiliary Configuration');
GUI.active_tab = '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); MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data);
function 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() { function load_html() {
@ -13,71 +18,48 @@ function tab_initialize_auxiliary_configuration() {
} }
function process_html() { 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('<th colspan="3">AUX ' + (i + 1) + '</th>');
// 3 columns per aux channel (this might be requested to change to 6 in the future, so watch out)
main_head.append('\
<th i18n="auxiliaryLow"></th>\
<th i18n="auxiliaryMed"></th>\
<th i18n="auxiliaryHigh"></th>\
');
}
// translate to user-selected language // translate to user-selected language
localize(); localize();
function box_check(num, pos) {
if (bit_check(num, pos)) { // 1
return '<td><input type="checkbox" checked="checked" /></td>';
} else { // 0
return '<td><input type="checkbox" /></td>';
}
}
// 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 // generate table from the supplied AUX names and AUX data
for (var i = 0; i < AUX_CONFIG.length; i++) { for (var i = 0; i < AUX_CONFIG.length; i++) {
$('.boxes > tbody:last').append( var line = '<tr class="switches">';
'<tr class="switches">' + line += '<td class="name">' + AUX_CONFIG[i] + '</td>';
'<td class="name">' + AUX_CONFIG[i] + '</td>' +
box_check(AUX_CONFIG_values[i], 0) +
box_check(AUX_CONFIG_values[i], 1) +
box_check(AUX_CONFIG_values[i], 2) +
box_check(AUX_CONFIG_values[i], 3) + var bitIndex = 0;
box_check(AUX_CONFIG_values[i], 4) + var chunks = 1;
box_check(AUX_CONFIG_values[i], 5) + 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 += '<td><input type="checkbox" checked="checked" /></td>';
} else {
line += '<td><input type="checkbox" /></td>';
}
}
bitIndex += 16 - (4 * 3);
}
line += '</tr>';
box_check(AUX_CONFIG_values[i], 6) + $('.boxes > tbody:last').append(line);
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) +
'</tr>'
);
} }
// UI Hooks // UI Hooks
@ -112,18 +94,17 @@ function tab_initialize_auxiliary_configuration() {
} }
}); });
// send over the data // send over data
var AUX_val_buffer_out = new Array(); // current code will only handle 4 AUX as the variable length is 16bits
var AUX_val_buffer_out = [];
var needle = 0;
for (var i = 0; i < AUX_CONFIG_values.length; i++) { 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.push(lowByte(AUX_CONFIG_values[i] & 0xFFF));
AUX_val_buffer_out[needle++] = highByte(AUX_CONFIG_values[i] & 0xFFF); AUX_val_buffer_out.push(highByte(AUX_CONFIG_values[i] & 0xFFF));
} }
if (bit_check(CONFIG.capability, 5)) { if (bit_check(CONFIG.capability, 5)) {
for (var i = 0; i < AUX_CONFIG_values.length; i++) { 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.push(lowByte((AUX_CONFIG_values[i] >> 16) & 0xFFF));
AUX_val_buffer_out[needle++] = highByte((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() { function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
GUI.log(chrome.i18n.getMessage('auxiliaryEepromSaved')); 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 // data pulling functions used inside interval timer
function get_rc_data() { function get_rc_data() {
MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); 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'); $('td.name').eq(i).addClass('off');
} }
} }
} }
box_highlight(RC.channels[4], 2); // aux 1 for (var i = 0; i < (RC.active_channels - 4); i++) {
box_highlight(RC.channels[5], 5); // aux 2 box_highlight(i, RC.channels[i + 4]);
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
}
} }
// update ui instantly on first load
update_ui();
// enable data pulling // 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 // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function() { GUI.interval_add('status_pull', function() {

View File

@ -1,3 +1,6 @@
var CLI_active = false;
var CLI_valid = false;
var CliHistory = function () { var CliHistory = function () {
this.history = []; this.history = [];
this.index = 0; this.index = 0;

View File

@ -8,6 +8,45 @@
width: calc(40% - 10px); 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 { .welcome {
margin-bottom: 10px; margin-bottom: 10px;

View File

@ -1,5 +1,12 @@
<div class="tab-default"> <div class="tab-default">
<div class="left"> <div class="left">
<div class="optional_permissions">
<div class="title" i18n="default_optional_permissions_head"></div>
<p i18n="default_optional_permissions_text">
</p>
<a id="requestOptionalPermissions" href="#" i18n="default_request_optional_permissions"></a>
<div class="clear-both"></div>
</div>
<div class="welcome" i18n="defaultWelcomeText"> <div class="welcome" i18n="defaultWelcomeText">
</div> </div>
<div class="donate"> <div class="donate">

View File

@ -2,6 +2,8 @@ function tab_initialize_default() {
GUI.active_tab = 'default'; GUI.active_tab = 'default';
$('#content').load("./tabs/default.html", function() { $('#content').load("./tabs/default.html", function() {
//check_usb_permissions(); // temporary enabled in dev branch, should be commented out untill DFU support goes live
// translate to user-selected language // translate to user-selected language
localize(); localize();
@ -10,5 +12,9 @@ function tab_initialize_default() {
// UI Hooks // UI Hooks
$('a.firmware_flasher').click(tab_initialize_firmware_flasher); $('a.firmware_flasher').click(tab_initialize_firmware_flasher);
$('div.welcome a').click(function() {
ga_tracker.sendEvent('ExternalUrls', 'Click', $(this).prop('href'));
});
}); });
} }

View File

@ -27,10 +27,17 @@
.tab-firmware_flasher .note p { .tab-firmware_flasher .note p {
margin-bottom: 5px; margin-bottom: 5px;
} }
.tab-firmware_flasher .note input { .tab-firmware_flasher .note label {
float: left;
}
.tab-firmware_flasher .note label input {
float: left; float: left;
margin-top: 2px; margin-top: 2px;
} }
.tab-firmware_flasher .note label span {
font-weight: bold;
margin-left: 6px;
}
.tab-firmware_flasher .note .flash_on_connect_wrapper { .tab-firmware_flasher .note .flash_on_connect_wrapper {
display: none; display: none;
} }

View File

@ -2,7 +2,6 @@
<div class="info"> <div class="info">
<strong i18n="firmwareFlasherPath"></strong><span class="path">empty</span><br /> <strong i18n="firmwareFlasherPath"></strong><span class="path">empty</span><br />
<strong i18n="firmwareFlasherSize"></strong><span class="size">0 bytes</span><br /> <strong i18n="firmwareFlasherSize"></strong><span class="size">0 bytes</span><br />
<strong i18n="firmwareFlasherStatus"></strong><span class="status">Firmware not loaded</span><br />
<strong i18n="firmwareFlasherProgress"></strong><progress class="progress" value="0" min="0" max="100"></progress> <strong i18n="firmwareFlasherProgress"></strong><progress class="progress" value="0" min="0" max="100"></progress>
</div> </div>
<div class="note"> <div class="note">
@ -10,16 +9,19 @@
</p> </p>
<label> <label>
<input class="updating" type="checkbox" /> <input class="updating" type="checkbox" />
<span style="font-weight: bold; margin-left: 6px" i18n="firmwareFlasherNoReboot"></span> <span i18n="firmwareFlasherNoReboot"></span>
</label><br /> </label>
<div class="clear-both"></div>
<label class="flash_on_connect_wrapper"> <label class="flash_on_connect_wrapper">
<input class="flash_on_connect" type="checkbox" /> <input class="flash_on_connect" type="checkbox" />
<span style="font-weight: bold; margin-left: 6px" i18n="firmwareFlasherFlashOnConnect"></span><br /> <span i18n="firmwareFlasherFlashOnConnect"></span><br />
</label> </label>
<div class="clear-both"></div>
<label> <label>
<input class="erase_chip" type="checkbox" /> <input class="erase_chip" type="checkbox" />
<span style="font-weight: bold; margin-left: 6px" i18n="firmwareFlasherFullChipErase"></span> <span i18n="firmwareFlasherFullChipErase"></span>
</label><br /> </label>
<div class="clear-both"></div>
</div> </div>
<div class="clear-both"></div> <div class="clear-both"></div>
<div class="git_info"> <div class="git_info">

View File

@ -46,12 +46,13 @@ function tab_initialize_firmware_flasher() {
parsed_hex = data; parsed_hex = data;
if (parsed_hex) { if (parsed_hex) {
STM32.GUI_status(chrome.i18n.getMessage('firmwareFlasherFirmwareLoaded')); GUI.log(chrome.i18n.getMessage('firmwareFlasherLocalFirmwareLoaded'));
ga_tracker.sendEvent('Flashing', 'Firmware', 'local');
$('a.flash_firmware').removeClass('locked'); $('a.flash_firmware').removeClass('locked');
$('span.size').html(parsed_hex.bytes_total + ' bytes'); $('span.size').html(parsed_hex.bytes_total + ' bytes');
} else { } else {
STM32.GUI_status(chrome.i18n.getMessage('firmwareFlasherHexCorrupted')); GUI.log(chrome.i18n.getMessage('firmwareFlasherHexCorrupted'));
} }
}); });
} }
@ -71,17 +72,18 @@ function tab_initialize_firmware_flasher() {
parsed_hex = data; parsed_hex = data;
if (parsed_hex) { if (parsed_hex) {
STM32.GUI_status(chrome.i18n.getMessage('firmwareFlasherRemoteFirmwareLoaded')); GUI.log(chrome.i18n.getMessage('firmwareFlasherRemoteFirmwareLoaded'));
ga_tracker.sendEvent('Flashing', 'Firmware', 'online');
$('a.flash_firmware').removeClass('locked'); $('a.flash_firmware').removeClass('locked');
$('span.path').text('Using remote Firmware'); $('span.path').text('Using remote Firmware');
$('span.size').text(parsed_hex.bytes_total + ' bytes'); $('span.size').text(parsed_hex.bytes_total + ' bytes');
} else { } else {
STM32.GUI_status(chrome.i18n.getMessage('firmwareFlasherHexCorrupted')); GUI.log(chrome.i18n.getMessage('firmwareFlasherHexCorrupted'));
} }
}); });
}).fail(function() { }).fail(function() {
STM32.GUI_status(chrome.i18n.getMessage('firmwareFlasherFailedToLoadOnlineFirmware')); GUI.log(chrome.i18n.getMessage('firmwareFlasherFailedToLoadOnlineFirmware'));
$('a.flash_firmware').addClass('locked'); $('a.flash_firmware').addClass('locked');
}); });
@ -103,9 +105,13 @@ function tab_initialize_firmware_flasher() {
if (!$(this).hasClass('locked')) { if (!$(this).hasClass('locked')) {
if (!GUI.connect_lock) { // button disabled while flashing is in progress if (!GUI.connect_lock) { // button disabled while flashing is in progress
if (parsed_hex != false) { if (parsed_hex != false) {
STM32.connect(parsed_hex); if (String($('div#port-picker #port').val()) != 'DFU') {
STM32.connect(parsed_hex);
} else {
STM32DFU.connect(parsed_hex);
}
} else { } else {
STM32.GUI_status(chrome.i18n.getMessage('firmwareFlasherFirmwareNotLoaded')); GUI.log(chrome.i18n.getMessage('firmwareFlasherFirmwareNotLoaded'));
} }
} }
} }

View File

@ -309,16 +309,21 @@
margin-left: 100px; margin-left: 100px;
} }
.tab-initial_setup .buttons {
width: calc(100% - 20px);
position: absolute;
bottom: 10px;
}
.tab-initial_setup .update { .tab-initial_setup .update {
display: block; display: block;
float: right; float: right;
margin: 0 3px 0 0;
width: 80px;
height: 28px; height: 28px;
line-height: 28px; line-height: 28px;
padding: 0 15px 0 15px;
text-align: center; text-align: center;
font-weight: bold; font-weight: bold;
@ -327,7 +332,4 @@
} }
.tab-initial_setup .update:hover { .tab-initial_setup .update:hover {
background-color: #dedcdc; background-color: #dedcdc;
}
.tab-initial_setup .update.success {
border: 1px solid #43c84d;
} }

View File

@ -38,7 +38,7 @@
</div> </div>
</div> </div>
</div> </div>
<div class="left" style="width: 515px"> <div class="left">
<div class="throttle"> <div class="throttle">
<span class="head" i18n="initialSetupThrottleHead"></span> <span class="head" i18n="initialSetupThrottleHead"></span>
<div class="fields"> <div class="fields">
@ -69,8 +69,15 @@
</dl> </dl>
</div> </div>
</div> </div>
<a class="update" href="#" i18n="initialSetupButtonSave"></a>
<div class="clear-both"></div> <div class="clear-both"></div>
<div class="magnetometer">
<span class="head" i18n="initialSetupMagHead"></span>
<div class="fields">
<dl>
<dt i18n="initialSetupDeclination"></dt><dd><input type="number" name="mag_declination" step="0.1" min="-180" max="180" /></dd>
</dl>
</div>
</div>
<div class="info"> <div class="info">
<span class="head" i18n="initialSetupInfoHead"></span> <span class="head" i18n="initialSetupInfoHead"></span>
<div class="fields"> <div class="fields">
@ -82,14 +89,9 @@
</dl> </dl>
</div> </div>
</div> </div>
<div class="magnetometer">
<span class="head" i18n="initialSetupMagHead"></span>
<div class="fields">
<dl>
<dt i18n="initialSetupDeclination"></dt><dd><input type="number" name="mag_declination" step="0.1" min="-180" max="180" /></dd>
</dl>
</div>
</div>
<div class="clear-both"></div> <div class="clear-both"></div>
</div> </div>
<div class="buttons">
<a class="update" href="#" i18n="initialSetupButtonSave"></a>
</div>
</div> </div>

View File

@ -211,21 +211,14 @@ function tab_initialize_initial_setup() {
function save_to_eeprom() { function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
GUI.log(chrome.i18n.getMessage('initialSetupEepromSaved')); 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 // reset yaw button hook
$('div#interactive_block > a.reset').click(function() { $('div#interactive_block > a.reset').click(function() {
yaw_fix = SENSOR_DATA.kinematicsZ * - 1.0; yaw_fix = SENSOR_DATA.kinematics[2] * - 1.0;
console.log("YAW reset to 0"); console.log('YAW reset to 0 deg, fix: ' + yaw_fix + ' deg');
}); });
$('#content .backup').click(configuration_backup); $('#content .backup').click(configuration_backup);
@ -251,9 +244,9 @@ function tab_initialize_initial_setup() {
// Update cube // Update cube
var cube = $('div#cube'); var cube = $('div#cube');
cube.css('-webkit-transform', 'rotateY(' + ((SENSOR_DATA.kinematicsZ * -1.0) - yaw_fix) + 'deg)'); cube.css('-webkit-transform', 'rotateY(' + ((SENSOR_DATA.kinematics[2] * -1.0) - yaw_fix) + 'deg)');
$('#cubePITCH', cube).css('-webkit-transform', 'rotateX(' + SENSOR_DATA.kinematicsY + 'deg)'); $('#cubePITCH', cube).css('-webkit-transform', 'rotateX(' + SENSOR_DATA.kinematics[1] + 'deg)');
$('#cubeROLL', cube).css('-webkit-transform', 'rotateZ(' + SENSOR_DATA.kinematicsX + 'deg)'); $('#cubeROLL', cube).css('-webkit-transform', 'rotateZ(' + SENSOR_DATA.kinematics[0] + 'deg)');
} }
GUI.interval_add('initial_setup_data_pull', get_analog_data, 50, true); GUI.interval_add('initial_setup_data_pull', get_analog_data, 50, true);

View File

@ -49,13 +49,16 @@
line-height: 20px; line-height: 20px;
} }
.tab-logging .buttons { .tab-logging .buttons {
margin-top: 10px; width: calc(100% - 20px);
position: absolute;
bottom: 10px;
} }
.tab-logging .buttons a { .tab-logging .buttons a {
display: block; display: block;
float: left; float: right;
margin-right: 10px; margin-left: 10px;
height: 28px; height: 28px;
line-height: 28px; line-height: 28px;
@ -71,3 +74,6 @@
.tab-logging .buttons a:hover { .tab-logging .buttons a:hover {
background-color: #dedcdc; background-color: #dedcdc;
} }
.tab-logging .buttons .back {
display: none;
}

View File

@ -7,6 +7,7 @@
<dt><label><input type="checkbox" name="MSP_ATTITUDE" /> MSP_ATTITUDE</label></dt><dd>3 columns (x, y, z)</dd> <dt><label><input type="checkbox" name="MSP_ATTITUDE" /> MSP_ATTITUDE</label></dt><dd>3 columns (x, y, z)</dd>
<dt><label><input type="checkbox" name="MSP_ALTITUDE" /> MSP_ALTITUDE</label></dt><dd>one column</dd> <dt><label><input type="checkbox" name="MSP_ALTITUDE" /> MSP_ALTITUDE</label></dt><dd>one column</dd>
<dt><label><input type="checkbox" name="MSP_RAW_GPS" /> MSP_RAW_GPS</label></dt><dd>7 columns</dd> <dt><label><input type="checkbox" name="MSP_RAW_GPS" /> MSP_RAW_GPS</label></dt><dd>7 columns</dd>
<dt><label><input type="checkbox" name="MSP_ANALOG" /> MSP_ANALOG</label></dt><dd>4 columns</dd>
<dt><label><input type="checkbox" name="MSP_RC" /> MSP_RC</label></dt><dd>8 columns by default</dd> <dt><label><input type="checkbox" name="MSP_RC" /> MSP_RC</label></dt><dd>8 columns by default</dd>
<dt><label><input type="checkbox" name="MSP_MOTOR" /> MSP_MOTOR</label></dt><dd>8 columns by default</dd> <dt><label><input type="checkbox" name="MSP_MOTOR" /> MSP_MOTOR</label></dt><dd>8 columns by default</dd>
<dt><label><input type="checkbox" name="MSP_DEBUG" /> MSP_DEBUG</label></dt><dd>4 columns</dd> <dt><label><input type="checkbox" name="MSP_DEBUG" /> MSP_DEBUG</label></dt><dd>4 columns</dd>
@ -28,11 +29,12 @@
<div class="info"> <div class="info">
<dl> <dl>
<dt i18n="loggingSamplesSaved"></dt><dd class="samples">0</dd> <dt i18n="loggingSamplesSaved"></dt><dd class="samples">0</dd>
<dt i18n="loggingLogSize"></dt><dd class="size">0 kB</dd> <dt i18n="loggingLogSize"></dt><dd class="size">0 Bytes</dd>
</dl> </dl>
</div> </div>
<div class="buttons"> <div class="buttons">
<a href="#" class="log_file" i18n="loggingButtonLogFile"></a> <a href="#" class="back" i18n="loggingBack"></a>
<a href="#" class="logging" i18n="loggingStart"></a> <a href="#" class="logging" i18n="loggingStart"></a>
<a href="#" class="log_file" i18n="loggingButtonLogFile"></a>
</div> </div>
</div> </div>

View File

@ -1,16 +1,34 @@
var MSP_pass_through = false;
function tab_initialize_logging() { function tab_initialize_logging() {
ga_tracker.sendAppView('Logging'); ga_tracker.sendAppView('Logging');
GUI.active_tab = 'logging'; GUI.active_tab = 'logging';
var requested_properties = []; 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() { function get_motor_data() {
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); 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); $('#content').load("./tabs/logging.html", process_html);
} }
@ -22,76 +40,92 @@ function tab_initialize_logging() {
$('a.log_file').click(prepare_file); $('a.log_file').click(prepare_file);
$('a.logging').click(function() { $('a.logging').click(function() {
if (fileEntry != null) { if (GUI.connected_to) {
var clicks = $(this).data('clicks'); if (fileEntry != null) {
var clicks = $(this).data('clicks');
if (!clicks) { if (!clicks) {
// reset some variables before start // reset some variables before start
samples = 0; samples = 0;
log_buffer = []; requests = 0;
requested_properties = []; log_buffer = [];
requested_properties = [];
$('.properties input:checked').each(function() { $('.properties input:checked').each(function() {
requested_properties.push($(this).prop('name')); requested_properties.push($(this).prop('name'));
}); });
if (requested_properties.length) { if (requested_properties.length) {
// print header for the // print header for the csv file
print_head(); print_head();
function poll_data() { function poll_data() {
// save current if (requests) {
crunch_data(); // save current data (only after everything is initialized)
crunch_data();
// request new }
for (var i = 0; i < requested_properties.length; i++) {
MSP.send_message(MSP_codes[requested_properties[i]]); // request new
if (!MSP_pass_through) {
/* this approach could be used if we want to utilize request time compensation for (var i = 0; i < requested_properties.length; i++, requests++) {
if (i < requested_properties.length -1) { MSP.send_message(MSP_codes[requested_properties[i]]);
MSP.send_message(requested_properties[i]); }
} else {
MSP.send_message(requested_properties[i], false, false, poll_data);
} }
*/
} }
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 { } 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 { } else {
GUI.interval_remove('log_data_pull'); GUI.log(chrome.i18n.getMessage('loggingErrorLogFile'));
GUI.interval_remove('flush_data');
$('.speed').prop('disabled', false);
$(this).text(chrome.i18n.getMessage('loggingStart'));
$(this).data("clicks", !clicks);
} }
} else { } 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) { chrome.storage.local.get('logging_file_entry', function(result) {
if (result.logging_file_entry) { if (result.logging_file_entry) {
chrome.fileSystem.restoreEntry(result.logging_file_entry, function(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() { function print_head() {
var head = "timestamp"; var head = "timestamp";
@ -183,6 +171,12 @@ function tab_initialize_logging() {
head += ',' + 'gpsSpeed'; head += ',' + 'gpsSpeed';
head += ',' + 'gpsGroundCourse'; head += ',' + 'gpsGroundCourse';
break; break;
case 'MSP_ANALOG':
head += ',' + 'voltage';
head += ',' + 'amperage';
head += ',' + 'mAhdrawn';
head += ',' + 'rssi';
break;
case 'MSP_RC': case 'MSP_RC':
for (var chan = 0; chan < RC.active_channels; chan++) { for (var chan = 0; chan < RC.active_channels; chan++) {
head += ',' + 'RC' + 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 // IO related methods
@ -233,6 +280,9 @@ function tab_initialize_logging() {
// save entry for next use // save entry for next use
chrome.storage.local.set({'logging_file_entry': chrome.fileSystem.retainEntry(fileEntry)}); chrome.storage.local.set({'logging_file_entry': chrome.fileSystem.retainEntry(fileEntry)});
// reset sample counter in UI
$('.samples').text(0);
prepare_writer(); prepare_writer();
} else { } else {
console.log('File appears to be read only, sorry.'); console.log('File appears to be read only, sorry.');
@ -254,7 +304,7 @@ function tab_initialize_logging() {
}; };
fileWriter.onwriteend = function() { fileWriter.onwriteend = function() {
// console.log('Data written'); $('.size').text(bytesToSize(fileWriter.length));
}; };
if (retaining) { if (retaining) {
@ -262,6 +312,9 @@ function tab_initialize_logging() {
GUI.log(chrome.i18n.getMessage('loggingAutomaticallyRetained', [path])); GUI.log(chrome.i18n.getMessage('loggingAutomaticallyRetained', [path]));
}); });
} }
// update log size in UI on fileWriter creation
$('.size').text(bytesToSize(fileWriter.length));
}, function(e) { }, function(e) {
// File is not readable or does not exist! // File is not readable or does not exist!
console.error(e); console.error(e);

View File

@ -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; 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); width: calc(50% - 50px);
} }
.tab-motor_outputs .right.servos { .tab-motor_outputs .motor_testing .sliders input {
float: left; -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 { .tab-motor_outputs .motor_testing .values li {
height: 20px;
}
.tab-motor_outputs .titles li {
float: left; float: left;
width: calc((100% / 9) - 10px); /* - (margin) */ width: calc((100% / 9) - 10px);
margin-right: 10px; margin-right: 10px;
text-align: center; text-align: center;
} }
.tab-motor_outputs .servos .titles li { .tab-motor_outputs .motor_testing .notice {
width: calc((100% / 8) - 10px); /* - (margin) */ float: right;
}
.tab-motor_outputs .titles .active {
color: green;
}
.tab-motor_outputs .m-block {
float: left;
width: calc((100% / 9) - 12px); /* - (margin, border) */ width: calc(50% - 22px);
height: 160px;
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; padding: 5px;
border: 1px dotted silver; border: 1px dotted silver;
} }
.tab-motor_outputs .motor_testing { .tab-motor_outputs .motor_testing .notice input[type="checkbox"] {
display: none; margin-left: 5px;
}
.tab-motor_outputs .motor_testing .left {
margin-right: 50px;
width: calc(50% - 50px); vertical-align: middle;
} }
.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;
}

View File

@ -1,14 +1,60 @@
<div class="tab-motor_outputs"> <div class="tab-motor_outputs">
<div class="wrapper accel">
<div class="plot_control">
<div class="title">Accelerometer - <a class="reset_accel_max" href="#" title="Reset overtime maximum">[Reset]</a></div>
<dl>
<dt i18n="sensorsRefresh"></dt>
<dd class="rate">
<select name="accel_refresh_rate">
<option value="10">10 ms</option>
<option value="20" selected="selected">20 ms</option>
<option value="30">30 ms</option>
<option value="40">40 ms</option>
<option value="50">50 ms</option>
<option value="100">100 ms</option>
<option value="250">250 ms</option>
<option value="500">500 ms</option>
<option value="1000">1000 ms</option>
</select>
</dd>
<dt i18n="sensorsScale"></dt>
<dd class="scale">
<select name="accel_scale">
<option value="0.05">0.05</option>
<option value="0.1">0.1</option>
<option value="0.2">0.2</option>
<option value="0.3">0.3</option>
<option value="0.4">0.4</option>
<option value="0.5">0.5</option>
<option value="1">1</option>
<option value="2" selected="selected">2</option>
</select>
</dd>
<dt>X:</dt><dd class="x">0</dd>
<dt>Y:</dt><dd class="y">0</dd>
<dt>Z:</dt><dd class="z">0</dd>
</dl>
</div>
<svg id="accel">
<g class="grid x" transform="translate(40, 120)"></g>
<g class="grid y" transform="translate(40, 10)"></g>
<g class="data" transform="translate(41, 10)"></g>
<g class="axis x" transform="translate(40, 120)"></g>
<g class="axis y" transform="translate(40, 10)"></g>
</svg>
<div class="clear-both"></div>
</div>
<div class="left motors"> <div class="left motors">
<div class="title">Motors</div>
<ul class="titles"> <ul class="titles">
<li title="Motor - 1">M - 1</li> <li title="Motor - 1">1</li>
<li title="Motor - 2">M - 2</li> <li title="Motor - 2">2</li>
<li title="Motor - 3">M - 3</li> <li title="Motor - 3">3</li>
<li title="Motor - 4">M - 4</li> <li title="Motor - 4">4</li>
<li title="Motor - 5">M - 5</li> <li title="Motor - 5">5</li>
<li title="Motor - 6">M - 6</li> <li title="Motor - 6">6</li>
<li title="Motor - 7">M - 7</li> <li title="Motor - 7">7</li>
<li title="Motor - 8">M - 8</li> <li title="Motor - 8">8</li>
</ul> </ul>
<div class="bar-wrapper"> <div class="bar-wrapper">
<div class="m-block motor-0"><div class="indicator"></div></div> <div class="m-block motor-0"><div class="indicator"></div></div>
@ -22,30 +68,29 @@
</div> </div>
</div> </div>
<div class="right servos"> <div class="right servos">
<div class="title">Servos</div>
<ul class="titles"> <ul class="titles">
<li title="Servo - 1">S - 1</li> <li title="Servo - 8">8</li>
<li title="Servo - 2">S - 2</li> <li title="Servo - 7">7</li>
<li title="Servo - 3">S - 3</li> <li title="Servo - 6">6</li>
<li title="Servo - 4">S - 4</li> <li title="Servo - 5">5</li>
<li title="Servo - 5">S - 5</li> <li title="Servo - 4">4</li>
<li title="Servo - 6">S - 6</li> <li title="Servo - 3">3</li>
<li title="Servo - 7">S - 7</li> <li title="Servo - 2">2</li>
<li title="Servo - 8">S - 8</li> <li title="Servo - 1">1</li>
</ul> </ul>
<div class="bar-wrapper"> <div class="bar-wrapper">
<div class="m-block servo-0"><div class="indicator"></div></div>
<div class="m-block servo-1"><div class="indicator"></div></div>
<div class="m-block servo-2"><div class="indicator"></div></div>
<div class="m-block servo-3"><div class="indicator"></div></div>
<div class="m-block servo-4"><div class="indicator"></div></div>
<div class="m-block servo-5"><div class="indicator"></div></div>
<div class="m-block servo-6"><div class="indicator"></div></div>
<div class="m-block servo-7"><div class="indicator"></div></div> <div class="m-block servo-7"><div class="indicator"></div></div>
<div class="m-block servo-6"><div class="indicator"></div></div>
<div class="m-block servo-5"><div class="indicator"></div></div>
<div class="m-block servo-4"><div class="indicator"></div></div>
<div class="m-block servo-3"><div class="indicator"></div></div>
<div class="m-block servo-2"><div class="indicator"></div></div>
<div class="m-block servo-1"><div class="indicator"></div></div>
<div class="m-block servo-0"><div class="indicator"></div></div>
</div> </div>
</div> </div>
<div class="clear-both"></div> <div class="clear-both"></div>
<p i18n="motorsBarInfo">
</p>
<div class="motor_testing"> <div class="motor_testing">
<div class="left"> <div class="left">
<div class="sliders"> <div class="sliders">
@ -73,8 +118,7 @@
</ul> </ul>
</div> </div>
</div> </div>
<div class="notice" i18n="motorsNotice"> <div class="notice" i18n="motorsNotice"></div>
</div>
<div class="cler-both"></div> <div class="cler-both"></div>
</div> </div>
</div> </div>

View File

@ -2,6 +2,124 @@ function tab_initialize_motor_outputs() {
ga_tracker.sendAppView('Motor Outputs Page'); ga_tracker.sendAppView('Motor Outputs Page');
GUI.active_tab = 'motor_outputs'; 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); MSP.send_message(MSP_codes.MSP_MISC, false, false, get_motor_data);
function get_motor_data() { function get_motor_data() {
@ -16,6 +134,97 @@ function tab_initialize_motor_outputs() {
// translate to user-selected language // translate to user-selected language
localize(); 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 CAP_DYNBALANCE is true
if (bit_check(CONFIG.capability, 2)) { if (bit_check(CONFIG.capability, 2)) {
$('div.motor_testing').show(); $('div.motor_testing').show();
@ -70,14 +279,51 @@ function tab_initialize_motor_outputs() {
$('div.sliders input').prop('disabled', true); $('div.sliders input').prop('disabled', true);
// change all values to default // change all values to default
$('div.sliders input').val(1000); $('div.sliders input').val(MISC.mincommand);
$('div.values li:not(:last)').html(1000);
// trigger change event so values are sent to mcu // trigger change event so values are sent to mcu
$('div.sliders input').trigger('input'); $('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 // data pulling functions used inside interval timer
function get_motor_data() { function get_motor_data() {
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, get_servo_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); MSP.send_message(MSP_codes.MSP_SERVO, false, false, update_ui);
} }
var full_block_scale = MISC.maxthrottle - MISC.mincommand;
function update_ui() { function update_ui() {
var block_height = $('div.m-block:first').height(); var block_height = $('div.m-block:first').height();
for (var i = 0; i < MOTOR_DATA.length; i++) { for (var i = 0; i < MOTOR_DATA.length; i++) {
var data = MOTOR_DATA[i] - 1000; var data = MOTOR_DATA[i] - MISC.mincommand;
var margin_top = block_height - (data * (block_height / 1000)); var margin_top = block_height - (data * (block_height / full_block_scale));
var height = (data * (block_height / 1000)); var height = (data * (block_height / full_block_scale));
var color = parseInt(data * 0.256); var color = parseInt(data * 0.256);
$('.motor-' + i + ' .indicator').css({'margin-top' : margin_top + 'px', 'height' : height + 'px', 'background-color' : 'rgb(' + color + ',0,0)'}); $('.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++) { for (var i = 0; i < SERVO_DATA.length; i++) {
var data = SERVO_DATA[i] - 1000; var data = SERVO_DATA[i] - 1000;
var margin_top = block_height - (data * (block_height / 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); GUI.interval_add('motor_pull', get_motor_data, 50, 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() { GUI.interval_add('status_pull', function get_status_data() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSP_codes.MSP_STATUS);
}, 250, true); }, 250, true);
} }

View File

@ -40,7 +40,7 @@
width: calc(18% - 2px); /* - border*/ width: calc(18% - 2px); /* - border*/
border: 1px solid silver; border: 1px solid #8b8b8b;
} }
.tab-pid_tuning .profile .head { .tab-pid_tuning .profile .head {
display: block; display: block;
@ -49,7 +49,7 @@
line-height: 20px; line-height: 20px;
font-weight: bold; font-weight: bold;
border-bottom: 1px solid silver; border-bottom: 1px solid #8b8b8b;
background-color: #ececec; background-color: #ececec;
} }
.tab-pid_tuning .profile input { .tab-pid_tuning .profile input {
@ -73,6 +73,12 @@
float: right; float: right;
width: calc(40% - 10px); /* - ( "virtual" margin) */ 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 .update,
.tab-pid_tuning .refresh { .tab-pid_tuning .refresh {
display: block; display: block;
@ -95,7 +101,4 @@
.tab-pid_tuning .update:hover, .tab-pid_tuning .update:hover,
.tab-pid_tuning .refresh:hover { .tab-pid_tuning .refresh:hover {
background-color: #dedcdc; background-color: #dedcdc;
}
.tab-pid_tuning .update.success {
border: 1px solid #43c84d;
} }

View File

@ -55,9 +55,9 @@
</tr> </tr>
<tr class="LEVEL"><!-- 7 --> <tr class="LEVEL"><!-- 7 -->
<td></td> <td></td>
<td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td> <td><input type="number" name="p" step="0.1" min="0" max="25.5" /></td>
<td><input type="number" name="i" step="0.01" min="0" max="0.255" /></td> <td><input type="number" name="i" step="0.001" min="0" max="0.255" /></td>
<td><input type="number" name="d" step="1" min="0" max="255" /></td> <td><input type="number" name="d" step="1" min="0" max="255" /></td>
</tr> </tr>
<tr class="MAG"><!-- 8 --> <tr class="MAG"><!-- 8 -->
<td></td> <td></td>
@ -76,11 +76,13 @@
<td><input type="number" name="tpa" step="0.01" min="0" max="2.55" /></td> <td><input type="number" name="tpa" step="0.01" min="0" max="2.55" /></td>
</tr> </tr>
</table> </table>
<a class="update" href="#" i18n="pidTuningButtonSave"></a>
<a class="refresh" href="#" i18n="pidTuningButtonRefresh"></a>
<div class="clear-both"></div> <div class="clear-both"></div>
<div class="profile"> <div class="profile">
<span class="head" i18n="pidTuningProfileHead"></span> <span class="head" i18n="pidTuningProfileHead"></span>
<input type="number" name="profile" min="1" max="3" /> <input type="number" name="profile" min="1" max="3" />
</div> </div>
<div class="buttons">
<a class="update" href="#" i18n="pidTuningButtonSave"></a>
<a class="refresh" href="#" i18n="pidTuningButtonRefresh"></a>
</div>
</div> </div>

View File

@ -141,7 +141,7 @@ function tab_initialize_pid_tuning() {
$(this).val(PIDs[7][i++].toFixed(1)); $(this).val(PIDs[7][i++].toFixed(1));
break; break;
case 1: case 1:
$(this).val(PIDs[7][i++].toFixed(2)); $(this).val(PIDs[7][i++].toFixed(3));
break; break;
case 2: case 2:
$(this).val(PIDs[7][i++].toFixed(0)); $(this).val(PIDs[7][i++].toFixed(0));
@ -300,13 +300,6 @@ function tab_initialize_pid_tuning() {
function save_to_eeprom() { function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved')); GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved'));
var element = $('a.update');
element.addClass('success');
GUI.timeout_add('success_highlight', function() {
element.removeClass('success');
}, 2000);
}); });
} }
}); });

View File

@ -12,6 +12,42 @@
.tab-receiver .bars ul { .tab-receiver .bars ul {
margin-bottom: 5px; 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 { .tab-receiver .bars li {
float: left; float: left;
@ -66,50 +102,9 @@
padding: 0 5px 0 5px; padding: 0 5px 0 5px;
text-align: right; text-align: right;
} }
.tab-receiver #RX_plot {
margin-left: 5px;
height: 200px;
}
.tab-receiver .curves { .tab-receiver .curves {
float: right; 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 { .tab-receiver .throttle_curve {
margin: 0 10px 10px 0; margin: 0 10px 10px 0;
@ -126,6 +121,57 @@
border: 1px solid silver; 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 .update,
.tab-receiver .refresh { .tab-receiver .refresh {
display: block; display: block;
@ -151,17 +197,6 @@
.tab-receiver .refresh:hover { .tab-receiver .refresh:hover {
background-color: #dedcdc; 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*/ /* SVG classes*/
.tab-receiver .grid .tick { .tab-receiver .grid .tick {

View File

@ -22,8 +22,6 @@
<td><input type="number" name="expo" step="0.01" min="0" max="1" /></td> <td><input type="number" name="expo" step="0.01" min="0" max="1" /></td>
</tr> </tr>
</table> </table>
<a class="update" href="#" i18n="receiverButtonSave"></a>
<a class="refresh" href="#" i18n="receiverButtonRefresh"></a>
</div> </div>
<div class="curves"> <div class="curves">
<div class="throttle_curve"> <div class="throttle_curve">
@ -53,4 +51,8 @@
<g class="axis x" transform="translate(40, 180)"></g> <g class="axis x" transform="translate(40, 180)"></g>
<g class="axis y" transform="translate(40, 10)"></g> <g class="axis y" transform="translate(40, 10)"></g>
</svg> </svg>
<div class="buttons">
<a class="update" href="#" i18n="receiverButtonSave"></a>
<a class="refresh" href="#" i18n="receiverButtonRefresh"></a>
</div>
</div> </div>

View File

@ -154,13 +154,6 @@ function tab_initialize_receiver() {
function save_to_eeprom() { function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
GUI.log(chrome.i18n.getMessage('receiverEepromSaved')); 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 svg = d3.select("svg");
var RX_plot_e = $('#RX_plot'); 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; var width, height, widthScale, heightScale;
function update_receiver_plot_size() { function update_receiver_plot_size() {
width = RX_plot_e.width() - margin.left - margin.right; width = RX_plot_e.width() - margin.left - margin.right;

View File

@ -60,6 +60,10 @@
.tab-sensors .plot_control .z { .tab-sensors .plot_control .z {
color: #CB4B4B; 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 { .tab-sensors select {
width: 70px; width: 70px;
border: 1px solid silver; border: 1px solid silver;

View File

@ -40,7 +40,7 @@ function tab_initialize_sensors() {
return sampleNumber + 1; 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) { function updateGraphHelperSize(helpers) {
helpers.width = helpers.targetElement.width() - margin.left - margin.right; helpers.width = helpers.targetElement.width() - margin.left - margin.right;
helpers.height = helpers.targetElement.height() - margin.top - margin.bottom; helpers.height = helpers.targetElement.height() - margin.top - margin.bottom;

View File

@ -106,6 +106,12 @@
float: left; float: left;
margin: 0 0 0 5px; margin: 0 0 0 5px;
} }
.tab-servos .buttons {
width: calc(100% - 20px);
position: absolute;
bottom: 10px;
}
.tab-servos .update { .tab-servos .update {
display: block; display: block;
float: right; float: right;
@ -125,7 +131,4 @@
} }
.tab-servos .update:hover { .tab-servos .update:hover {
background-color: #dedcdc; background-color: #dedcdc;
}
.tab-servos .update.success {
border: 1px solid #43c84d;
} }

View File

@ -31,6 +31,8 @@
<div class="live"> <div class="live">
<span i18n="servosLiveMode"></span> <input type="checkbox" /> <span i18n="servosLiveMode"></span> <input type="checkbox" />
</div> </div>
<a class="update" href="#" i18n="servosButtonSave"></a> <div class="buttons">
<a class="update" href="#" i18n="servosButtonSave"></a>
</div>
</div> </div>
</div> </div>

View File

@ -188,13 +188,6 @@ function tab_initialize_servos() {
// Save changes to EEPROM // Save changes to EEPROM
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
GUI.log(chrome.i18n.getMessage('servosEepromSave')); GUI.log(chrome.i18n.getMessage('servosEepromSave'));
var element = $('a.update');
element.addClass('success');
GUI.timeout_add('success_highlight', function() {
element.removeClass('success');
}, 2000);
}); });
} }
} }