1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-24 16:55:22 +03:00

BLE, TCP and UDP Support

This commit is contained in:
Andi Kanzler 2022-03-31 16:18:46 +02:00
parent 1322fd69bd
commit ab7162980b
24 changed files with 1190 additions and 387 deletions

299
js/connection/connection.js Normal file
View file

@ -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;
}
}
}

View file

@ -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);
}
}

View file

@ -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);
}
}

View file

@ -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);
}
}

View file

@ -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);
}
}