diff --git a/_locales/en/messages.json b/_locales/en/messages.json index ae0e0df4..8a28e9e8 100755 --- a/_locales/en/messages.json +++ b/_locales/en/messages.json @@ -141,18 +141,41 @@ }, "serialPortOpened": { - "message": "Serial port successfully opened with ID: $1" + "message": "MSP connection successfully opened with ID: $1" }, "serialPortOpenFail": { - "message": "Failed to open serial port" + "message": "Failed to open MSP connection" }, "serialPortClosedOk": { - "message": "Serial port successfully closed" + "message": "MSP connection successfully closed" }, "serialPortClosedFail": { - "message": "Failed to close serial port" + "message": "Failed to close MSP connection" + }, + "serialPortUnrecoverable": { + "message": "Unrecoverable failure of serial connection, disconnecting...'" + }, + "connectionConnected": { + "message": "Connected to: $1" + }, + "connectionBleType": { + "message": "BLE device type: $1" + }, + "connectionBleNotSupported" : { + "message": "Connection error: Firmware doesn't support BLE connections. Abort." + }, + "connectionBleInterrupted": { + "message": "The connection was unexpectedly interrupted." + }, + "connectionBleError": { + "message": "Error while opening BLE device: $1" + }, + "connectionBleCliEnter": { + "message": "Connection over BLE active, output might be slower than usual." + }, + "connectionUdpTimeout": { + "message": "UDP connection timed out." }, - "usbDeviceOpened": { "message": "USB device successfully opened with ID: $1" }, diff --git a/eventPage.js b/eventPage.js index a321e4e9..2843cdbf 100755 --- a/eventPage.js +++ b/eventPage.js @@ -21,10 +21,11 @@ function startApplication() { createdWindow.onClosed.addListener(function () { // automatically close the port when application closes // save connectionId in separate variable before createdWindow.contentWindow is destroyed - var connectionId = createdWindow.contentWindow.serial.connectionId, + var connectionId = createdWindow.contentWindow.CONFIGURATOR.connection.connectionId, valid_connection = createdWindow.contentWindow.CONFIGURATOR.connectionValid, mincommand = createdWindow.contentWindow.MISC.mincommand; + console.log("EP:" + connectionId); if (connectionId && valid_connection) { // code below is handmade MSP message (without pretty JS wrapper), it behaves exactly like MSP.send_message // sending exit command just in case the cli tab was open. diff --git a/gulpfile.js b/gulpfile.js index 57c58d89..661b95d6 100644 --- a/gulpfile.js +++ b/gulpfile.js @@ -88,7 +88,11 @@ sources.js = [ './js/msp/MSPHelper.js', './js/msp/MSPchainer.js', './js/port_handler.js', - './js/serial.js', + './js/connection/connection.js', + './js/connection/connectionBle.js', + './js/connection/connectionSerial.js', + './js/connection/connectionTcp.js', + './js/connection/connectionUdp.js', './js/servoMixRule.js', './js/motorMixRule.js', './js/logicCondition.js', diff --git a/js/connection/connection.js b/js/connection/connection.js new file mode 100644 index 00000000..343a5b9f --- /dev/null +++ b/js/connection/connection.js @@ -0,0 +1,299 @@ +'use strict'; + +const ConnectionType = { + Serial: 0, + TCP: 1, + UDP: 2, + BLE: 3 +} + +class Connection { + + constructor() { + this._connectionId = false; + this._openRequested = false; + this._openCanceled = false; + this._bitrate = 0; + this._bytesReceived = 0; + this._bytesSent = 0; + this._transmitting = false; + this._outputBuffer = []; + this._onReceiveListeners = []; + this._onReceiveErrorListeners = []; + + if (this.constructor === Connection) { + throw new TypeError("Abstract class, cannot be instanced."); + } + + if (this.connectImplementation === Connection.prototype.connectImplementation) { + throw new TypeError("connectImplementation is an abstract member and not implemented.") + } + + if (this.disconnectImplementation === Connection.prototype.disconnectImplementation) { + throw new TypeError("disconnectImplementation is an abstract member and not implemented.") + } + + if (this.addOnReceiveCallback === Connection.prototype.addOnReceiveCallback) { + throw new TypeError("addOnReceiveCallback is an abstract member and not implemented.") + } + + if (this.removeOnReceiveCallback === Connection.prototype.removeOnReceiveCallback) { + throw new TypeError("removeOnReceiveCallback is an abstract member and not implemented.") + } + + if (this.addOnReceiveErrorCallback === Connection.prototype.addOnReceiveErrorCallback) { + throw new TypeError("addOnReceiveErrorCallback is an abstract member and not implemented.") + } + + if (this.removeOnReceiveErrorCallback === Connection.prototype.removeOnReceiveErrorCallback) { + throw new TypeError("removeOnReceiveErrorCallback is an abstract member and not implemented.") + } + } + + get connectionId() { + return this._connectionId; + } + + get bitrate() { + return this._bitrate; + } + + get type() { + switch (this.constructor.name) { + case ConnectionSerial.name: + return ConnectionType.Serial; + case ConnectionTcp.name: + return ConnectionType.TCP; + case ConnectionUdp.name: + return ConnectionType.UDP; + case ConnectionBle.name: + return ConnectionType.BLE; + } + } + + static create(type) { + if (Connection.instance && (Connection.instance.type == type || Connection.instance.connectionId)){ + return Connection.instance; + } + + switch (type) { + case ConnectionType.BLE: + Connection.instance = new ConnectionBle(); + break; + case ConnectionType.TCP: + Connection.instance = new ConnectionTcp(); + break; + case ConnectionType.UDP: + Connection.instance = new ConnectionUdp(); + break; + default: + case ConnectionType.Serial: + Connection.instance = new ConnectionSerial(); + break; + } + return Connection.instance; + }; + + connectImplementation(path, options, callback) { + throw new TypeError("Abstract method"); + } + + connect(path, options, callback) { + this._openRequested = true; + this._failed = 0; + this.connectImplementation(path, options, connectionInfo => { + if (connectionInfo && !this._openCanceled) { + this._connectionId = connectionInfo.connectionId; + this._bitrate = connectionInfo.bitrate; + this._bytesReceived = 0; + this._bytesSent = 0; + this._openRequested = false; + + this.addOnReceiveListener((info) => { + this._bytesReceived += info.data.byteLength; + }); + + console.log('Connection opened with ID: ' + connectionInfo.connectionId + ', Baud: ' + connectionInfo.bitrate); + + if (callback) { + callback(connectionInfo); + } + } else if (connectionInfo && this.openCanceled) { + // connection opened, but this connect sequence was canceled + // we will disconnect without triggering any callbacks + this._connectionId = connectionInfo.connectionId; + console.log('Connection opened with ID: ' + connectionInfo.connectionId + ', but request was canceled, disconnecting'); + + // some bluetooth dongles/dongle drivers really doesn't like to be closed instantly, adding a small delay + setTimeout(() => { + this._openRequested = false; + this._openCanceled = false; + this.disconnect(() => { + if (callback) { + callback(false); + } + }); + }, 150); + } else if (this._openCanceled) { + // connection didn't open and sequence was canceled, so we will do nothing + console.log('Connection didn\'t open and request was canceled'); + this._openRequested = false; + this._openCanceled = false; + if (callback) { + callback(false); + } + } else { + this._openRequested = false; + console.log('Failed to open'); + googleAnalytics.sendException('FailedToOpen', false); + if (callback) { + callback(false); + } + } + }); + } + + disconnectImplementation(callback) { + throw new TypeError("Abstract method"); + } + + disconnect(callback) { + if (this._connectionId) { + this.emptyOutputBuffer(); + this.removeAllListeners(); + + this.disconnectImplementation(result => { + this.checkChromeLastError(); + + if (result) { + console.log('Connection with ID: ' + this._connectionId + ' closed, Sent: ' + this._bytesSent + ' bytes, Received: ' + this._bytesReceived + ' bytes'); + } else { + console.log('Failed to close connection with ID: ' + this._connectionId + ' closed, Sent: ' + this._bytesSent + ' bytes, Received: ' + this._bytesReceived + ' bytes'); + googleAnalytics.sendException('Connection: FailedToClose', false); + } + + this._connectionId = false; + if (callback) { + callback(result); + } + }); + } else { + this._openCanceled = true; + } + } + + sendImplementation(data, callback) { + throw new TypeError("Abstract method"); + } + + send(data, callback) { + this._outputBuffer.push({'data': data, 'callback': callback}); + + var send = () => { + // store inside separate variables in case array gets destroyed + var data = this._outputBuffer[0].data, + callback = this._outputBuffer[0].callback; + + this.sendImplementation(data, sendInfo => { + // track sent bytes for statistics + this._bytesSent += sendInfo.bytesSent; + + // fire callback + if (callback) { + callback(sendInfo); + } + + // remove data for current transmission form the buffer + this._outputBuffer.shift(); + + // if there is any data in the queue fire send immediately, otherwise stop trasmitting + if (this._outputBuffer.length) { + // keep the buffer withing reasonable limits + if (this._outputBuffer.length > 100) { + var counter = 0; + + while (this._outputBuffer.length > 100) { + this._outputBuffer.pop(); + counter++; + } + + console.log('Send buffer overflowing, dropped: ' + counter + ' entries'); + } + send(); + } else { + this._transmitting = false; + } + }); + } + + if (!this._transmitting) { + this._transmitting = true; + send(); + } + } + + abort() { + if (GUI.connected_to || GUI.connecting_to) { + $('a.connect').trigger('click'); + } else { + this.disconnect(); + } + } + + checkChromeLastError() { + if (chrome.runtime.lastError) { + console.error(chrome.runtime.lastError.message); + } + } + + addOnReceiveCallback(callback) { + throw new TypeError("Abstract method"); + } + + removeOnReceiveCallback(callback) { + throw new TypeError("Abstract method"); + } + + addOnReceiveListener(callback) { + this._onReceiveListeners.push(callback); + this.addOnReceiveCallback(callback) + } + + addOnReceiveErrorCallback(callback) { + throw new TypeError("Abstract method"); + } + + removeOnReceiveErrorCallback(callback) { + throw new TypeError("Abstract method"); + } + + addOnReceiveErrorListener(callback) { + this._onReceiveErrorListeners.push(callback); + this.addOnReceiveErrorCallback(callback) + } + + removeAllListeners() { + this._onReceiveListeners.forEach(listener => this.removeOnReceiveCallback(listener)); + this._onReceiveListeners = []; + + this._onReceiveErrorListeners.forEach(listener => this.removeOnReceiveErrorCallback(listener)); + this._onReceiveErrorListeners = []; + } + + emptyOutputBuffer() { + this._outputBuffer = []; + this._transmitting = false; + } + + /** + * Default timeout values + * @returns {number} [ms] + */ + getTimeout() { + if (this._bitrate >= 57600) { + return 3000; + } else { + return 4000; + } + } +} diff --git a/js/connection/connectionBle.js b/js/connection/connectionBle.js new file mode 100644 index 00000000..92abadf2 --- /dev/null +++ b/js/connection/connectionBle.js @@ -0,0 +1,253 @@ +'use strict' + +// BLE 20 bytes buffer +const BLE_WRITE_BUFFER_LENGTH = 20; + +const BleDevices = [ + { + name: "CC2541 based", + serviceUuid: '0000ffe0-0000-1000-8000-00805f9b34fb', + writeCharateristic: '0000ffe1-0000-1000-8000-00805f9b34fb', + readCharateristic: '0000ffe1-0000-1000-8000-00805f9b34fb', + delay: 30, + }, + { + name: "Nordic Semiconductor NRF", + serviceUuid: '6e400001-b5a3-f393-e0a9-e50e24dcca9e', + writeCharateristic: '6e400003-b5a3-f393-e0a9-e50e24dcca9e', + readCharateristic: '6e400002-b5a3-f393-e0a9-e50e24dcca9e', + delay: 30, + }, + { + name: "SpeedyBee Type 2", + serviceUuid: '0000abf0-0000-1000-8000-00805f9b34fb', + writeCharateristic: '0000abf1-0000-1000-8000-00805f9b34fb', + readCharateristic: '0000abf2-0000-1000-8000-00805f9b34fb', + delay: 0, + }, + { + name: "SpeedyBee Type 1", + serviceUuid: '00001000-0000-1000-8000-00805f9b34fb', + writeCharateristic: '00001001-0000-1000-8000-00805f9b34fb', + readCharateristic: '00001002-0000-1000-8000-00805f9b34fb', + delay: 0, + } +]; + +class ConnectionBle extends Connection { + + constructor() { + super(); + + this._readCharacteristic = false; + this._writeCharacteristic = false; + this._device = false; + this._deviceDescription = false; + this._onCharateristicValueChangedListeners = []; + this._onDisconnectListeners = []; + this._reconnects = 0; + this._handleOnCharateristicValueChanged = false; + this._handleDisconnect = false; + } + + get deviceDescription() { + return this._deviceDescription; + } + + async connectImplementation(path, options, callback) { + console.log("Request BLE Device"); + await this.openDevice() + .then(() => { + this.addOnReceiveErrorListener(error => { + GUI.log(chrome.i18n.getMessage('connectionBleInterrupted')); + this.abort(); + }); + + if (callback) { + callback({ + // Dummy values + connectionId: 0xff, + bitrate: 115200 + }); + } + }).catch(error => { + GUI.log(chrome.i18n.getMessage('connectionBleError', [error])); + if (callback) { + callback(false); + } + }); + + return Promise.resolve(); + } + + async openDevice(){ + await this.request() + .then(device => this.connectBle(device)) + .then(() => this.startNotification()); + + return Promise.resolve(); + }; + + request() { + var ids = []; + BleDevices.forEach(device => { + ids.push(device.serviceUuid) + }); + + return navigator.bluetooth.requestDevice({ + acceptAllDevices: true, + optionalServices: ids + }).then(device => { + console.log("Found BLE device: " + device.name); + this._device = device; + this._handleDisconnect = event => { + this._onDisconnectListeners.forEach(listener => { + listener("disconnected"); + }); + }; + + this._device.addEventListener('gattserverdisconnected', this._handleDisconnect); + return this._device; + }); + } + + connectBle(device) { + if (device.gatt.connected && this._readCharacteristic && this._writeCharacteristic) { + return Promise.resolve(); + } + + return device.gatt.connect() + .then(server => { + console.log("Connect to: " + device.name); + GUI.log(chrome.i18n.getMessage('connectionConnected', [device.name])); + return server.getPrimaryServices(); + }).then(services => { + let connectedService = services.find(service => { + this._deviceDescription = BleDevices.find(device => device.serviceUuid == service.uuid); + return this._deviceDescription; + }); + + if (!this._deviceDescription) { + throw new Error("Unsupported device (service UUID mismatch)."); + } + + GUI.log(chrome.i18n.getMessage('connectionBleType', [this._deviceDescription.name])); + return connectedService.getCharacteristics(); + }).then(characteristics => { + characteristics.forEach(characteristic => { + if (characteristic.uuid == this._deviceDescription.writeCharateristic) { + this._writeCharacteristic = characteristic; + } + + if (characteristic.uuid == this._deviceDescription.readCharateristic) { + this._readCharacteristic = characteristic; + } + + return this._writeCharacteristic && this._readCharacteristic; + }); + + if (!this._writeCharacteristic) { + throw new Error("No or unexpected write charateristic found (should be " + this._deviceDescription.writeCharateristic + ")"); + } + + if (!this._readCharacteristic) { + throw new Error("No or unexpected read charateristic found (should be " + this._deviceDescription.readCharateristic + ")"); + } + + this._handleOnCharateristicValueChanged = event => { + let buffer = new Uint8Array(event.target.value.byteLength); + for (var i = 0; i < event.target.value.byteLength; i++) { + buffer[i] = event.target.value.getUint8(i); + } + + this._onCharateristicValueChangedListeners.forEach(listener => { + listener({ + connectionId: 0xFF, + data: buffer + }); + }); + }; + + this._readCharacteristic.addEventListener('characteristicvaluechanged', this._handleOnCharateristicValueChanged) + return Promise.resolve(); + }); + } + + startNotification() { + if (!this._readCharacteristic) { + throw new Error("No read charateristic"); + } + + if (!this._readCharacteristic.properties.notify) { + throw new Error("Read charateristic can't notify."); + } + + return this._readCharacteristic.startNotifications() + .then(() => { + console.log("BLE notifications started."); + }); + } + + disconnectImplementation(callback) { + if (this._device) { + this._device.removeEventListener('gattserverdisconnected', this._handleDisconnect); + this._readCharacteristic.removeEventListener('characteristicvaluechanged', this._handleOnCharateristicValueChanged); + + if (this._device.gatt.connected) { + this._device.gatt.disconnect(); + } + this._device = false; + this._writeCharacteristic = false; + this._readCharacteristic = false; + this._deviceDescription = false; + } + + if (callback) { + callback(true); + } + } + + async sendImplementation (data, callback) {; + if (!this._writeCharacteristic) { + return; + } + + let sent = 0; + let dataBuffer = new Uint8Array(data); + for (var i = 0; i < dataBuffer.length; i += BLE_WRITE_BUFFER_LENGTH) { + var length = BLE_WRITE_BUFFER_LENGTH; + + if (i + BLE_WRITE_BUFFER_LENGTH > dataBuffer.length) { + length = dataBuffer.length % BLE_WRITE_BUFFER_LENGTH; + } + + var outBuffer = dataBuffer.subarray(i, i + length); + sent += outBuffer.length; + await this._writeCharacteristic.writeValue(outBuffer); + } + + if (callback) { + callback({ + bytesSent: sent, + resultCode: 0 + }); + } + + } + + addOnReceiveCallback(callback){ + this._onCharateristicValueChangedListeners.push(callback); + } + + removeOnReceiveCallback(callback){ + this._onCharateristicValueChangedListeners = this._onCharateristicValueChangedListeners.filter(listener => listener !== callback); + } + + addOnReceiveErrorCallback(callback) { + this._onDisconnectListeners.push(callback); + } + + removeOnReceiveErrorCallback(callback) { + this._onDisconnectListeners = this._onDisconnectListeners.filter(listener => listener !== callback); + } +} diff --git a/js/connection/connectionSerial.js b/js/connection/connectionSerial.js new file mode 100644 index 00000000..7140c5f2 --- /dev/null +++ b/js/connection/connectionSerial.js @@ -0,0 +1,139 @@ +'use strict' + +class ConnectionSerial extends Connection { + + constructor() { + super(); + + this._failed = 0; + } + + connectImplementation(path, options, callback) { + chrome.serial.connect(path, options, (connectionInfo) => { + this.checkChromeLastError(); + if (connectionInfo && !this._openCanceled) { + this.addOnReceiveErrorListener(info => { + console.error(info); + googleAnalytics.sendException('Serial: ' + info.error, false); + + switch (info.error) { + case 'system_error': // we might be able to recover from this one + if (!this._failed++) { + chrome.serial.setPaused(this._connectionId, false, function () { + SerialCom.getInfo((info) => { + if (info) { + if (!info.paused) { + console.log('SERIAL: Connection recovered from last onReceiveError'); + googleAnalytics.sendException('Serial: onReceiveError - recovered', false); + + this._failed = 0; + } else { + console.log('SERIAL: Connection did not recover from last onReceiveError, disconnecting'); + GUI.log(chrome.i18n.getMessage('serialPortUnrecoverable')); + googleAnalytics.sendException('Serial: onReceiveError - unrecoverable', false); + + this.abort(); + } + } else { + this.checkChromeLastError(); + } + }); + }); + } + break; + + case 'break': // This occurs on F1 boards with old firmware during reboot + case 'overrun': + case 'frame_error': //Got disconnected + // wait 50 ms and attempt recovery + var error = info.error; + setTimeout(() => { + chrome.serial.setPaused(info.connectionId, false, function() { + SerialCom.getInfo(function (info) { + if (info) { + if (info.paused) { + // assume unrecoverable, disconnect + console.log('SERIAL: Connection did not recover from ' + error + ' condition, disconnecting'); + GUI.log(chrome.i18n.getMessage('serialPortUnrecoverable'));; + googleAnalytics.sendException('Serial: ' + error + ' - unrecoverable', false); + + this.abort(); + } else { + console.log('SERIAL: Connection recovered from ' + error + ' condition'); + googleAnalytics.sendException('Serial: ' + error + ' - recovered', false); + } + } + }); + }); + }, 50); + break; + + case 'timeout': + // TODO + break; + + case 'device_lost': + case 'disconnected': + default: + this.abort(); + } + }); + GUI.log(chrome.i18n.getMessage('connectionConnected', [path])); + } + + if (callback) { + callback(connectionInfo); + } + }); + } + + disconnectImplementation(callback) { + chrome.serial.disconnect(this._connectionId, (result) => { + if (callback) { + callback(result); + } + }); + } + + sendImplementation(data, callback) { + chrome.serial.send(this._connectionId, data, callback); + } + + addOnReceiveCallback(callback){ + chrome.serial.onReceive.addListener(callback); + } + + removeOnReceiveCallback(callback){ + chrome.serial.onReceive.removeListener(callback); + } + + addOnReceiveErrorCallback(callback) { + chrome.serial.onReceiveError.addListener(callback); + } + + removeOnReceiveErrorCallback(callback) { + chrome.serial.onReceiveError.removeListener(callback); + } + + static getDevices(callback) { + chrome.serial.getDevices((devices_array) => { + var devices = []; + devices_array.forEach((device) => { + devices.push(device.path); + }); + callback(devices); + }); + } + + static getInfo(connectionId, callback) { + chrome.serial.getInfo(connectionId, callback); + } + + static getControlSignals(connectionId, callback) { + chrome.serial.getControlSignals(connectionId, callback); + } + + static setControlSignals(connectionId, signals, callback) { + chrome.serial.setControlSignals(connectionId, signals, callback); + } +} diff --git a/js/connection/connectionTcp.js b/js/connection/connectionTcp.js new file mode 100644 index 00000000..48253cbf --- /dev/null +++ b/js/connection/connectionTcp.js @@ -0,0 +1,139 @@ +'use strict' + +const STANDARD_TCP_PORT = 5761; + +class ConnectionTcp extends Connection { + + constructor() { + super(); + + this._connectionIP = ""; + this.connectionPort = 0; + } + + connectImplementation(address, options, callback) { + var addr = address.split(':'); + if (addr.length >= 2) { + this._connectionIP = addr[0]; + this._connectionPort = parseInt(addr[1]) + } else { + this._connectionIP = address[0]; + this._connectionPort = STANDARD_PORT; + } + + chrome.sockets.tcp.create({ + name: "iNavTCP", + bufferSize: 65535 + }, createInfo => { + this.checkChromeLastError(); + if (createInfo && !this._openCanceled) { + chrome.sockets.tcp.connect(createInfo.socketId, this._connectionIP, this._connectionPort, result => { + this.checkChromeLastError(); + + if (result == 0) { + // Disable Nagle's algorithm + chrome.sockets.tcp.setNoDelay(createInfo.socketId, true, noDelayResult => { + this.checkChromeLastError(); + if (noDelayResult < 0) { + console.warn("Unable to set TCP_NODELAY: " + noDelayResult); + if (callback) { + callback(false); + } + } + + this.addOnReceiveErrorListener(info => { + console.error(info); + googleAnalytics.sendException('TCP: ' + info.error, false); + + let message; + switch (info.resultCode) { + case -15: + // connection is lost, cannot write to it anymore, preventing further disconnect attempts + message = 'error: ERR_SOCKET_NOT_CONNECTED'; + console.log(`TCP: ${message}: ${info.resultCode}`); + this._connectionId = false; + return; + case -21: + message = 'error: NETWORK_CHANGED'; + break; + case -100: + message = 'error: CONNECTION_CLOSED'; + break; + case -102: + message = 'error: CONNECTION_REFUSED'; + break; + case -105: + message = 'error: NAME_NOT_RESOLVED'; + break; + case -106: + message = 'error: INTERNET_DISCONNECTED'; + break; + case -109: + message = 'error: ADDRESS_UNREACHABLE'; + break; + } + + let resultMessage = message ? `${message} ${info.resultCode}` : info.resultCode; + console.warn(`TCP: ${resultMessage} ID: ${this._connectionId}`); + + this.abort(); + }); + + GUI.log(chrome.i18n.getMessage('connectionConnected', ["tcp://" + this._connectionIP + ":" + this._connectionPort])); + + if (callback) { + callback({ + bitrate: 115200, + connectionId: createInfo.socketId + }); + } + + }); + } else { + console.error("Unable to open TCP socket: " + result); + if (callback) { + callback(false); + } + } + }); + } else { + console.error("Unable to create TCP socket."); + + if (callback) { + callback(false); + } + } + }); + } + + disconnectImplementation(callback) { + chrome.sockets.tcp.disconnect(this._connectionId); + this.checkChromeLastError(); + this._connectionIP = ""; + this._connectionPort = 0; + + if (callback) { + callback(true); + } + } + + sendImplementation(data, callback) {; + chrome.sockets.tcp.send(this._connectionId, data, callback); + } + + addOnReceiveCallback(callback){ + chrome.sockets.tcp.onReceive.addListener(callback); + } + + removeOnReceiveCallback(callback){ + chrome.sockets.tcp.onReceive.removeListener(callback); + } + + addOnReceiveErrorCallback(callback) { + chrome.sockets.tcp.onReceiveError.addListener(callback); + } + + removeOnReceiveErrorCallback(callback) { + chrome.sockets.tcp.onReceiveError.removeListener(callback); + } +} diff --git a/js/connection/connectionUdp.js b/js/connection/connectionUdp.js new file mode 100644 index 00000000..2f50887f --- /dev/null +++ b/js/connection/connectionUdp.js @@ -0,0 +1,149 @@ +'use strict' + +const STANDARD_UDP_PORT = 5762; + +class ConnectionUdp extends Connection { + constructor() { + super(); + + this._connectionIP = ""; + this._connectionPort = 0; + this._timeoutId = false; + this._isCli = false; + } + + /** + * @param {boolean} value + */ + set isCli(value) { + this._isCli = value; + } + + connectImplementation(address, options, callback) { + var addr = address.split(':'); + if (addr.length >= 2) { + this._connectionIP = addr[0]; + this._connectionPort = parseInt(addr[1]) + } else { + this._connectionIP = address[0]; + this._connectionPort = STANDARD_UDP_PORT; + } + + chrome.sockets.udp.create({ + name: "iNavUDP", + bufferSize: 65535, + }, createInfo => { + this.checkChromeLastError(); + if (createInfo && !this._openCanceled) { + chrome.sockets.udp.bind(createInfo.socketId, "0.0.0.0", this._connectionPort, result => { + this.checkChromeLastError(); + if (result == 0) { + // UDP connections don't trigger an event if they are interrupted, a simple timeout mechanism must suffice here. + this.addOnReceiveCallback(() => { + if (this._timeoutId) { + clearTimeout(this._timeoutId); + } + + this._timeoutId = setTimeout(() => { + if (!this._isCli) { // Disable timeout for CLI + GUI.log(chrome.i18n.getMessage('connectionUdpTimeout')); + this.abort(); + } + }, 10000); + }) + + // Actually useless, but according to chrome documentation also UDP triggers error events ¯\_(ツ)_/¯ + this.addOnReceiveErrorListener(info => { + console.error(info); + googleAnalytics.sendException('UDP: ' + info.error, false); + + let message; + switch (info.resultCode) { + case -15: + // connection is lost, cannot write to it anymore, preventing further disconnect attempts + message = 'error: ERR_SOCKET_NOT_CONNECTED'; + console.log(`UDP: ${message}: ${info.resultCode}`); + this._connectionId = false; + return; + case -21: + message = 'error: NETWORK_CHANGED'; + break; + case -100: + message = 'error: CONNECTION_CLOSED'; + break; + case -102: + message = 'error: CONNECTION_REFUSED'; + break; + case -105: + message = 'error: NAME_NOT_RESOLVED'; + break; + case -106: + message = 'error: INTERNET_DISCONNECTED'; + break; + case -109: + message = 'error: ADDRESS_UNREACHABLE'; + break; + } + + let resultMessage = message ? `${message} ${info.resultCode}` : info.resultCode; + console.warn(`UDP: ${resultMessage} ID: ${this._connectionId}`); + + this.abort(); + }); + + GUI.log(chrome.i18n.getMessage('connectionConnected', ["udp://" + this._connectionIP + ":" + this._connectionPort])); + + if (callback) { + callback({ + bitrate: 115200, + connectionId: createInfo.socketId + }); + } + } else { + console.error("Unable to open UDP socket: " + result); + if (callback) { + callback(false); + } + } + }); + } else { + console.error("Unable to create UDP socket."); + if (callback) { + callback(false); + } + } + }); + } + + disconnectImplementation(callback) { + chrome.sockets.udp.close(this._connectionId); + this.checkChromeLastError(); + this._connectionIP = ""; + this._connectionPort = 0; + clearTimeout(this._timeoutId); + this._timeoutId = false; + if (callback) { + callback(true); + } + } + + sendImplementation(data, callback) {; + chrome.sockets.udp.send(this._connectionId, data, this._connectionIP, this._connectionPort, callback); + } + + addOnReceiveCallback(callback){ + chrome.sockets.udp.onReceive.addListener(callback); + } + + removeOnReceiveCallback(callback){ + chrome.sockets.udp.onReceive.removeListener(callback); + } + + addOnReceiveErrorCallback(callback) { + chrome.sockets.udp.onReceiveError.addListener(callback); + } + + removeOnReceiveErrorCallback(callback) { + chrome.sockets.udp.onReceiveError.removeListener(callback); + } +} diff --git a/js/data_storage.js b/js/data_storage.js index 3de1a4f2..1bfe7b60 100755 --- a/js/data_storage.js +++ b/js/data_storage.js @@ -7,5 +7,6 @@ var CONFIGURATOR = { 'connectionValid': false, 'connectionValidCliOnly': false, 'cliActive': false, - 'cliValid': false + 'cliValid': false, + 'connection': false }; diff --git a/js/logicConditionsCollection.js b/js/logicConditionsCollection.js index 10707f02..7d7bb762 100644 --- a/js/logicConditionsCollection.js +++ b/js/logicConditionsCollection.js @@ -6,6 +6,12 @@ let LogicConditionsCollection = function () { data = [], $container; + let max_logicConditions = 32; + + self.getMaxLogicConditionCount = function () { + return max_logicConditions; + } + self.put = function (element) { data.push(element); }; diff --git a/js/msp/MSPCodes.js b/js/msp/MSPCodes.js index 856a6ade..966a701d 100644 --- a/js/msp/MSPCodes.js +++ b/js/msp/MSPCodes.js @@ -229,5 +229,7 @@ var MSPCodes = { MSP2_INAV_FWUPDT_ROLLBACK_EXEC: 0x2037, MSP2_INAV_SAFEHOME: 0x2038, - MSP2_INAV_SET_SAFEHOME: 0x2039 + MSP2_INAV_SET_SAFEHOME: 0x2039, + + MSP2_INAV_LOGIC_CONDITIONS_SINGLE: 0x203B }; diff --git a/js/msp/MSPHelper.js b/js/msp/MSPHelper.js index b362d94f..2fb11c66 100644 --- a/js/msp/MSPHelper.js +++ b/js/msp/MSPHelper.js @@ -477,8 +477,20 @@ var mspHelper = (function (gui) { data.getInt8(i + 13) )); } - } - + } + break; + + case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_SINGLE: + LOGIC_CONDITIONS.put(new LogicCondition( + data.getInt8(0), + data.getInt8(1), + data.getUint8(2), + data.getUint8(3), + data.getInt32(4, true), + data.getUint8(8), + data.getInt32(9, true), + data.getInt8(13) + )); break; case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS: @@ -2258,8 +2270,23 @@ var mspHelper = (function (gui) { } }; - self.loadLogicConditions = function (callback) { - MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS, false, false, callback); + self.loadLogicConditions = function (callback) { + if (semver.gte(CONFIG.flightControllerVersion, "5.0.0")) { + LOGIC_CONDITIONS.flush(); + let idx = 0; + MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_SINGLE, [idx], false, nextLogicCondition); + + function nextLogicCondition() { + idx++; + if (idx < LOGIC_CONDITIONS.getMaxLogicConditionCount() - 1) { + MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_SINGLE, [idx], false, nextLogicCondition); + } else { + MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_SINGLE, [idx], false, callback); + } + } + } else { + MSP.send_message(MSPCodes.MSP2_INAV_LOGIC_CONDITIONS, false, false, callback); + } } self.sendLogicConditions = function (onCompleteCallback) { @@ -3228,5 +3255,6 @@ var mspHelper = (function (gui) { MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback); }; + return self; })(GUI); diff --git a/js/periodicStatusUpdater.js b/js/periodicStatusUpdater.js index 213df83c..c60f9f59 100644 --- a/js/periodicStatusUpdater.js +++ b/js/periodicStatusUpdater.js @@ -31,7 +31,7 @@ helper.periodicStatusUpdater = (function () { privateScope.updateView = function () { - var active = ((Date.now() - MSP.analog_last_received_timestamp) < publicScope.getUpdateInterval(serial.bitrate) * 3); + var active = ((Date.now() - MSP.analog_last_received_timestamp) < publicScope.getUpdateInterval(CONFIGURATOR.connection.bitrate) * 3); if (FC.isModeEnabled('ARM')) $(".armedicon").css({ diff --git a/js/port_handler.js b/js/port_handler.js index 28023291..58e464fd 100755 --- a/js/port_handler.js +++ b/js/port_handler.js @@ -19,7 +19,7 @@ PortHandler.initialize = function () { PortHandler.check = function () { var self = this; - serial.getDevices(function(current_ports) { + ConnectionSerial.getDevices(function(current_ports) { // port got removed or initial_ports wasn't initialized yet if (self.array_difference(self.initial_ports, current_ports).length > 0 || !self.initial_ports) { var removed_ports = self.array_difference(self.initial_ports, current_ports); @@ -66,13 +66,16 @@ PortHandler.check = function () { chrome.storage.local.get('last_used_port', function (result) { // if last_used_port was set, we try to select it if (result.last_used_port) { - current_ports.forEach(function(port) { - if (port == result.last_used_port) { - console.log('Selecting last used port: ' + result.last_used_port); - - $('#port').val(result.last_used_port); - } - }); + if (result.last_used_port == "ble" || result.last_used_port == "tcp" || result.last_used_port == "udp") { + $('#port').val(result.last_used_port); + } else { + current_ports.forEach(function(port) { + if (port == result.last_used_port) { + console.log('Selecting last used port: ' + result.last_used_port); + $('#port').val(result.last_used_port); + } + }); + } } else { console.log('Last used port wasn\'t saved "yet", auto-select disabled.'); } @@ -175,6 +178,9 @@ PortHandler.update_port_select = function (ports) { } $('div#port-picker #port').append($("", {value: 'manual', text: 'Manual Selection', data: {isManual: true}})); + $('div#port-picker #port').append($("", {value: 'ble', text: 'BLE', data: {isBle: true}})); + $('div#port-picker #port').append($("", {value: 'tcp', text: 'TCP', data: {isTcp: true}})); + $('div#port-picker #port').append($("", {value: 'udp', text: 'UDP', data: {isUdp: true}})); }; PortHandler.port_detected = function(name, code, timeout, ignore_timeout) { diff --git a/js/protocols/stm32.js b/js/protocols/stm32.js index 968d4901..bb479152 100644 --- a/js/protocols/stm32.js +++ b/js/protocols/stm32.js @@ -74,7 +74,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback) } if (self.options.no_reboot) { - serial.connect(port, {bitrate: self.baud, parityBit: 'even', stopBits: 'one'}, function (openInfo) { + CONFIGURATOR.connection.connect(port, {bitrate: self.baud, parityBit: 'even', stopBits: 'one'}, function (openInfo) { if (openInfo) { // we are connected, disabling connect button in the UI GUI.connect_lock = true; @@ -85,7 +85,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback) } }); } else { - serial.connect(port, {bitrate: self.options.reboot_baud}, function (openInfo) { + CONFIGURATOR.connection.connect(port, {bitrate: self.options.reboot_baud}, function (openInfo) { if (openInfo) { console.log('Sending ascii "R" to reboot'); @@ -97,8 +97,8 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback) bufferView[0] = 0x52; - serial.send(bufferOut, function () { - serial.disconnect(function (result) { + CONFIGURATOR.connection.send(bufferOut, function () { + CONFIGURATOR.connection.disconnect(function (result) { if (result) { var intervalMs = 200; var retries = 0; @@ -119,12 +119,12 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback) return; } // Check for the serial port - serial.getDevices(function(devices) { + ConnectionSerial.getDevices(function(devices) { if (devices && devices.includes(port)) { // Serial port might briefly reappear on DFU devices while // the FC is rebooting, so we don't clear the interval // until we succesfully connect. - serial.connect(port, {bitrate: self.baud, parityBit: 'even', stopBits: 'one'}, function (openInfo) { + CONFIGURATOR.connection.connect(port, {bitrate: self.baud, parityBit: 'even', stopBits: 'one'}, function (openInfo) { if (openInfo) { clearInterval(interval); self.initialize(); @@ -170,7 +170,7 @@ STM32_protocol.prototype.initialize = function () { // lock some UI elements TODO needs rework $('select[name="release"]').prop('disabled', true); - serial.onReceive.addListener(function (info) { + CONFIGURATOR.connection.onReceive.addListener(function (info) { self.read(info); }); @@ -253,7 +253,7 @@ STM32_protocol.prototype.send = function (Array, bytes_to_read, callback) { this.receive_buffer = []; // send over the actual data - serial.send(bufferOut, function (writeInfo) {}); + CONFIGURATOR.connection.send(bufferOut, function (writeInfo) {}); }; // val = single byte to be verified @@ -772,7 +772,7 @@ STM32_protocol.prototype.upload_procedure = function (step) { helper.interval.remove('STM32_timeout'); // stop STM32 timeout timer (everything is finished now) // close connection - serial.disconnect(function (result) { + CONFIGURATOR.connection.disconnect(function (result) { // unlocking connect button GUI.connect_lock = false; diff --git a/js/serial.js b/js/serial.js deleted file mode 100644 index 98a1f9ae..00000000 --- a/js/serial.js +++ /dev/null @@ -1,309 +0,0 @@ -'use strict'; - -/*global chrome*/ - -var serial = { - connectionId: false, - openRequested: false, - openCanceled: false, - bitrate: 0, - bytesReceived: 0, - bytesSent: 0, - failed: 0, - - transmitting: false, - outputBuffer: [], - - connect: function (path, options, callback) { - var self = this; - self.openRequested = true; - - chrome.serial.connect(path, options, function (connectionInfo) { - if (chrome.runtime.lastError) { - console.error(chrome.runtime.lastError.message); - } - - if (connectionInfo && !self.openCanceled) { - self.connectionId = connectionInfo.connectionId; - self.bitrate = connectionInfo.bitrate; - self.bytesReceived = 0; - self.bytesSent = 0; - self.failed = 0; - self.openRequested = false; - - self.onReceive.addListener(function log_bytesReceived(info) { - self.bytesReceived += info.data.byteLength; - }); - - self.onReceiveError.addListener(function watch_for_on_receive_errors(info) { - console.error(info); - googleAnalytics.sendException('Serial: ' + info.error, false); - - switch (info.error) { - case 'system_error': // we might be able to recover from this one - if (!self.failed++) { - chrome.serial.setPaused(self.connectionId, false, function () { - self.getInfo(function (info) { - if (info) { - if (!info.paused) { - console.log('SERIAL: Connection recovered from last onReceiveError'); - googleAnalytics.sendException('Serial: onReceiveError - recovered', false); - - self.failed = 0; - } else { - console.log('SERIAL: Connection did not recover from last onReceiveError, disconnecting'); - GUI.log('Unrecoverable failure of serial connection, disconnecting...'); - googleAnalytics.sendException('Serial: onReceiveError - unrecoverable', false); - - if (GUI.connected_to || GUI.connecting_to) { - $('a.connect').click(); - } else { - self.disconnect(); - } - } - } else { - if (chrome.runtime.lastError) { - console.error(chrome.runtime.lastError.message); - } - } - }); - }); - } - break; - - case 'break': // This occurs on F1 boards with old firmware during reboot - case 'overrun': - case 'frame_error': //Got disconnected - // wait 50 ms and attempt recovery - self.error = info.error; - setTimeout(function() { - chrome.serial.setPaused(info.connectionId, false, function() { - self.getInfo(function (info) { - if (info) { - if (info.paused) { - // assume unrecoverable, disconnect - console.log('SERIAL: Connection did not recover from ' + self.error + ' condition, disconnecting'); - GUI.log('Unrecoverable failure of serial connection, disconnecting...'); - googleAnalytics.sendException('Serial: ' + self.error + ' - unrecoverable', false); - - if (GUI.connected_to || GUI.connecting_to) { - $('a.connect').click(); - } else { - self.disconnect(); - } - } - else { - console.log('SERIAL: Connection recovered from ' + self.error + ' condition'); - googleAnalytics.sendException('Serial: ' + self.error + ' - recovered', false); - } - } - }); - }); - }, 50); - break; - - case 'timeout': - // TODO - break; - - case 'device_lost': - if (GUI.connected_to || GUI.connecting_to) { - $('a.connect').click(); - } else { - self.disconnect(); - } - break; - - case 'disconnected': - // TODO - break; - } - }); - - console.log('SERIAL: Connection opened with ID: ' + connectionInfo.connectionId + ', Baud: ' + connectionInfo.bitrate); - - if (callback) callback(connectionInfo); - } else if (connectionInfo && self.openCanceled) { - // connection opened, but this connect sequence was canceled - // we will disconnect without triggering any callbacks - self.connectionId = connectionInfo.connectionId; - console.log('SERIAL: Connection opened with ID: ' + connectionInfo.connectionId + ', but request was canceled, disconnecting'); - - // some bluetooth dongles/dongle drivers really doesn't like to be closed instantly, adding a small delay - setTimeout(function initialization() { - self.openRequested = false; - self.openCanceled = false; - self.disconnect(function resetUI() { - if (callback) callback(false); - }); - }, 150); - } else if (self.openCanceled) { - // connection didn't open and sequence was canceled, so we will do nothing - console.log('SERIAL: Connection didn\'t open and request was canceled'); - self.openRequested = false; - self.openCanceled = false; - if (callback) callback(false); - } else { - self.openRequested = false; - console.log('SERIAL: Failed to open serial port'); - googleAnalytics.sendException('Serial: FailedToOpen', false); - if (callback) callback(false); - } - }); - }, - disconnect: function (callback) { - var self = this; - - if (self.connectionId) { - self.emptyOutputBuffer(); - - // remove listeners - for (var i = (self.onReceive.listeners.length - 1); i >= 0; 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) { - if (chrome.runtime.lastError) { - console.error(chrome.runtime.lastError.message); - } - - if (result) { - console.log('SERIAL: Connection with ID: ' + self.connectionId + ' closed, Sent: ' + self.bytesSent + ' bytes, Received: ' + self.bytesReceived + ' bytes'); - } else { - console.log('SERIAL: Failed to close connection with ID: ' + self.connectionId + ' closed, Sent: ' + self.bytesSent + ' bytes, Received: ' + self.bytesReceived + ' bytes'); - googleAnalytics.sendException('Serial: FailedToClose', false); - } - - self.connectionId = false; - self.bitrate = 0; - - if (callback) callback(result); - }); - } else { - // connection wasn't opened, so we won't try to close anything - // instead we will rise canceled flag which will prevent connect from continueing further after being canceled - self.openCanceled = true; - } - }, - getDevices: function (callback) { - chrome.serial.getDevices(function (devices_array) { - var devices = []; - devices_array.forEach(function (device) { - devices.push(device.path); - }); - - callback(devices); - }); - }, - getInfo: function (callback) { - chrome.serial.getInfo(this.connectionId, callback); - }, - getControlSignals: function (callback) { - chrome.serial.getControlSignals(this.connectionId, callback); - }, - setControlSignals: function (signals, callback) { - chrome.serial.setControlSignals(this.connectionId, signals, callback); - }, - send: function (data, callback) { - var self = this; - this.outputBuffer.push({'data': data, 'callback': callback}); - - function send() { - // store inside separate variables in case array gets destroyed - var data = self.outputBuffer[0].data, - callback = self.outputBuffer[0].callback; - - chrome.serial.send(self.connectionId, data, function (sendInfo) { - // track sent bytes for statistics - self.bytesSent += sendInfo.bytesSent; - - // fire callback - if (callback) callback(sendInfo); - - // remove data for current transmission form the buffer - self.outputBuffer.shift(); - - // if there is any data in the queue fire send immediately, otherwise stop trasmitting - if (self.outputBuffer.length) { - // keep the buffer withing reasonable limits - if (self.outputBuffer.length > 100) { - var counter = 0; - - while (self.outputBuffer.length > 100) { - self.outputBuffer.pop(); - counter++; - } - - console.log('SERIAL: Send buffer overflowing, dropped: ' + counter + ' entries'); - } - - send(); - } else { - self.transmitting = false; - } - }); - } - - if (!this.transmitting) { - this.transmitting = true; - send(); - } - }, - onReceive: { - listeners: [], - - addListener: function (function_reference) { - chrome.serial.onReceive.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.onReceive.removeListener(function_reference); - - this.listeners.splice(i, 1); - break; - } - } - } - }, - onReceiveError: { - listeners: [], - - addListener: function (function_reference) { - 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; - } - } - } - }, - emptyOutputBuffer: function () { - this.outputBuffer = []; - this.transmitting = false; - }, - - /** - * Default timeout value for serial messages - * @returns {number} [ms] - */ - getTimeout: function () { - if (serial.bitrate >= 57600) { - return 3000; - } else { - return 4000; - } - } - -}; \ No newline at end of file diff --git a/js/serial_backend.js b/js/serial_backend.js index b39f1bec..c6d1220c 100755 --- a/js/serial_backend.js +++ b/js/serial_backend.js @@ -72,20 +72,45 @@ $(document).ready(function () { } }; + + GUI.updateManualPortVisibility = function(){ var selected_port = $port.find('option:selected'); - if (selected_port.data().isManual) { + if (selected_port.data().isManual || selected_port.data().isTcp || selected_port.data().isUdp) { $('#port-override-option').show(); } else { $('#port-override-option').hide(); } - if (selected_port.data().isDFU) { + + if (selected_port.data().isTcp || selected_port.data().isUdp) { + $('#port-override-label').text("IP:Port"); + } else { + $('#port-override-label').text("Port"); + } + + if (selected_port.data().isDFU || selected_port.data().isBle || selected_port.data().isTcp || selected_port.data().isUdp) { $baud.hide(); } else { $baud.show(); + } + + if (selected_port.data().isBle || selected_port.data().isTcp || selected_port.data().isUdp) { + $('.tab_firmware_flasher').hide(); + } else { + $('.tab_firmware_flasher').show(); } + var type = ConnectionType.Serial; + if (selected_port.data().isBle) { + type = ConnectionType.BLE; + } else if (selected_port.data().isTcp) { + type = ConnectionType.TCP; + } else if (selected_port.data().isUdp) { + type = ConnectionType.UDP; + } + CONFIGURATOR.connection = Connection.create(type); + }; GUI.updateManualPortVisibility(); @@ -110,6 +135,7 @@ $(document).ready(function () { var selected_port = $port.find('option:selected').data().isManual ? $portOverride.val() : String($port.val()); + if (selected_port === 'DFU') { GUI.log(chrome.i18n.getMessage('dfu_connect_message')); } @@ -122,7 +148,11 @@ $(document).ready(function () { $('#port, #baud, #delay').prop('disabled', true); $('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connecting')); - serial.connect(selected_port, {bitrate: selected_baud}, onOpen); + if (selected_port == 'tcp' || selected_port == 'udp') { + CONFIGURATOR.connection.connect($portOverride.val(), {}, onOpen); + } else { + CONFIGURATOR.connection.connect(selected_port, {bitrate: selected_baud}, onOpen); + } } else { var wasConnected = CONFIGURATOR.connectionValid; @@ -135,6 +165,7 @@ $(document).ready(function () { } else { GUI.tab_switch_cleanup(); finishDisconnect(); + } function finishDisconnect() { @@ -150,7 +181,7 @@ $(document).ready(function () { helper.mspQueue.freeHardLock(); helper.mspQueue.freeSoftLock(); - serial.disconnect(onClosed); + CONFIGURATOR.connection.disconnect(onClosed); MSP.disconnect_cleanup(); // Reset various UI elements @@ -235,6 +266,12 @@ function onInvalidFirmwareVersion() $('#tabs .tab_cli a').click(); } +function onBleNotSupported() { + GUI.log(chrome.i18n.getMessage('connectionBleNotSupported')); + CONFIGURATOR.connection.abort(); +} + + function onOpen(openInfo) { if (FC.restartRequired) { @@ -265,10 +302,10 @@ function onOpen(openInfo) { } }); - chrome.storage.local.set({last_used_bps: serial.bitrate}); + chrome.storage.local.set({last_used_bps: CONFIGURATOR.connection.bitrate}); chrome.storage.local.set({wireless_mode_enabled: $('#wireless-mode').is(":checked")}); - serial.onReceive.addListener(read_serial); + CONFIGURATOR.connection.addOnReceiveListener(read_serial); // disconnect after 10 seconds with error if we don't get IDENT data helper.timeout.add('connecting', function () { @@ -278,7 +315,7 @@ function onOpen(openInfo) { helper.mspQueue.flush(); helper.mspQueue.freeHardLock(); helper.mspQueue.freeSoftLock(); - serial.emptyOutputBuffer(); + CONFIGURATOR.connection.emptyOutputBuffer(); $('div.connect_controls a').click(); // disconnect } @@ -305,12 +342,16 @@ function onOpen(openInfo) { googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion); GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion])); if (semver.gte(CONFIG.flightControllerVersion, CONFIGURATOR.minfirmwareVersionAccepted) && semver.lt(CONFIG.flightControllerVersion, CONFIGURATOR.maxFirmwareVersionAccepted)) { - mspHelper.getCraftName(function(name) { - if (name) { - CONFIG.name = name; - } - onValidFirmware(); - }); + if (CONFIGURATOR.connection.type == ConnectionType.BLE && semver.lt(CONFIG.flightControllerVersion, "5.0.0")) { + onBleNotSupported(); + } else { + mspHelper.getCraftName(function(name) { + if (name) { + CONFIG.name = name; + } + onValidFirmware(); + }); + } } else { onInvalidFirmwareVersion(); } @@ -372,7 +413,7 @@ function onConnect() { $('#drop-rate').text("Drop ratio: " + helper.mspQueue.getDropRatio().toFixed(0) + "%"); }, 100); - helper.interval.add('global_data_refresh', helper.periodicStatusUpdater.run, helper.periodicStatusUpdater.getUpdateInterval(serial.bitrate), false); + helper.interval.add('global_data_refresh', helper.periodicStatusUpdater.run, helper.periodicStatusUpdater.getUpdateInterval(CONFIGURATOR.connection.bitrate), false); } function onClosed(result) { diff --git a/js/serial_queue.js b/js/serial_queue.js index 0c6b14cd..60cb1a56 100644 --- a/js/serial_queue.js +++ b/js/serial_queue.js @@ -2,7 +2,7 @@ var helper = helper || {}; -helper.mspQueue = (function (serial, MSP) { +helper.mspQueue = (function (MSP) { var publicScope = {}, privateScope = {}; @@ -101,7 +101,7 @@ helper.mspQueue = (function (serial, MSP) { if (code == MSPCodes.MSP_SET_REBOOT || code == MSPCodes.MSP_EEPROM_WRITE) { return 5000; } else { - return serial.getTimeout(); + return CONFIGURATOR.connection.getTimeout(); } }; @@ -128,7 +128,7 @@ helper.mspQueue = (function (serial, MSP) { /* * if port is blocked or there is no connection, do not process the queue */ - if (publicScope.isLocked() || serial.connectionId === false) { + if (publicScope.isLocked() || CONFIGURATOR.connection === false) { helper.eventFrequencyAnalyzer.put("port in use"); return false; } @@ -178,7 +178,7 @@ helper.mspQueue = (function (serial, MSP) { /* * Send data to serial port */ - serial.send(request.messageBody, function (sendInfo) { + CONFIGURATOR.connection.send(request.messageBody, function (sendInfo) { if (sendInfo.bytesSent == request.messageBody.byteLength) { /* * message has been sent, check callbacks and free resource @@ -305,4 +305,4 @@ helper.mspQueue = (function (serial, MSP) { setInterval(publicScope.balancer, Math.round(1000 / privateScope.balancerFrequency)); return publicScope; -})(serial, MSP); \ No newline at end of file +})(MSP); \ No newline at end of file diff --git a/main.css b/main.css index 42a4630c..33f54e7d 100644 --- a/main.css +++ b/main.css @@ -211,7 +211,7 @@ input[type="number"]::-webkit-inner-spin-button { position: relative; overflow: hidden; height: 20px; - width: 140px !important; + width: 180px !important; margin-bottom: 7px; border: 1px solid; border-radius: 3px; @@ -235,7 +235,7 @@ input[type="number"]::-webkit-inner-spin-button { #port-override { background-color: rgba(0, 0, 0, 0.1); color: #888888; - width: 90px; + width: 120px; margin-left: 2px; margin-top: 0; padding: 1px; diff --git a/main.html b/main.html index 3d46a306..71da7b46 100755 --- a/main.html +++ b/main.html @@ -43,7 +43,7 @@