Merge pull request #1851 from fiam/agh_cf_serial_config

[MSP] Use MSP2_COMMON[_SET]_SERIAL_CONFIG for configuring ports
10.7.0-preview
Michael Keller 2020-01-26 12:48:05 +13:00 committed by GitHub
commit cee091f103
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
8 changed files with 360 additions and 165 deletions

View File

@ -89,4 +89,8 @@ DataView.prototype.read32 = function() {
} else {
return null;
}
};
};
DataView.prototype.remaining = function() {
return this.byteLength - this.offset;
};

View File

@ -1,6 +1,39 @@
'use strict';
var MSP = {
symbols: {
BEGIN: '$'.charCodeAt(0),
PROTO_V1: 'M'.charCodeAt(0),
PROTO_V2: 'X'.charCodeAt(0),
FROM_MWC: '>'.charCodeAt(0),
TO_MWC: '<'.charCodeAt(0),
UNSUPPORTED: '!'.charCodeAt(0),
},
constants: {
PROTOCOL_V1: 1,
PROTOCOL_V2: 2,
JUMBO_FRAME_MIN_SIZE: 255,
},
decoder_states: {
IDLE: 0,
PROTO_IDENTIFIER: 1,
DIRECTION_V1: 2,
DIRECTION_V2: 3,
FLAG_V2: 4,
PAYLOAD_LENGTH_V1: 5,
PAYLOAD_LENGTH_JUMBO_LOW: 6,
PAYLOAD_LENGTH_JUMBO_HIGH: 7,
PAYLOAD_LENGTH_V2_LOW: 8,
PAYLOAD_LENGTH_V2_HIGH: 9,
CODE_V1: 10,
CODE_JUMBO_V1: 11,
CODE_V2_LOW: 12,
CODE_V2_HIGH: 13,
PAYLOAD_V1: 14,
PAYLOAD_V2: 15,
CHECKSUM_V1: 16,
CHECKSUM_V2: 17,
},
state: 0,
message_direction: 1,
code: 0,
@ -27,112 +60,166 @@ var MSP = {
for (var i = 0; i < data.length; i++) {
switch (this.state) {
case 0: // sync char 1
if (data[i] == 36) { // $
this.state++;
}
break;
case 1: // sync char 2
if (data[i] == 77) { // M
this.state++;
} else { // restart and try again
this.state = 0;
}
break;
case 2: // direction (should be >)
this.unsupported = 0;
if (data[i] == 62) { // >
case this.decoder_states.IDLE: // sync char 1
if (data[i] === this.symbols.BEGIN) {
this.state = this.decoder_states.PROTO_IDENTIFIER;
}
break;
case this.decoder_states.PROTO_IDENTIFIER: // sync char 2
switch (data[i]) {
case this.symbols.PROTO_V1:
this.state = this.decoder_states.DIRECTION_V1;
break;
case this.symbols.PROTO_V2:
this.state = this.decoder_states.DIRECTION_V2;
break;
default:
console.log(`Unknown protocol char ${String.fromCharCode(data[i])}`);
this.state = this.decoder_states.IDLE;
}
break;
case this.decoder_states.DIRECTION_V1: // direction (should be >)
case this.decoder_states.DIRECTION_V2:
this.unsupported = 0;
switch (data[i]) {
case this.symbols.FROM_MWC:
this.message_direction = 1;
} else if (data[i] == 60) { // <
break;
case this.symbols.TO_MWC:
this.message_direction = 0;
} else if (data[i] == 33) { // !
// FC reports unsupported message error
break;
case this.symbols.UNSUPPORTED:
this.unsupported = 1;
}
break;
}
this.state = this.state === this.decoder_states.DIRECTION_V1 ?
this.decoder_states.PAYLOAD_LENGTH_V1 :
this.decoder_states.FLAG_V2;
break;
case this.decoder_states.FLAG_V2:
// Ignored for now
this.state = this.decoder_states.CODE_V2_LOW;
break;
case this.decoder_states.PAYLOAD_LENGTH_V1:
this.message_length_expected = data[i];
this.state++;
break;
case 3:
this.message_length_expected = data[i];
if (this.message_length_expected === this.JUMBO_FRAME_SIZE_LIMIT) {
this.messageIsJumboFrame = true;
}
if (this.message_length_expected === this.constants.JUMBO_FRAME_MIN_SIZE) {
this.state = this.decoder_states.CODE_JUMBO_V1;
} else {
this._initialize_read_buffer();
this.state = this.decoder_states.CODE_V1;
}
this.message_checksum = data[i];
this.state++;
break;
case 4:
this.code = data[i];
this.message_checksum ^= data[i];
if (this.message_length_expected > 0) {
// process payload
if (this.messageIsJumboFrame) {
this.state++;
} else {
this.state = this.state + 3;
}
break;
case this.decoder_states.PAYLOAD_LENGTH_V2_LOW:
this.message_length_expected = data[i];
this.state = this.decoder_states.PAYLOAD_LENGTH_V2_HIGH;
break;
case this.decoder_states.PAYLOAD_LENGTH_V2_HIGH:
this.message_length_expected |= data[i] << 8;
this._initialize_read_buffer();
this.state = this.message_length_expected > 0 ?
this.decoder_states.PAYLOAD_V2 :
this.decoder_states.CHECKSUM_V2;
break;
case this.decoder_states.CODE_V1:
case this.decoder_states.CODE_JUMBO_V1:
this.code = data[i];
if (this.message_length_expected > 0) {
// process payload
if (this.state === this.decoder_states.CODE_JUMBO_V1) {
this.state = this.decoder_states.PAYLOAD_LENGTH_JUMBO_LOW;
} else {
// no payload
this.state += 5;
this.state = this.decoder_states.PAYLOAD_V1;
}
break;
case 5:
this.message_length_expected = data[i];
} else {
// no payload
this.state = this.decoder_states.CHECKSUM_V1;
}
break;
case this.decoder_states.CODE_V2_LOW:
this.code = data[i];
this.state = this.decoder_states.CODE_V2_HIGH;
break;
case this.decoder_states.CODE_V2_HIGH:
this.code |= data[i] << 8;
this.state = this.decoder_states.PAYLOAD_LENGTH_V2_LOW;
break;
case this.decoder_states.PAYLOAD_LENGTH_JUMBO_LOW:
this.message_length_expected = data[i];
this.state = this.decoder_states.PAYLOAD_LENGTH_JUMBO_HIGH;
break;
case this.decoder_states.PAYLOAD_LENGTH_JUMBO_HIGH:
this.message_length_expected |= data[i] << 8;
this._initialize_read_buffer();
this.state = this.decoder_states.PAYLOAD_V1;
break;
case this.decoder_states.PAYLOAD_V1:
case this.decoder_states.PAYLOAD_V2:
this.message_buffer_uint8_view[this.message_length_received] = data[i];
this.message_length_received++;
this.message_checksum ^= data[i];
this.state++;
break;
case 6:
this.message_length_expected = this.message_length_expected + 256 * data[i];
this.message_checksum ^= data[i];
this.state++;
break;
case 7:
// setup arraybuffer
this.message_buffer = new ArrayBuffer(this.message_length_expected);
this.message_buffer_uint8_view = new Uint8Array(this.message_buffer);
this.state++;
case 8: // payload
this.message_buffer_uint8_view[this.message_length_received] = data[i];
this.message_checksum ^= data[i];
this.message_length_received++;
if (this.message_length_received >= this.message_length_expected) {
this.state++;
}
break;
case 9:
if (this.message_checksum == data[i]) {
// message received, store dataview
this.dataView = new DataView(this.message_buffer, 0, this.message_length_expected);
} else {
console.log('code: ' + this.code + ' - crc failed');
this.packet_error++;
this.crcError = true;
this.dataView = new DataView(new ArrayBuffer(0));
}
// Reset variables
this.message_length_received = 0;
this.state = 0;
this.messageIsJumboFrame = false;
this.notify();
this.crcError = false;
break;
default:
console.log('Unknown state detected: ' + this.state);
if (this.message_length_received >= this.message_length_expected) {
this.state = this.state === this.decoder_states.PAYLOAD_V1 ?
this.decoder_states.CHECKSUM_V1 :
this.decoder_states.CHECKSUM_V2;
}
break;
case this.decoder_states.CHECKSUM_V1:
if (this.message_length_expected >= this.constants.JUMBO_FRAME_MIN_SIZE) {
this.message_checksum = this.constants.JUMBO_FRAME_MIN_SIZE;
} else {
this.message_checksum = this.message_length_expected;
}
this.message_checksum ^= this.code;
if (this.message_length_expected >= this.constants.JUMBO_FRAME_MIN_SIZE) {
this.message_checksum ^= this.message_length_expected & 0xFF;
this.message_checksum ^= (this.message_length_expected & 0xFF00) >> 8;
}
for (let ii = 0; ii < this.message_length_received; ii++) {
this.message_checksum ^= this.message_buffer_uint8_view[ii];
}
this._dispatch_message(data[i]);
break;
case this.decoder_states.CHECKSUM_V2:
this.message_checksum = 0;
this.message_checksum = this.crc8_dvb_s2(this.message_checksum, 0); // flag
this.message_checksum = this.crc8_dvb_s2(this.message_checksum, this.code & 0xFF);
this.message_checksum = this.crc8_dvb_s2(this.message_checksum, (this.code & 0xFF00) >> 8);
this.message_checksum = this.crc8_dvb_s2(this.message_checksum, this.message_length_expected & 0xFF);
this.message_checksum = this.crc8_dvb_s2(this.message_checksum, (this.message_length_expected & 0xFF00) >> 8);
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._dispatch_message(data[i]);
break;
default:
console.log(`Unknown state detected: ${this.state}`);
}
}
this.last_received_timestamp = Date.now();
},
_initialize_read_buffer: function() {
this.message_buffer = new ArrayBuffer(this.message_length_expected);
this.message_buffer_uint8_view = new Uint8Array(this.message_buffer);
},
_dispatch_message: function(expectedChecksum) {
if (this.message_checksum === expectedChecksum) {
// message received, store dataview
this.dataView = new DataView(this.message_buffer, 0, this.message_length_expected);
} else {
console.log(`code: ${this.code} - crc failed`);
this.packet_error++;
this.crcError = true;
this.dataView = new DataView(new ArrayBuffer(0));
}
// Reset variables
this.message_length_received = 0;
this.state = 0;
this.messageIsJumboFrame = false;
this.notify();
this.crcError = false;
},
notify: function() {
var self = this;
this.listeners.forEach(function(listener) {
@ -147,13 +234,26 @@ var MSP = {
clearListeners: function() {
this.listeners = [];
},
send_message: function (code, data, callback_sent, callback_msp, doCallbackOnError) {
if (code === undefined) {
return;
crc8_dvb_s2: function(crc, ch) {
crc ^= ch;
for (let ii = 0; ii < 8; ii++) {
if (crc & 0x80) {
crc = ((crc << 1) & 0xFF) ^ 0xD5;
} else {
crc = (crc << 1) & 0xFF;
}
}
return crc;
},
crc8_dvb_s2_data: function(data, start, end) {
let crc = 0;
for (let ii = start; ii < end; ii++) {
crc = this.crc8_dvb_s2(crc, data[ii]);
}
return crc;
},
encode_message_v1: function(code, data) {
let bufferOut;
// always reserve 6 bytes for protocol overhead !
if (data) {
var size = data.length + 6,
@ -188,6 +288,38 @@ var MSP = {
bufView[4] = code; // code
bufView[5] = bufView[3] ^ bufView[4]; // checksum
}
return bufferOut;
},
encode_message_v2: function (code, data) {
const dataLength = data ? data.length : 0;
// 9 bytes for protocol overhead
const bufferSize = dataLength + 9;
const bufferOut = new ArrayBuffer(bufferSize);
const bufView = new Uint8Array(bufferOut);
bufView[0] = 36; // $
bufView[1] = 88; // X
bufView[2] = 60; // <
bufView[3] = 0; // flag
bufView[4] = code & 0xFF;
bufView[5] = (code >> 8) & 0xFF;
bufView[6] = dataLength & 0xFF;
bufView[7] = (dataLength >> 8) & 0xFF;
for (let ii = 0; ii < dataLength; ii++) {
bufView[8 + ii] = data[ii];
}
bufView[bufferSize - 1] = this.crc8_dvb_s2_data(bufView, 3, bufferSize - 1);
return bufferOut;
},
send_message: function (code, data, callback_sent, callback_msp, doCallbackOnError) {
if (code === undefined) {
return;
}
let bufferOut;
if (code <= 254) {
bufferOut = this.encode_message_v1(code, data);
} else {
bufferOut = this.encode_message_v2(code, data);
}
var obj = {'code': code, 'requestBuffer': bufferOut, 'callback': callback_msp ? callback_msp : false, 'timer': false, 'callbackOnError': doCallbackOnError};
@ -202,7 +334,7 @@ var MSP = {
if (!requestExists) {
obj.timer = setInterval(function () {
console.log('MSP data request timed-out: ' + code);
console.log(`MSP data request timed-out: ${code}`);
serial.send(bufferOut, false);
}, 1000); // we should be able to define timeout in the future

View File

@ -171,5 +171,9 @@ var MSPCodes = {
MSP_EEPROM_WRITE: 250,
MSP_DEBUGMSG: 253, // Not used
MSP_DEBUG: 254
MSP_DEBUG: 254,
// MSPv2
MSP2_COMMON_SERIAL_CONFIG: 0x1009,
MSP2_COMMON_SET_SERIAL_CONFIG: 0x100A,
};

View File

@ -99,7 +99,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
// Read flight mode flags
var byteCount = data.readU8();
for (var i = 0; i < byteCount; i++) {
for (let i = 0; i < byteCount; i++) {
data.readU8();
}
@ -136,13 +136,13 @@ MspHelper.prototype.process_data = function(dataHandler) {
break;
case MSPCodes.MSP_SERVO:
var servoCount = data.byteLength / 2;
for (var i = 0; i < servoCount; i++) {
for (let i = 0; i < servoCount; i++) {
SERVO_DATA[i] = data.readU16();
}
break;
case MSPCodes.MSP_MOTOR:
var motorCount = data.byteLength / 2;
for (var i = 0; i < motorCount; i++) {
for (let i = 0; i < motorCount; i++) {
MOTOR_DATA[i] = data.readU16();
}
break;
@ -159,7 +159,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
break;
case MSPCodes.MSP_RC:
RC.active_channels = data.byteLength / 2;
for (var i = 0; i < RC.active_channels; i++) {
for (let i = 0; i < RC.active_channels; i++) {
RC.channels[i] = data.readU16();
}
break;
@ -201,7 +201,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_VOLTAGE_METERS:
VOLTAGE_METERS = [];
var voltageMeterLength = 2;
for (var i = 0; i < (data.byteLength / voltageMeterLength); i++) {
for (let i = 0; i < (data.byteLength / voltageMeterLength); i++) {
var voltageMeter = {};
voltageMeter.id = data.readU8();
voltageMeter.voltage = data.readU8() / 10.0;
@ -213,7 +213,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
CURRENT_METERS = [];
var currentMeterLength = 5;
for (var i = 0; i < (data.byteLength / currentMeterLength); i++) {
for (let i = 0; i < (data.byteLength / currentMeterLength); i++) {
var currentMeter = {};
currentMeter.id = data.readU8();
currentMeter.mAhDrawn = data.readU16(); // mAh
@ -248,7 +248,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
VOLTAGE_METER_CONFIGS = [];
var voltage_meter_count = data.readU8();
for (var i = 0; i < voltage_meter_count; i++) {
for (let i = 0; i < voltage_meter_count; i++) {
var subframe_length = data.readU8();
if (subframe_length != 5) {
for (var j = 0; j < subframe_length; j++) {
@ -277,7 +277,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
var offset = 0;
CURRENT_METER_CONFIGS = [];
var current_meter_count = data.readU8();
for (var i = 0; i < current_meter_count; i++) {
for (let i = 0; i < current_meter_count; i++) {
var currentMeterConfig = {};
var subframe_length = data.readU8();
@ -360,7 +360,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
break;
case MSPCodes.MSP_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (var i = 0, needle = 0; i < (data.byteLength / 3); i++, needle += 3) {
for (let i = 0, needle = 0; i < (data.byteLength / 3); i++, needle += 3) {
// main for loop selecting the pid section
for (var j = 0; j < 3; j++) {
PIDS_ACTIVE[i][j] = data.readU8();
@ -463,7 +463,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
AUX_CONFIG = []; // empty the array as new data is coming in
var buff = [];
for (var i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
var char = data.readU8();
if (char == 0x3B) { // ; (delimeter char)
AUX_CONFIG.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
@ -479,7 +479,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
PID_names = []; // empty the array as new data is coming in
var buff = [];
for (var i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
var char = data.readU8();
if (char == 0x3B) { // ; (delimeter char)
PID_names.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
@ -494,7 +494,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_BOXIDS:
AUX_CONFIG_IDS = []; // empty the array as new data is coming in
for (var i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
AUX_CONFIG_IDS.push(data.readU8());
}
break;
@ -505,7 +505,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
SERVO_CONFIG = []; // empty the array as new data is coming in
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
if (data.byteLength % 12 == 0) {
for (var i = 0; i < data.byteLength; i += 12) {
for (let i = 0; i < data.byteLength; i += 12) {
var arr = {
'min': data.readU16(),
'max': data.readU16(),
@ -520,7 +520,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
}
} else if (semver.gte(CONFIG.apiVersion, "1.12.0")) {
if (data.byteLength % 14 == 0) {
for (var i = 0; i < data.byteLength; i += 14) {
for (let i = 0; i < data.byteLength; i += 14) {
var arr = {
'min': data.readU16(),
'max': data.readU16(),
@ -537,7 +537,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
}
} else {
if (data.byteLength % 7 == 0) {
for (var i = 0; i < data.byteLength; i += 7) {
for (let i = 0; i < data.byteLength; i += 7) {
var arr = {
'min': data.readU16(),
'max': data.readU16(),
@ -632,7 +632,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
console.log('Voltage config saved');
case MSPCodes.MSP_DEBUG:
for (var i = 0; i < 4; i++)
for (let i = 0; i < 4; i++)
SENSOR_DATA.debug[i] = data.read16();
break;
case MSPCodes.MSP_SET_MOTOR:
@ -654,7 +654,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
if (data.byteLength > 0) {
var numCh = data.readU8();
for (var i = 0; i < numCh; i++) {
for (let i = 0; i < numCh; i++) {
GPS_DATA.chn[i] = data.readU8();
GPS_DATA.svid[i] = data.readU8();
GPS_DATA.quality[i] = data.readU8();
@ -666,7 +666,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_RX_MAP:
RC_MAP = []; // empty the array as new data is coming in
for (var i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
RC_MAP.push(data.readU8());
}
break;
@ -725,7 +725,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_FC_VARIANT:
var identifier = '';
for (var i = 0; i < 4; i++) {
for (let i = 0; i < 4; i++) {
identifier += String.fromCharCode(data.readU8());
}
CONFIG.flightControllerIdentifier = identifier;
@ -738,13 +738,13 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_BUILD_INFO:
var dateLength = 11;
var buff = [];
for (var i = 0; i < dateLength; i++) {
for (let i = 0; i < dateLength; i++) {
buff.push(data.readU8());
}
buff.push(32); // ascii space
var timeLength = 8;
for (var i = 0; i < timeLength; i++) {
for (let i = 0; i < timeLength; i++) {
buff.push(data.readU8());
}
CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
@ -752,7 +752,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_BOARD_INFO:
var identifier = '';
for (var i = 0; i < 4; i++) {
for (let i = 0; i < 4; i++) {
identifier += String.fromCharCode(data.readU8());
}
CONFIG.boardIdentifier = identifier;
@ -821,9 +821,9 @@ MspHelper.prototype.process_data = function(dataHandler) {
case MSPCodes.MSP_CF_SERIAL_CONFIG:
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
SERIAL_CONFIG.ports = [];
var serialPortCount = (data.byteLength - (4 * 4)) / 2;
for (var i = 0; i < serialPortCount; i++) {
var serialPort = {
const serialPortCount = (data.byteLength - (4 * 4)) / 2;
for (let i = 0; i < serialPortCount; i++) {
const serialPort = {
identifier: data.readU8(),
scenario: data.readU8()
}
@ -835,11 +835,11 @@ MspHelper.prototype.process_data = function(dataHandler) {
SERIAL_CONFIG.gpsPassthroughBaudRate = data.readU32();
} else {
SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 2 + (1 * 4);
var serialPortCount = data.byteLength / bytesPerPort;
const bytesPerPort = 1 + 2 + (1 * 4);
for (var i = 0; i < serialPortCount; i++) {
var serialPort = {
const serialPortCount = data.byteLength / bytesPerPort;
for (let i = 0; i < serialPortCount; i++) {
const serialPort = {
identifier: data.readU8(),
functions: self.serialPortFunctionMaskToFunctions(data.readU16()),
msp_baudrate: self.BAUD_RATES[data.readU8()],
@ -853,16 +853,40 @@ MspHelper.prototype.process_data = function(dataHandler) {
}
break;
case MSPCodes.MSP2_COMMON_SERIAL_CONFIG:
const count = data.readU8();
const portConfigSize = data.remaining() / count;
for (let ii = 0; ii < count; ii++) {
const start = data.remaining();
const serialPort = {
identifier: data.readU8(),
functions: self.serialPortFunctionMaskToFunctions(data.readU32()),
msp_baudrate: self.BAUD_RATES[data.readU8()],
gps_baudrate: self.BAUD_RATES[data.readU8()],
telemetry_baudrate: self.BAUD_RATES[data.readU8()],
blackbox_baudrate: self.BAUD_RATES[data.readU8()],
};
SERIAL_CONFIG.ports.push(serialPort);
while(start - data.remaining() < portConfigSize && data.remaining() > 0) {
data.readU8();
}
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
console.log('Serial config saved');
break;
case MSPCodes.MSP2_COMMON_SET_SERIAL_CONFIG:
console.log('Serial config saved (MSPv2)');
break;
case MSPCodes.MSP_MODE_RANGES:
MODE_RANGES = []; // empty the array as new data is coming in
var modeRangeCount = data.byteLength / 4; // 4 bytes per item.
for (var i = 0; i < modeRangeCount; i++) {
for (let i = 0; i < modeRangeCount; i++) {
var modeRange = {
id: data.readU8(),
auxChannelIndex: data.readU8(),
@ -880,7 +904,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
var modeRangeExtraCount = data.readU8();
for (var i = 0; i < modeRangeExtraCount; i++) {
for (let i = 0; i < modeRangeExtraCount; i++) {
var modeRangeExtra = {
id: data.readU8(),
modeLogic: data.readU8(),
@ -895,7 +919,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
var adjustmentRangeCount = data.byteLength / 6; // 6 bytes per item.
for (var i = 0; i < adjustmentRangeCount; i++) {
for (let i = 0; i < adjustmentRangeCount; i++) {
var adjustmentRange = {
slotIndex: data.readU8(),
auxChannelIndex: data.readU8(),
@ -969,7 +993,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
RXFAIL_CONFIG = []; // empty the array as new data is coming in
var channelCount = data.byteLength / 3;
for (var i = 0; i < channelCount; i++) {
for (let i = 0; i < channelCount; i++) {
var rxfailChannel = {
mode: data.readU8(),
value: data.readU16()
@ -1150,7 +1174,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
// Following byte is the current LED profile
ledCount = (data.byteLength - 2) / 4;
}
for (var i = 0; i < ledCount; i++) {
for (let i = 0; i < ledCount; i++) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
var directionMask = data.readU16();
@ -1162,7 +1186,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
}
}
var functionMask = data.readU16();
const functionMask = data.readU16();
var functions = [];
for (var functionLetterIndex = 0; functionLetterIndex < ledFunctionLetters.length; functionLetterIndex++) {
@ -1228,7 +1252,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
var colorCount = data.byteLength / 4;
for (var i = 0; i < colorCount; i++) {
for (let i = 0; i < colorCount; i++) {
var color = {
h: data.readU16(),
@ -1249,7 +1273,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
var colorCount = data.byteLength / 3;
for (var i = 0; i < colorCount; i++) {
for (let i = 0; i < colorCount; i++) {
var mode_color = {
mode: data.readU8(),
@ -1319,7 +1343,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
TRANSPONDER.supported = providerCount > 0;
TRANSPONDER.providers = [];
for (var i = 0; i < providerCount; i++) {
for (let i = 0; i < providerCount; i++) {
var provider = {
id: data.readU8(),
dataLength: data.readU8()
@ -1343,7 +1367,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
TRANSPONDER.provider = TRANSPONDER.providers[0].id;
}
TRANSPONDER.data = [];
for (var i = 0; i < bytesRemaining; i++) {
for (let i = 0; i < bytesRemaining; i++) {
TRANSPONDER.data.push(data.readU8());
}
break;
@ -1554,7 +1578,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
}
}
// trigger callbacks, cleanup/remove callback after trigger
for (var i = dataHandler.callbacks.length - 1; i >= 0; i--) { // itterating in reverse because we use .splice which modifies array length
for (let i = dataHandler.callbacks.length - 1; i >= 0; i--) { // itterating in reverse because we use .splice which modifies array length
if (dataHandler.callbacks[i].code == code) {
// save callback reference
var callback = dataHandler.callbacks[i].callback;
@ -1610,8 +1634,8 @@ MspHelper.prototype.crunch = function(code) {
buffer.push8(PID.controller);
break;
case MSPCodes.MSP_SET_PID:
for (var i = 0; i < PIDs.length; i++) {
for (var j = 0; j < 3; j++) {
for (let i = 0; i < PIDs.length; i++) {
for (let j = 0; j < 3; j++) {
buffer.push8(parseInt(PIDs[i][j]));
}
}
@ -1653,7 +1677,7 @@ MspHelper.prototype.crunch = function(code) {
}
break;
case MSPCodes.MSP_SET_RX_MAP:
for (var i = 0; i < RC_MAP.length; i++) {
for (let i = 0; i < RC_MAP.length; i++) {
buffer.push8(RC_MAP[i]);
}
break;
@ -1821,13 +1845,13 @@ MspHelper.prototype.crunch = function(code) {
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
buffer.push8(TRANSPONDER.provider); //
}
for (var i = 0; i < TRANSPONDER.data.length; i++) {
for (let i = 0; i < TRANSPONDER.data.length; i++) {
buffer.push8(TRANSPONDER.data[i]);
}
break;
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
for (var i = 0; i < SERVO_CONFIG.length; i++) {
for (let i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;
if (out == undefined) {
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
@ -1838,7 +1862,7 @@ MspHelper.prototype.crunch = function(code) {
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) {
for (let i = 0; i < SERIAL_CONFIG.ports.length; i++) {
buffer.push8(SERIAL_CONFIG.ports[i].scenario);
}
buffer.push32(SERIAL_CONFIG.mspBaudRate)
@ -1846,13 +1870,14 @@ MspHelper.prototype.crunch = function(code) {
.push32(SERIAL_CONFIG.gpsBaudRate)
.push32(SERIAL_CONFIG.gpsPassthroughBaudRate);
} else {
for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
for (let i = 0; i < SERIAL_CONFIG.ports.length; i++) {
const serialPort = SERIAL_CONFIG.ports[i];
buffer.push8(serialPort.identifier);
var functionMask = self.serialPortFunctionsToMask(serialPort.functions);
const functionMask = self.serialPortFunctionsToMask(serialPort.functions);
buffer.push16(functionMask)
.push8(self.BAUD_RATES.indexOf(serialPort.msp_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.msp_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.gps_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.telemetry_baudrate))
@ -1861,6 +1886,24 @@ MspHelper.prototype.crunch = function(code) {
}
break;
case MSPCodes.MSP2_COMMON_SET_SERIAL_CONFIG:
buffer.push8(SERIAL_CONFIG.ports.length);
for (let i = 0; i < SERIAL_CONFIG.ports.length; i++) {
const serialPort = SERIAL_CONFIG.ports[i];
buffer.push8(serialPort.identifier);
const functionMask = self.serialPortFunctionsToMask(serialPort.functions);
buffer.push32(functionMask)
.push8(self.BAUD_RATES.indexOf(serialPort.msp_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.msp_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.gps_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.telemetry_baudrate))
.push8(self.BAUD_RATES.indexOf(serialPort.blackbox_baudrate));
}
break;
case MSPCodes.MSP_SET_MOTOR_3D_CONFIG:
buffer.push16(MOTOR_3D_CONFIG.deadband3d_low)
.push16(MOTOR_3D_CONFIG.deadband3d_high)
@ -2043,7 +2086,7 @@ MspHelper.prototype.crunch = function(code) {
case MSPCodes.MSP_SET_NAME:
var MSP_BUFFER_SIZE = 64;
for (var i = 0; i<CONFIG.name.length && i<MSP_BUFFER_SIZE; i++) {
for (let i = 0; i<CONFIG.name.length && i<MSP_BUFFER_SIZE; i++) {
buffer.push8(CONFIG.name.charCodeAt(i));
}
break;
@ -2182,7 +2225,7 @@ MspHelper.prototype.crunch = function(code) {
MspHelper.prototype.setRawRx = function(channels) {
var buffer = [];
for (var i = 0; i < channels.length; i++) {
for (let i = 0; i < channels.length; i++) {
buffer.push16(channels[i]);
}
@ -2267,7 +2310,7 @@ MspHelper.prototype.sendServoConfigurations = function(onCompleteCallback) {
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
// send all in one go
// 1.9.0 had a bug where the MSP input buffer was too small, limit to 8.
for (var i = 0; i < SERVO_CONFIG.length && i < 8; i++) {
for (let i = 0; i < SERVO_CONFIG.length && i < 8; i++) {
buffer.push16(SERVO_CONFIG[i].min)
.push16(SERVO_CONFIG[i].max)
.push16(SERVO_CONFIG[i].middle)
@ -2309,7 +2352,7 @@ MspHelper.prototype.sendServoConfigurations = function(onCompleteCallback) {
function send_channel_forwarding() {
var buffer = [];
for (var i = 0; i < SERVO_CONFIG.length; i++) {
for (let i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;
if (out == undefined) {
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
@ -2495,7 +2538,7 @@ MspHelper.prototype.sendLedStripConfig = function(onCompleteCallback) {
}
buffer.push16(directionMask);
var functionMask = 0;
let functionMask = 0;
for (var functionLetterIndex = 0; functionLetterIndex < led.functions.length; functionLetterIndex++) {
var bitIndex = ledFunctionLetters.indexOf(led.functions[functionLetterIndex]);
if (bitIndex >= 0) {
@ -2690,6 +2733,16 @@ MspHelper.prototype.setArmingEnabled = function(doEnable, disableRunawayTakeoffP
}
}
MspHelper.prototype.loadSerialConfig = function(callback) {
const mspCode = semver.gte(CONFIG.apiVersion, "1.43.0") ? MSPCodes.MSP2_COMMON_SERIAL_CONFIG : MSPCodes.MSP_CF_SERIAL_CONFIG;
MSP.send_message(mspCode, false, false, callback);
};
MspHelper.prototype.sendSerialConfig = function(callback) {
const mspCode = semver.gte(CONFIG.apiVersion, "1.43.0") ? MSPCodes.MSP2_COMMON_SET_SERIAL_CONFIG : MSPCodes.MSP_SET_CF_SERIAL_CONFIG;
MSP.send_message(mspCode, mspHelper.crunch(mspCode), false, callback);
};
MSP.SDCARD_STATE_NOT_PRESENT = 0; //TODO, move these to better place
MSP.SDCARD_STATE_FATAL = 1;
MSP.SDCARD_STATE_CARD_INIT = 2;

View File

@ -29,7 +29,7 @@ TABS.auxiliary.initialize = function (callback) {
}
function get_serial_config() {
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, load_html);
mspHelper.loadSerialConfig(load_html);
}
function load_html() {

View File

@ -35,7 +35,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
}
function load_serial_config() {
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, load_board_alignment_config);
mspHelper.loadSerialConfig(load_board_alignment_config);
}
function load_board_alignment_config() {
@ -1210,7 +1210,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function save_serial_config() {
var next_callback = save_feature_config;
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, next_callback);
mspHelper.sendSerialConfig(next_callback);
}
function save_feature_config() {

View File

@ -39,7 +39,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
}
function get_ports_config() {
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, get_rc_data);
mspHelper.loadSerialConfig(get_rc_data);
}
function get_rc_data() {

View File

@ -111,13 +111,15 @@ TABS.ports.initialize = function (callback, scrollPosition) {
load_configuration_from_fc();
function load_configuration_from_fc() {
let promise;
if(semver.gte(CONFIG.apiVersion, "1.42.0")) {
MSP.promise(MSPCodes.MSP_VTX_CONFIG).then(function() {
return MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
});
promise = MSP.promise(MSPCodes.MSP_VTX_CONFIG);
} else {
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
promise = Promise.resolve();
}
promise.then(function() {
mspHelper.loadSerialConfig(on_configuration_loaded_handler);
});
function on_configuration_loaded_handler() {
$('#content').load("./tabs/ports.html", on_tab_loaded_handler);
@ -392,7 +394,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
SERIAL_CONFIG.ports.push(serialPort);
});
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
mspHelper.sendSerialConfig(save_to_eeprom);
function save_to_eeprom() {
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, on_saved_handler);