Merge pull request #2308 from haslinghuis/msp

10.8-maintenance
Michael Keller 2020-12-16 14:43:50 +01:00 committed by GitHub
commit 92faf5fcdf
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
4 changed files with 270 additions and 283 deletions

View File

@ -1,6 +1,6 @@
'use strict'; 'use strict';
var MSP = { const MSP = {
symbols: { symbols: {
BEGIN: '$'.charCodeAt(0), BEGIN: '$'.charCodeAt(0),
PROTO_V1: 'M'.charCodeAt(0), PROTO_V1: 'M'.charCodeAt(0),
@ -56,17 +56,17 @@ var MSP = {
JUMBO_FRAME_SIZE_LIMIT: 255, JUMBO_FRAME_SIZE_LIMIT: 255,
read: function (readInfo) { read: function (readInfo) {
var data = new Uint8Array(readInfo.data); const data = new Uint8Array(readInfo.data);
for (var i = 0; i < data.length; i++) { for (const chunk of data) {
switch (this.state) { switch (this.state) {
case this.decoder_states.IDLE: // sync char 1 case this.decoder_states.IDLE: // sync char 1
if (data[i] === this.symbols.BEGIN) { if (chunk === this.symbols.BEGIN) {
this.state = this.decoder_states.PROTO_IDENTIFIER; this.state = this.decoder_states.PROTO_IDENTIFIER;
} }
break; break;
case this.decoder_states.PROTO_IDENTIFIER: // sync char 2 case this.decoder_states.PROTO_IDENTIFIER: // sync char 2
switch (data[i]) { switch (chunk) {
case this.symbols.PROTO_V1: case this.symbols.PROTO_V1:
this.state = this.decoder_states.DIRECTION_V1; this.state = this.decoder_states.DIRECTION_V1;
break; break;
@ -74,14 +74,14 @@ var MSP = {
this.state = this.decoder_states.DIRECTION_V2; this.state = this.decoder_states.DIRECTION_V2;
break; break;
default: default:
console.log(`Unknown protocol char ${String.fromCharCode(data[i])}`); console.log(`Unknown protocol char ${String.fromCharCode(chunk)}`);
this.state = this.decoder_states.IDLE; this.state = this.decoder_states.IDLE;
} }
break; break;
case this.decoder_states.DIRECTION_V1: // direction (should be >) case this.decoder_states.DIRECTION_V1: // direction (should be >)
case this.decoder_states.DIRECTION_V2: case this.decoder_states.DIRECTION_V2:
this.unsupported = 0; this.unsupported = 0;
switch (data[i]) { switch (chunk) {
case this.symbols.FROM_MWC: case this.symbols.FROM_MWC:
this.message_direction = 1; this.message_direction = 1;
break; break;
@ -101,7 +101,7 @@ var MSP = {
this.state = this.decoder_states.CODE_V2_LOW; this.state = this.decoder_states.CODE_V2_LOW;
break; break;
case this.decoder_states.PAYLOAD_LENGTH_V1: case this.decoder_states.PAYLOAD_LENGTH_V1:
this.message_length_expected = data[i]; this.message_length_expected = chunk;
if (this.message_length_expected === this.constants.JUMBO_FRAME_MIN_SIZE) { if (this.message_length_expected === this.constants.JUMBO_FRAME_MIN_SIZE) {
this.state = this.decoder_states.CODE_JUMBO_V1; this.state = this.decoder_states.CODE_JUMBO_V1;
@ -112,11 +112,11 @@ var MSP = {
break; break;
case this.decoder_states.PAYLOAD_LENGTH_V2_LOW: case this.decoder_states.PAYLOAD_LENGTH_V2_LOW:
this.message_length_expected = data[i]; this.message_length_expected = chunk;
this.state = this.decoder_states.PAYLOAD_LENGTH_V2_HIGH; this.state = this.decoder_states.PAYLOAD_LENGTH_V2_HIGH;
break; break;
case this.decoder_states.PAYLOAD_LENGTH_V2_HIGH: case this.decoder_states.PAYLOAD_LENGTH_V2_HIGH:
this.message_length_expected |= data[i] << 8; this.message_length_expected |= chunk << 8;
this._initialize_read_buffer(); this._initialize_read_buffer();
this.state = this.message_length_expected > 0 ? this.state = this.message_length_expected > 0 ?
this.decoder_states.PAYLOAD_V2 : this.decoder_states.PAYLOAD_V2 :
@ -124,7 +124,7 @@ var MSP = {
break; break;
case this.decoder_states.CODE_V1: case this.decoder_states.CODE_V1:
case this.decoder_states.CODE_JUMBO_V1: case this.decoder_states.CODE_JUMBO_V1:
this.code = data[i]; this.code = chunk;
if (this.message_length_expected > 0) { if (this.message_length_expected > 0) {
// process payload // process payload
if (this.state === this.decoder_states.CODE_JUMBO_V1) { if (this.state === this.decoder_states.CODE_JUMBO_V1) {
@ -138,25 +138,25 @@ var MSP = {
} }
break; break;
case this.decoder_states.CODE_V2_LOW: case this.decoder_states.CODE_V2_LOW:
this.code = data[i]; this.code = chunk;
this.state = this.decoder_states.CODE_V2_HIGH; this.state = this.decoder_states.CODE_V2_HIGH;
break; break;
case this.decoder_states.CODE_V2_HIGH: case this.decoder_states.CODE_V2_HIGH:
this.code |= data[i] << 8; this.code |= chunk << 8;
this.state = this.decoder_states.PAYLOAD_LENGTH_V2_LOW; this.state = this.decoder_states.PAYLOAD_LENGTH_V2_LOW;
break; break;
case this.decoder_states.PAYLOAD_LENGTH_JUMBO_LOW: case this.decoder_states.PAYLOAD_LENGTH_JUMBO_LOW:
this.message_length_expected = data[i]; this.message_length_expected = chunk;
this.state = this.decoder_states.PAYLOAD_LENGTH_JUMBO_HIGH; this.state = this.decoder_states.PAYLOAD_LENGTH_JUMBO_HIGH;
break; break;
case this.decoder_states.PAYLOAD_LENGTH_JUMBO_HIGH: case this.decoder_states.PAYLOAD_LENGTH_JUMBO_HIGH:
this.message_length_expected |= data[i] << 8; this.message_length_expected |= chunk << 8;
this._initialize_read_buffer(); this._initialize_read_buffer();
this.state = this.decoder_states.PAYLOAD_V1; this.state = this.decoder_states.PAYLOAD_V1;
break; break;
case this.decoder_states.PAYLOAD_V1: case this.decoder_states.PAYLOAD_V1:
case this.decoder_states.PAYLOAD_V2: case this.decoder_states.PAYLOAD_V2:
this.message_buffer_uint8_view[this.message_length_received] = data[i]; this.message_buffer_uint8_view[this.message_length_received] = chunk;
this.message_length_received++; this.message_length_received++;
if (this.message_length_received >= this.message_length_expected) { if (this.message_length_received >= this.message_length_expected) {
@ -179,7 +179,7 @@ var MSP = {
for (let ii = 0; ii < this.message_length_received; ii++) { for (let ii = 0; ii < this.message_length_received; ii++) {
this.message_checksum ^= this.message_buffer_uint8_view[ii]; this.message_checksum ^= this.message_buffer_uint8_view[ii];
} }
this._dispatch_message(data[i]); this._dispatch_message(chunk);
break; break;
case this.decoder_states.CHECKSUM_V2: case this.decoder_states.CHECKSUM_V2:
this.message_checksum = 0; this.message_checksum = 0;
@ -191,7 +191,7 @@ var MSP = {
for (let ii = 0; ii < this.message_length_received; ii++) { for (let ii = 0; ii < this.message_length_received; ii++) {
this.message_checksum = this.crc8_dvb_s2(this.message_checksum, this.message_buffer_uint8_view[ii]); this.message_checksum = this.crc8_dvb_s2(this.message_checksum, this.message_buffer_uint8_view[ii]);
} }
this._dispatch_message(data[i]); this._dispatch_message(chunk);
break; break;
default: default:
console.log(`Unknown state detected: ${this.state}`); console.log(`Unknown state detected: ${this.state}`);
@ -212,16 +212,16 @@ var MSP = {
this.crcError = true; this.crcError = true;
this.dataView = new DataView(new ArrayBuffer(0)); this.dataView = new DataView(new ArrayBuffer(0));
} }
this.notify();
// Reset variables // Reset variables
this.message_length_received = 0; this.message_length_received = 0;
this.state = 0; this.state = 0;
this.messageIsJumboFrame = false; this.messageIsJumboFrame = false;
this.notify();
this.crcError = false; this.crcError = false;
}, },
notify: function() { notify: function() {
var self = this; const self = this;
this.listeners.forEach(function(listener) { self.listeners.forEach(function(listener) {
listener(self); listener(self);
}); });
}, },
@ -255,8 +255,8 @@ var MSP = {
let bufferOut; let bufferOut;
// always reserve 6 bytes for protocol overhead ! // always reserve 6 bytes for protocol overhead !
if (data) { if (data) {
var size = data.length + 6, const size = data.length + 6;
checksum = 0; let checksum = 0;
bufferOut = new ArrayBuffer(size); bufferOut = new ArrayBuffer(size);
let bufView = new Uint8Array(bufferOut); let bufView = new Uint8Array(bufferOut);
@ -269,7 +269,7 @@ var MSP = {
checksum = bufView[3] ^ bufView[4]; checksum = bufView[3] ^ bufView[4];
for (var i = 0; i < data.length; i++) { for (let i = 0; i < data.length; i++) {
bufView[i + 5] = data[i]; bufView[i + 5] = data[i];
checksum ^= bufView[i + 5]; checksum ^= bufView[i + 5];
@ -320,11 +320,11 @@ var MSP = {
bufferOut = this.encode_message_v2(code, data); bufferOut = this.encode_message_v2(code, data);
} }
var obj = {'code': code, 'requestBuffer': bufferOut, 'callback': callback_msp ? callback_msp : false, 'timer': false, 'callbackOnError': doCallbackOnError}; const obj = {'code': code, 'requestBuffer': bufferOut, 'callback': callback_msp ? callback_msp : false, 'timer': false, 'callbackOnError': doCallbackOnError};
var requestExists = false; let requestExists = false;
for (var i = 0; i < MSP.callbacks.length; i++) { for (const value of MSP.callbacks) {
if (MSP.callbacks[i].code == code) { if (value.code === code) {
// request already exist, we will just attach // request already exist, we will just attach
requestExists = true; requestExists = true;
break; break;
@ -333,7 +333,7 @@ var MSP = {
if (!requestExists) { if (!requestExists) {
obj.timer = setInterval(function () { obj.timer = setInterval(function () {
console.log(`MSP data request timed-out: ${code}`); console.log(`MSP data request timed-out: ${code} direction: ${MSP.message_direction} tab: ${GUI.active_tab}`);
serial.send(bufferOut, false); serial.send(bufferOut, false);
}, 1000); // we should be able to define timeout in the future }, 1000); // we should be able to define timeout in the future
@ -359,16 +359,16 @@ var MSP = {
* resolves: {command: code, data: data, length: message_length} * resolves: {command: code, data: data, length: message_length}
*/ */
promise: function(code, data) { promise: function(code, data) {
var self = this; const self = this;
return new Promise(function(resolve) { return new Promise(function(resolve) {
self.send_message(code, data, false, function(data) { self.send_message(code, data, false, function(_data) {
resolve(data); resolve(_data);
}); });
}); });
}, },
callbacks_cleanup: function () { callbacks_cleanup: function () {
for (var i = 0; i < this.callbacks.length; i++) { for (let index = 0; index < this.callbacks.length; index++) {
clearInterval(this.callbacks[i].timer); clearInterval(this.callbacks[index].timer);
} }
this.callbacks = []; this.callbacks = [];

View File

@ -1,7 +1,7 @@
'use strict'; 'use strict';
//MSPCodes needs to be re-integrated inside MSP object //MSPCodes needs to be re-integrated inside MSP object
var MSPCodes = { const MSPCodes = {
MSP_API_VERSION: 1, MSP_API_VERSION: 1,
MSP_FC_VARIANT: 2, MSP_FC_VARIANT: 2,
MSP_FC_VERSION: 3, MSP_FC_VERSION: 3,

View File

@ -1,6 +1,6 @@
'use strict'; 'use strict';
var MSPConnectorImpl = function () { const MSPConnectorImpl = function () {
this.baud = undefined; this.baud = undefined;
this.port = undefined; this.port = undefined;
this.onConnectCallback = undefined; this.onConnectCallback = undefined;
@ -10,7 +10,7 @@ var MSPConnectorImpl = function () {
MSPConnectorImpl.prototype.connect = function (port, baud, onConnectCallback, onTimeoutCallback, onFailureCallback) { MSPConnectorImpl.prototype.connect = function (port, baud, onConnectCallback, onTimeoutCallback, onFailureCallback) {
var self = this; const self = this;
self.port = port; self.port = port;
self.baud = baud; self.baud = baud;
self.onConnectCallback = onConnectCallback; self.onConnectCallback = onConnectCallback;
@ -19,7 +19,7 @@ MSPConnectorImpl.prototype.connect = function (port, baud, onConnectCallback, on
serial.connect(self.port, {bitrate: self.baud}, function (openInfo) { serial.connect(self.port, {bitrate: self.baud}, function (openInfo) {
if (openInfo) { if (openInfo) {
var disconnectAndCleanup = function() { const disconnectAndCleanup = function() {
serial.disconnect(function(result) { serial.disconnect(function(result) {
console.log('Disconnected'); console.log('Disconnected');
@ -44,7 +44,7 @@ MSPConnectorImpl.prototype.connect = function (port, baud, onConnectCallback, on
serial.onReceive.addListener(read_serial); serial.onReceive.addListener(read_serial);
mspHelper = new MspHelper(); const mspHelper = new MspHelper();
MSP.listen(mspHelper.process_data.bind(mspHelper)); MSP.listen(mspHelper.process_data.bind(mspHelper));
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () { MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
@ -74,4 +74,3 @@ MSPConnectorImpl.prototype.disconnect = function(onDisconnectCallback) {
MSP.disconnect_cleanup(); MSP.disconnect_cleanup();
}; };

File diff suppressed because it is too large Load Diff