1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-14 20:10:11 +03:00

MSP sanity fixes

This commit is contained in:
Pawel Spychalski (DzikuVx) 2017-01-06 14:44:46 +01:00
parent 5bccc1798a
commit 3d47c137cf
2 changed files with 141 additions and 136 deletions

View file

@ -1,5 +1,9 @@
'use strict';
/**
*
* @typedef {{state: number, message_direction: number, code: number, message_length_expected: number, message_length_received: number, message_buffer: null, message_buffer_uint8_view: null, message_checksum: number, callbacks: Array, packet_error: number, unsupported: number, ledDirectionLetters: [*], ledFunctionLetters: [*], ledBaseFunctionLetters: [*], ledOverlayLetters: [*], last_received_timestamp: null, analog_last_received_timestamp: number, read: MSP.read, send_message: MSP.send_message, promise: MSP.promise, callbacks_cleanup: MSP.callbacks_cleanup, disconnect_cleanup: MSP.disconnect_cleanup}} MSP
*/
var MSP = {
state: 0,
message_direction: 1,

View file

@ -36,7 +36,8 @@ var mspHelper = (function (gui) {
var data = new DataView(dataHandler.message_buffer, 0), // DataView (allowing us to view arrayBuffer as struct/union)
offset = 0,
needle = 0,
i = 0;
i = 0,
buff = [];
if (!dataHandler.unsupported) switch (dataHandler.code) {
case MSPCodes.MSP_IDENT:
@ -45,13 +46,13 @@ var mspHelper = (function (gui) {
CONFIG.version = parseFloat((data.getUint8(0) / 100).toFixed(2));
CONFIG.multiType = data.getUint8(1);
CONFIG.msp_version = data.getUint8(2);
CONFIG.capability = data.getUint32(3, 1);
CONFIG.capability = data.getUint32(3, true);
break;
case MSPCodes.MSP_STATUS:
CONFIG.cycleTime = data.getUint16(0, 1);
CONFIG.i2cError = data.getUint16(2, 1);
CONFIG.activeSensors = data.getUint16(4, 1);
CONFIG.mode = data.getUint32(6, 1);
CONFIG.cycleTime = data.getUint16(0, true);
CONFIG.i2cError = data.getUint16(2, true);
CONFIG.activeSensors = data.getUint16(4, true);
CONFIG.mode = data.getUint32(6, true);
CONFIG.profile = data.getUint8(10);
gui.updateProfileChange();
gui.updateStatusBar();
@ -66,15 +67,15 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_STATUS_EX:
CONFIG.cycleTime = data.getUint16(0, 1);
CONFIG.i2cError = data.getUint16(2, 1);
CONFIG.activeSensors = data.getUint16(4, 1);
CONFIG.mode = data.getUint32(6, 1);
CONFIG.cycleTime = data.getUint16(0, true);
CONFIG.i2cError = data.getUint16(2, true);
CONFIG.activeSensors = data.getUint16(4, true);
CONFIG.mode = data.getUint32(6, true);
CONFIG.profile = data.getUint8(10);
CONFIG.cpuload = data.getUint16(11, 1);
CONFIG.cpuload = data.getUint16(11, true);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
CONFIG.armingFlags = data.getUint16(13, 2);
CONFIG.armingFlags = data.getUint16(13, true);
}
if (semver.lt(CONFIG.flightControllerVersion, "1.5.0")) {
@ -101,24 +102,24 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_RAW_IMU:
// 512 for mpu6050, 256 for mma
// currently we are unable to differentiate between the sensor types, so we are goign with 512
SENSOR_DATA.accelerometer[0] = data.getInt16(0, 1) / 512;
SENSOR_DATA.accelerometer[1] = data.getInt16(2, 1) / 512;
SENSOR_DATA.accelerometer[2] = data.getInt16(4, 1) / 512;
SENSOR_DATA.accelerometer[0] = data.getInt16(0, true) / 512;
SENSOR_DATA.accelerometer[1] = data.getInt16(2, true) / 512;
SENSOR_DATA.accelerometer[2] = data.getInt16(4, true) / 512;
// properly scaled
SENSOR_DATA.gyroscope[0] = data.getInt16(6, 1) * (4 / 16.4);
SENSOR_DATA.gyroscope[1] = data.getInt16(8, 1) * (4 / 16.4);
SENSOR_DATA.gyroscope[2] = data.getInt16(10, 1) * (4 / 16.4);
SENSOR_DATA.gyroscope[0] = data.getInt16(6, true) * (4 / 16.4);
SENSOR_DATA.gyroscope[1] = data.getInt16(8, true) * (4 / 16.4);
SENSOR_DATA.gyroscope[2] = data.getInt16(10, true) * (4 / 16.4);
// no clue about scaling factor
SENSOR_DATA.magnetometer[0] = data.getInt16(12, 1) / 1090;
SENSOR_DATA.magnetometer[1] = data.getInt16(14, 1) / 1090;
SENSOR_DATA.magnetometer[2] = data.getInt16(16, 1) / 1090;
SENSOR_DATA.magnetometer[0] = data.getInt16(12, true) / 1090;
SENSOR_DATA.magnetometer[1] = data.getInt16(14, true) / 1090;
SENSOR_DATA.magnetometer[2] = data.getInt16(16, true) / 1090;
break;
case MSPCodes.MSP_SERVO:
var servoCount = dataHandler.message_length_expected / 2;
for (i = 0; i < servoCount; i++) {
SERVO_DATA[i] = data.getUint16(needle, 1);
SERVO_DATA[i] = data.getUint16(needle, true);
needle += 2;
}
@ -126,7 +127,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_MOTOR:
var motorCount = dataHandler.message_length_expected / 2;
for (i = 0; i < motorCount; i++) {
MOTOR_DATA[i] = data.getUint16(needle, 1);
MOTOR_DATA[i] = data.getUint16(needle, true);
needle += 2;
}
@ -135,18 +136,18 @@ var mspHelper = (function (gui) {
RC.active_channels = dataHandler.message_length_expected / 2;
for (i = 0; i < RC.active_channels; i++) {
RC.channels[i] = data.getUint16((i * 2), 1);
RC.channels[i] = data.getUint16((i * 2), true);
}
break;
case MSPCodes.MSP_RAW_GPS:
GPS_DATA.fix = data.getUint8(0);
GPS_DATA.numSat = data.getUint8(1);
GPS_DATA.lat = data.getInt32(2, 1);
GPS_DATA.lon = data.getInt32(6, 1);
GPS_DATA.alt = data.getUint16(10, 1);
GPS_DATA.speed = data.getUint16(12, 1);
GPS_DATA.ground_course = data.getUint16(14, 1);
GPS_DATA.hdop = data.getUint16(16, 1);
GPS_DATA.lat = data.getInt32(2, true);
GPS_DATA.lon = data.getInt32(6, true);
GPS_DATA.alt = data.getUint16(10, true);
GPS_DATA.speed = data.getUint16(12, true);
GPS_DATA.ground_course = data.getUint16(14, true);
GPS_DATA.hdop = data.getUint16(16, true);
break;
case MSPCodes.MSP_COMP_GPS:
GPS_DATA.distanceToHome = data.getUint16(0, 1);
@ -154,30 +155,31 @@ var mspHelper = (function (gui) {
GPS_DATA.update = data.getUint8(4);
break;
case MSPCodes.MSP_GPSSTATISTICS:
GPS_DATA.messageDt = data.getUint16(0, 1);
GPS_DATA.errors = data.getUint32(2, 1);
GPS_DATA.timeouts = data.getUint32(6, 1);
GPS_DATA.packetCount = data.getUint32(10, 1);
GPS_DATA.hdop = data.getUint16(14, 1);
GPS_DATA.eph = data.getUint16(16, 1);
GPS_DATA.epv = data.getUint16(18, 1);
GPS_DATA.messageDt = data.getUint16(0, true);
GPS_DATA.errors = data.getUint32(2, true);
GPS_DATA.timeouts = data.getUint32(6, true);
GPS_DATA.packetCount = data.getUint32(10, true);
GPS_DATA.hdop = data.getUint16(14, true);
GPS_DATA.eph = data.getUint16(16, true);
GPS_DATA.epv = data.getUint16(18, true);
break;
case MSPCodes.MSP_ATTITUDE:
SENSOR_DATA.kinematics[0] = data.getInt16(0, 1) / 10.0; // x
SENSOR_DATA.kinematics[1] = data.getInt16(2, 1) / 10.0; // y
SENSOR_DATA.kinematics[2] = data.getInt16(4, 1); // z
SENSOR_DATA.kinematics[0] = data.getInt16(0, true) / 10.0; // x
SENSOR_DATA.kinematics[1] = data.getInt16(2, true) / 10.0; // y
SENSOR_DATA.kinematics[2] = data.getInt16(4, true); // z
break;
case MSPCodes.MSP_ALTITUDE:
SENSOR_DATA.altitude = parseFloat((data.getInt32(0, 1) / 100.0).toFixed(2)); // correct scale factor
SENSOR_DATA.altitude = parseFloat((data.getInt32(0, true) / 100.0).toFixed(2)); // correct scale factor
break;
case MSPCodes.MSP_SONAR:
SENSOR_DATA.sonar = data.getInt32(0, 1);
SENSOR_DATA.sonar = data.getInt32(0, true);
break;
case MSPCodes.MSP_ANALOG:
ANALOG.voltage = data.getUint8(0) / 10.0;
ANALOG.mAhdrawn = data.getUint16(1, 1);
ANALOG.rssi = data.getUint16(3, 1); // 0-1023
ANALOG.amperage = data.getInt16(5, 1) / 100; // A
ANALOG.mAhdrawn = data.getUint16(1, true);
ANALOG.rssi = data.getUint16(3, true); // 0-1023
ANALOG.amperage = data.getInt16(5, true) / 100; // A
//noinspection JSValidateTypes
dataHandler.analog_last_received_timestamp = Date.now();
break;
case MSPCodes.MSP_RC_TUNING:
@ -198,7 +200,7 @@ var mspHelper = (function (gui) {
RC_tuning.dynamic_THR_PID = parseInt(data.getUint8(offset++));
RC_tuning.throttle_MID = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
RC_tuning.throttle_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
RC_tuning.dynamic_THR_breakpoint = data.getUint16(offset, 1);
RC_tuning.dynamic_THR_breakpoint = data.getUint16(offset, true);
offset += 2;
RC_tuning.RC_YAW_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
break;
@ -211,22 +213,22 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_ARMING_CONFIG:
ARMING_CONFIG.auto_disarm_delay = data.getUint8(0, 1);
ARMING_CONFIG.auto_disarm_delay = data.getUint8(0);
ARMING_CONFIG.disarm_kill_switch = data.getUint8(1);
break;
case MSPCodes.MSP_LOOP_TIME:
FC_CONFIG.loopTime = data.getInt16(0, 1);
FC_CONFIG.loopTime = data.getInt16(0, true);
break;
case MSPCodes.MSP_MISC: // 22 bytes
MISC.midrc = data.getInt16(offset, 1);
MISC.midrc = data.getInt16(offset, true);
offset += 2;
MISC.minthrottle = data.getUint16(offset, 1); // 0-2000
MISC.minthrottle = data.getUint16(offset, true); // 0-2000
offset += 2;
MISC.maxthrottle = data.getUint16(offset, 1); // 0-2000
MISC.maxthrottle = data.getUint16(offset, true); // 0-2000
offset += 2;
MISC.mincommand = data.getUint16(offset, 1); // 0-2000
MISC.mincommand = data.getUint16(offset, true); // 0-2000
offset += 2;
MISC.failsafe_throttle = data.getUint16(offset, 1); // 1000-2000
MISC.failsafe_throttle = data.getUint16(offset, true); // 1000-2000
offset += 2;
MISC.gps_type = data.getUint8(offset++);
MISC.gps_baudrate = data.getUint8(offset++);
@ -236,21 +238,21 @@ var mspHelper = (function (gui) {
MISC.placeholder2 = data.getUint8(offset++);
MISC.mag_declination = data.getInt16(offset, 1) / 10; // -18000-18000
offset += 2;
MISC.vbatscale = data.getUint8(offset++, 1); // 10-200
MISC.vbatmincellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
MISC.vbatmaxcellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
MISC.vbatwarningcellvoltage = data.getUint8(offset++, 1) / 10; // 10-50
MISC.vbatscale = data.getUint8(offset++); // 10-200
MISC.vbatmincellvoltage = data.getUint8(offset++) / 10; // 10-50
MISC.vbatmaxcellvoltage = data.getUint8(offset++) / 10; // 10-50
MISC.vbatwarningcellvoltage = data.getUint8(offset++) / 10; // 10-50
break;
case MSPCodes.MSP_3D:
_3D.deadband3d_low = data.getUint16(offset, 1);
_3D.deadband3d_low = data.getUint16(offset, true);
offset += 2;
_3D.deadband3d_high = data.getUint16(offset, 1);
_3D.deadband3d_high = data.getUint16(offset, true);
offset += 2;
_3D.neutral3d = data.getUint16(offset, 1);
_3D.neutral3d = data.getUint16(offset, true);
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
offset += 2;
_3D.deadband3d_throttle = data.getUint16(offset, 1);
_3D.deadband3d_throttle = data.getUint16(offset, true);
}
break;
case MSPCodes.MSP_MOTOR_PINS:
@ -259,8 +261,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_BOXNAMES:
//noinspection JSUndeclaredVariable
AUX_CONFIG = []; // empty the array as new data is coming in
var buff = [];
buff = [];
for (i = 0; i < data.byteLength; i++) {
if (data.getUint8(i) == 0x3B) { // ; (delimeter char)
AUX_CONFIG.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
@ -309,9 +310,9 @@ var mspHelper = (function (gui) {
if (data.byteLength % 14 == 0) {
for (i = 0; i < data.byteLength; i += 14) {
var arr = {
'min': data.getInt16(i + 0, 1),
'max': data.getInt16(i + 2, 1),
'middle': data.getInt16(i + 4, 1),
'min': data.getInt16(i + 0, true),
'max': data.getInt16(i + 2, true),
'middle': data.getInt16(i + 4, true),
'rate': data.getInt8(i + 6),
'angleAtMin': data.getInt8(i + 7),
'angleAtMax': data.getInt8(i + 8),
@ -324,14 +325,14 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_RC_DEADBAND:
RC_deadband.deadband = data.getUint8(offset++, 1);
RC_deadband.yaw_deadband = data.getUint8(offset++, 1);
RC_deadband.alt_hold_deadband = data.getUint8(offset++, 1);
RC_deadband.deadband = data.getUint8(offset++);
RC_deadband.yaw_deadband = data.getUint8(offset++);
RC_deadband.alt_hold_deadband = data.getUint8(offset++);
break;
case MSPCodes.MSP_SENSOR_ALIGNMENT:
SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++, 1);
SENSOR_ALIGNMENT.align_acc = data.getUint8(offset++, 1);
SENSOR_ALIGNMENT.align_mag = data.getUint8(offset++, 1);
SENSOR_ALIGNMENT.align_gyro = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_acc = data.getUint8(offset++);
SENSOR_ALIGNMENT.align_mag = data.getUint8(offset++);
break;
case MSPCodes.MSP_SET_RAW_RC:
break;
@ -375,13 +376,13 @@ var mspHelper = (function (gui) {
break;
// Additional baseflight commands that are not compatible with MultiWii
case MSPCodes.MSP_UID:
CONFIG.uid[0] = data.getUint32(0, 1);
CONFIG.uid[1] = data.getUint32(4, 1);
CONFIG.uid[2] = data.getUint32(8, 1);
CONFIG.uid[0] = data.getUint32(0, true);
CONFIG.uid[1] = data.getUint32(4, true);
CONFIG.uid[2] = data.getUint32(8, true);
break;
case MSPCodes.MSP_ACC_TRIM:
CONFIG.accelerometerTrims[0] = data.getInt16(0, 1); // pitch
CONFIG.accelerometerTrims[1] = data.getInt16(2, 1); // roll
CONFIG.accelerometerTrims[0] = data.getInt16(0, true); // pitch
CONFIG.accelerometerTrims[1] = data.getInt16(2, true); // roll
break;
case MSPCodes.MSP_SET_ACC_TRIM:
console.log('Accelerometer trimms saved.');
@ -400,13 +401,13 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_BF_CONFIG:
BF_CONFIG.mixerConfiguration = data.getUint8(0);
BF_CONFIG.features = data.getUint32(1, 1);
BF_CONFIG.features = data.getUint32(1, true);
BF_CONFIG.serialrx_type = data.getUint8(5);
BF_CONFIG.board_align_roll = data.getInt16(6, 1); // -180 - 360
BF_CONFIG.board_align_pitch = data.getInt16(8, 1); // -180 - 360
BF_CONFIG.board_align_yaw = data.getInt16(10, 1); // -180 - 360
BF_CONFIG.currentscale = data.getInt16(12, 1);
BF_CONFIG.currentoffset = data.getUint16(14, 1);
BF_CONFIG.board_align_roll = data.getInt16(6, true); // -180 - 360
BF_CONFIG.board_align_pitch = data.getInt16(8, true); // -180 - 360
BF_CONFIG.board_align_yaw = data.getInt16(10, true); // -180 - 360
BF_CONFIG.currentscale = data.getInt16(12, true);
BF_CONFIG.currentoffset = data.getUint16(14, true);
break;
case MSPCodes.MSP_SET_BF_CONFIG:
break;
@ -471,12 +472,12 @@ var mspHelper = (function (gui) {
for (i = 0; i < serialPortCount; i++) {
var serialPort = {
identifier: data.getUint8(offset, 1),
functions: mspHelper.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, 1)),
msp_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 3, 1)],
gps_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 4, 1)],
telemetry_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 5, 1)],
blackbox_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 6, 1)]
identifier: data.getUint8(offset),
functions: mspHelper.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, true)),
msp_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 3)],
gps_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 4)],
telemetry_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 5)],
blackbox_baudrate: mspHelper.BAUD_RATES[data.getUint8(offset + 6)]
};
offset += bytesPerPort;
@ -496,11 +497,11 @@ var mspHelper = (function (gui) {
for (i = 0; offset < data.byteLength && i < modeRangeCount; i++) {
var modeRange = {
id: data.getUint8(offset++, 1),
auxChannelIndex: data.getUint8(offset++, 1),
id: data.getUint8(offset++),
auxChannelIndex: data.getUint8(offset++),
range: {
start: 900 + (data.getUint8(offset++, 1) * 25),
end: 900 + (data.getUint8(offset++, 1) * 25)
start: 900 + (data.getUint8(offset++) * 25),
end: 900 + (data.getUint8(offset++) * 25)
}
};
MODE_RANGES.push(modeRange);
@ -515,14 +516,14 @@ var mspHelper = (function (gui) {
for (i = 0; offset < data.byteLength && i < adjustmentRangeCount; i++) {
var adjustmentRange = {
slotIndex: data.getUint8(offset++, 1),
auxChannelIndex: data.getUint8(offset++, 1),
slotIndex: data.getUint8(offset++),
auxChannelIndex: data.getUint8(offset++),
range: {
start: 900 + (data.getUint8(offset++, 1) * 25),
end: 900 + (data.getUint8(offset++, 1) * 25)
start: 900 + (data.getUint8(offset++) * 25),
end: 900 + (data.getUint8(offset++) * 25)
},
adjustmentFunction: data.getUint8(offset++, 1),
auxSwitchChannelIndex: data.getUint8(offset++, 1)
adjustmentFunction: data.getUint8(offset++),
auxSwitchChannelIndex: data.getUint8(offset++)
};
ADJUSTMENT_RANGES.push(adjustmentRange);
}
@ -540,42 +541,42 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_RX_CONFIG:
RX_CONFIG.serialrx_provider = data.getUint8(offset, 1);
RX_CONFIG.serialrx_provider = data.getUint8(offset);
offset++;
RX_CONFIG.maxcheck = data.getUint16(offset, 1);
RX_CONFIG.maxcheck = data.getUint16(offset, true);
offset += 2;
RX_CONFIG.midrc = data.getUint16(offset, 1);
RX_CONFIG.midrc = data.getUint16(offset, true);
offset += 2;
RX_CONFIG.mincheck = data.getUint16(offset, 1);
RX_CONFIG.mincheck = data.getUint16(offset, true);
offset += 2;
RX_CONFIG.spektrum_sat_bind = data.getUint8(offset, 1);
RX_CONFIG.spektrum_sat_bind = data.getUint8(offset);
offset++;
RX_CONFIG.rx_min_usec = data.getUint16(offset, 1);
RX_CONFIG.rx_min_usec = data.getUint16(offset, true);
offset += 2;
RX_CONFIG.rx_max_usec = data.getUint16(offset, 1);
RX_CONFIG.rx_max_usec = data.getUint16(offset, true);
offset += 2;
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
offset += 4; // 4 null bytes for betaflight compatibility
RX_CONFIG.nrf24rx_protocol = data.getUint8(offset, 1);
RX_CONFIG.nrf24rx_protocol = data.getUint8(offset);
offset++;
RX_CONFIG.nrf24rx_id = data.getUint32(offset, 1);
RX_CONFIG.nrf24rx_id = data.getUint32(offset, true);
offset += 4;
}
break;
case MSPCodes.MSP_FAILSAFE_CONFIG:
FAILSAFE_CONFIG.failsafe_delay = data.getUint8(offset, 1);
FAILSAFE_CONFIG.failsafe_delay = data.getUint8(offset);
offset++;
FAILSAFE_CONFIG.failsafe_off_delay = data.getUint8(offset, 1);
FAILSAFE_CONFIG.failsafe_off_delay = data.getUint8(offset);
offset++;
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1);
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset);
offset += 2;
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1);
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset);
offset++;
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1);
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, true);
offset += 2;
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1);
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset);
offset++;
}
break;
@ -588,8 +589,8 @@ var mspHelper = (function (gui) {
for (i = 0; offset < data.byteLength && i < channelCount; i++, offset++) {
var rxfailChannel = {
mode: data.getUint8(offset++, 1),
value: data.getUint16(offset++, 1)
mode: data.getUint8(offset++),
value: data.getUint16(offset++, true)
};
RXFAIL_CONFIG.push(rxfailChannel);
}
@ -607,7 +608,7 @@ var mspHelper = (function (gui) {
for (i = 0; offset < data.byteLength && i < ledCount; i++) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
var directionMask = data.getUint16(offset, 1);
var directionMask = data.getUint16(offset, true);
offset += 2;
var directions = [];
@ -630,9 +631,9 @@ var mspHelper = (function (gui) {
var led = {
directions: directions,
functions: functions,
x: data.getUint8(offset++, 1),
y: data.getUint8(offset++, 1),
color: data.getUint8(offset++, 1)
x: data.getUint8(offset++),
y: data.getUint8(offset++),
color: data.getUint8(offset++)
};
LED_STRIP.push(led);
@ -688,9 +689,9 @@ var mspHelper = (function (gui) {
for (i = 0; offset < data.byteLength && i < colorCount; i++) {
var h = data.getUint16(offset, 1);
var s = data.getUint8(offset + 2, 1);
var v = data.getUint8(offset + 3, 1);
var h = data.getUint16(offset, true);
var s = data.getUint8(offset + 2);
var v = data.getUint8(offset + 3);
offset += 4;
var color = {
@ -716,9 +717,9 @@ var mspHelper = (function (gui) {
for (i = 0; offset < data.byteLength && i < colorCount; i++) {
var mode = data.getUint8(offset++, 1);
var direction = data.getUint8(offset++, 1);
var color = data.getUint8(offset++, 1);
var mode = data.getUint8(offset++);
var direction = data.getUint8(offset++);
var color = data.getUint8(offset++);
var mode_color = {
mode: mode,
@ -764,8 +765,8 @@ var mspHelper = (function (gui) {
SDCARD.supported = (flags & 0x01) != 0;
SDCARD.state = data.getUint8(1);
SDCARD.filesystemLastError = data.getUint8(2);
SDCARD.freeSizeKB = data.getUint32(3, 1);
SDCARD.totalSizeKB = data.getUint32(7, 1);
SDCARD.freeSizeKB = data.getUint32(3, true);
SDCARD.totalSizeKB = data.getUint32(7, true);
break;
case MSPCodes.MSP_BLACKBOX_CONFIG:
BLACKBOX.supported = (data.getUint8(0) & 1) != 0;
@ -789,19 +790,19 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_ADVANCED_CONFIG:
ADVANCED_CONFIG.gyroSyncDenominator = data.getUint8(offset, 1);
ADVANCED_CONFIG.gyroSyncDenominator = data.getUint8(offset);
offset++;
ADVANCED_CONFIG.pidProcessDenom = data.getUint8(offset, 1);
ADVANCED_CONFIG.pidProcessDenom = data.getUint8(offset);
offset++;
ADVANCED_CONFIG.useUnsyncedPwm = data.getUint8(offset, 1);
ADVANCED_CONFIG.useUnsyncedPwm = data.getUint8(offset);
offset++;
ADVANCED_CONFIG.motorPwmProtocol = data.getUint8(offset, 1);
ADVANCED_CONFIG.motorPwmProtocol = data.getUint8(offset);
offset++;
ADVANCED_CONFIG.motorPwmRate = data.getUint16(offset, 1);
ADVANCED_CONFIG.motorPwmRate = data.getUint16(offset, true);
offset += 2;
ADVANCED_CONFIG.servoPwmRate = data.getUint16(offset, 1);
ADVANCED_CONFIG.servoPwmRate = data.getUint16(offset, true);
offset += 2;
ADVANCED_CONFIG.gyroSync = data.getUint8(offset, 1);
ADVANCED_CONFIG.gyroSync = data.getUint8(offset);
break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
@ -809,7 +810,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_FILTER_CONFIG:
FILTER_CONFIG.gyroSoftLpfHz = data.getUint8(0, true);
FILTER_CONFIG.gyroSoftLpfHz = data.getUint8(0);
FILTER_CONFIG.dtermLpfHz = data.getUint16(1, true);
FILTER_CONFIG.yawLpfHz = data.getUint16(3, true);
/*