You cannot select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
inav-configurator/js/msp/MSPHelper.js

1605 lines
67 KiB
JavaScript

8 years ago
/*global $, SERVO_DATA, PID_names, ADJUSTMENT_RANGES, RXFAIL_CONFIG, SERVO_CONFIG*/
'use strict';
8 years ago
8 years ago
var mspHelper = (function (gui) {
8 years ago
var self = {};
self.BAUD_RATES = [
'AUTO',
'9600',
'19200',
'38400',
'57600',
'115200',
'230400',
8 years ago
'250000'
];
8 years ago
self.SERIAL_PORT_FUNCTIONS = {
'MSP': 0,
'GPS': 1,
'TELEMETRY_FRSKY': 2,
'TELEMETRY_HOTT': 3,
'TELEMETRY_LTM': 4, // LTM replaced MSP
'TELEMETRY_SMARTPORT': 5,
'RX_SERIAL': 6,
'BLACKBOX': 7,
'TELEMETRY_MAVLINK': 8,
8 years ago
'TELEMETRY_IBUS': 9
};
8 years ago
8 years ago
/**
*
* @param {MSP} dataHandler
*/
self.processData = function (dataHandler) {
var data = new DataView(dataHandler.message_buffer, 0), // DataView (allowing us to view arrayBuffer as struct/union)
offset = 0,
needle = 0,
i = 0;
8 years ago
8 years ago
if (!dataHandler.unsupported) switch (dataHandler.code) {
8 years ago
case MSPCodes.MSP_IDENT:
console.log('Using deprecated msp command: MSP_IDENT');
// Deprecated
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);
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.profile = data.getUint8(10);
8 years ago
gui.updateProfileChange();
gui.updateStatusBar();
8 years ago
sensor_status(CONFIG.activeSensors);
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.profile = data.getUint8(10);
CONFIG.cpuload = data.getUint16(11, 1);
sensor_status(CONFIG.activeSensors);
8 years ago
gui.updateStatusBar();
8 years ago
break;
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;
// 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);
// 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;
break;
case MSPCodes.MSP_SERVO:
8 years ago
var servoCount = dataHandler.message_length_expected / 2;
for (i = 0; i < servoCount; i++) {
8 years ago
SERVO_DATA[i] = data.getUint16(needle, 1);
needle += 2;
}
break;
case MSPCodes.MSP_MOTOR:
8 years ago
var motorCount = dataHandler.message_length_expected / 2;
for (i = 0; i < motorCount; i++) {
8 years ago
MOTOR_DATA[i] = data.getUint16(needle, 1);
needle += 2;
}
break;
case MSPCodes.MSP_RC:
8 years ago
RC.active_channels = dataHandler.message_length_expected / 2;
8 years ago
8 years ago
for (i = 0; i < RC.active_channels; i++) {
8 years ago
RC.channels[i] = data.getUint16((i * 2), 1);
}
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);
break;
case MSPCodes.MSP_COMP_GPS:
GPS_DATA.distanceToHome = data.getUint16(0, 1);
GPS_DATA.directionToHome = data.getUint16(2, 1);
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);
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
break;
case MSPCodes.MSP_ALTITUDE:
SENSOR_DATA.altitude = parseFloat((data.getInt32(0, 1) / 100.0).toFixed(2)); // correct scale factor
break;
case MSPCodes.MSP_SONAR:
SENSOR_DATA.sonar = data.getInt32(0, 1);
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
8 years ago
dataHandler.analog_last_received_timestamp = Date.now();
8 years ago
break;
case MSPCodes.MSP_RC_TUNING:
RC_tuning.RC_RATE = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
RC_tuning.RC_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
8 years ago
if (FC.isRatesInDps()) {
8 years ago
RC_tuning.roll_pitch_rate = 0;
RC_tuning.roll_rate = parseFloat((data.getUint8(offset++) * 10));
RC_tuning.pitch_rate = parseFloat((data.getUint8(offset++) * 10));
RC_tuning.yaw_rate = parseFloat((data.getUint8(offset++) * 10));
} else {
RC_tuning.roll_pitch_rate = 0;
RC_tuning.roll_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
RC_tuning.pitch_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
RC_tuning.yaw_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
}
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));
8 years ago
RC_tuning.dynamic_THR_breakpoint = data.getUint16(offset, 1);
offset += 2;
RC_tuning.RC_YAW_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
8 years ago
break;
case MSPCodes.MSP_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
8 years ago
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 3); i++, needle += 3) {
8 years ago
PIDs[i][0] = data.getUint8(needle);
PIDs[i][1] = data.getUint8(needle + 1);
PIDs[i][2] = data.getUint8(needle + 2);
}
break;
case MSPCodes.MSP_ARMING_CONFIG:
8 years ago
ARMING_CONFIG.auto_disarm_delay = data.getUint8(0, 1);
ARMING_CONFIG.disarm_kill_switch = data.getUint8(1);
8 years ago
break;
case MSPCodes.MSP_LOOP_TIME:
8 years ago
FC_CONFIG.loopTime = data.getInt16(0, 1);
8 years ago
break;
case MSPCodes.MSP_MISC: // 22 bytes
MISC.midrc = data.getInt16(offset, 1);
offset += 2;
MISC.minthrottle = data.getUint16(offset, 1); // 0-2000
offset += 2;
MISC.maxthrottle = data.getUint16(offset, 1); // 0-2000
offset += 2;
MISC.mincommand = data.getUint16(offset, 1); // 0-2000
offset += 2;
MISC.failsafe_throttle = data.getUint16(offset, 1); // 1000-2000
offset += 2;
MISC.gps_type = data.getUint8(offset++);
MISC.gps_baudrate = data.getUint8(offset++);
MISC.gps_ubx_sbas = data.getInt8(offset++);
MISC.multiwiicurrentoutput = data.getUint8(offset++);
MISC.rssi_channel = data.getUint8(offset++);
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
break;
case MSPCodes.MSP_3D:
_3D.deadband3d_low = data.getUint16(offset, 1);
offset += 2;
_3D.deadband3d_high = data.getUint16(offset, 1);
offset += 2;
_3D.neutral3d = data.getUint16(offset, 1);
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
offset += 2;
_3D.deadband3d_throttle = data.getUint16(offset, 1);
}
break;
case MSPCodes.MSP_MOTOR_PINS:
console.log(data);
break;
case MSPCodes.MSP_BOXNAMES:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
AUX_CONFIG = []; // empty the array as new data is coming in
var buff = [];
8 years ago
for (i = 0; i < data.byteLength; i++) {
8 years ago
if (data.getUint8(i) == 0x3B) { // ; (delimeter char)
AUX_CONFIG.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
// empty buffer
buff = [];
} else {
buff.push(data.getUint8(i));
}
}
break;
case MSPCodes.MSP_PIDNAMES:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
PID_names = []; // empty the array as new data is coming in
var buff = [];
8 years ago
for (i = 0; i < data.byteLength; i++) {
if (data.getUint8(i) == 0x3B) { // ; (delimiter char)
8 years ago
PID_names.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
// empty buffer
buff = [];
} else {
buff.push(data.getUint8(i));
}
}
break;
case MSPCodes.MSP_WP:
console.log(data);
break;
case MSPCodes.MSP_BOXIDS:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
AUX_CONFIG_IDS = []; // empty the array as new data is coming in
8 years ago
for (i = 0; i < data.byteLength; i++) {
8 years ago
AUX_CONFIG_IDS.push(data.getUint8(i));
}
break;
case MSPCodes.MSP_SERVO_MIX_RULES:
break;
case MSPCodes.MSP_SERVO_CONFIGURATIONS:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
SERVO_CONFIG = []; // empty the array as new data is coming in
8 years ago
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),
'rate': data.getInt8(i + 6),
'angleAtMin': data.getInt8(i + 7),
'angleAtMax': data.getInt8(i + 8),
'indexOfChannelToForward': data.getInt8(i + 9),
'reversedInputSources': data.getUint32(i + 10)
};
8 years ago
8 years ago
SERVO_CONFIG.push(arr);
8 years ago
}
}
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);
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);
break;
case MSPCodes.MSP_SET_RAW_RC:
break;
case MSPCodes.MSP_SET_RAW_GPS:
break;
case MSPCodes.MSP_SET_PID:
console.log('PID settings saved');
break;
case MSPCodes.MSP_SET_RC_TUNING:
console.log('RC Tuning saved');
break;
case MSPCodes.MSP_ACC_CALIBRATION:
8 years ago
console.log('Accelerometer calibration executed');
8 years ago
break;
case MSPCodes.MSP_MAG_CALIBRATION:
console.log('Mag calibration executed');
break;
case MSPCodes.MSP_SET_MISC:
console.log('MISC Configuration saved');
break;
case MSPCodes.MSP_RESET_CONF:
console.log('Settings Reset');
break;
case MSPCodes.MSP_SELECT_SETTING:
console.log('Profile selected');
break;
case MSPCodes.MSP_SET_SERVO_CONFIGURATION:
console.log('Servo Configuration saved');
break;
case MSPCodes.MSP_EEPROM_WRITE:
console.log('Settings Saved in EEPROM');
break;
case MSPCodes.MSP_DEBUGMSG:
break;
case MSPCodes.MSP_DEBUG:
8 years ago
for (i = 0; i < 4; i++)
8 years ago
SENSOR_DATA.debug[i] = data.getInt16((2 * i), 1);
break;
case MSPCodes.MSP_SET_MOTOR:
console.log('Motor Speeds Updated');
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);
break;
case MSPCodes.MSP_ACC_TRIM:
CONFIG.accelerometerTrims[0] = data.getInt16(0, 1); // pitch
CONFIG.accelerometerTrims[1] = data.getInt16(2, 1); // roll
break;
case MSPCodes.MSP_SET_ACC_TRIM:
console.log('Accelerometer trimms saved.');
break;
// Additional private MSP for baseflight configurator
case MSPCodes.MSP_RX_MAP:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
RC_MAP = []; // empty the array as new data is coming in
8 years ago
for (i = 0; i < data.byteLength; i++) {
8 years ago
RC_MAP.push(data.getUint8(i));
}
break;
case MSPCodes.MSP_SET_RX_MAP:
console.log('RCMAP saved');
break;
case MSPCodes.MSP_BF_CONFIG:
BF_CONFIG.mixerConfiguration = data.getUint8(0);
BF_CONFIG.features = data.getUint32(1, 1);
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);
break;
case MSPCodes.MSP_SET_BF_CONFIG:
break;
case MSPCodes.MSP_SET_REBOOT:
console.log('Reboot request accepted');
break;
//
// Cleanflight specific
//
case MSPCodes.MSP_API_VERSION:
CONFIG.mspProtocolVersion = data.getUint8(offset++);
CONFIG.apiVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.0';
break;
case MSPCodes.MSP_FC_VARIANT:
var identifier = '';
for (offset = 0; offset < 4; offset++) {
identifier += String.fromCharCode(data.getUint8(offset));
}
CONFIG.flightControllerIdentifier = identifier;
break;
case MSPCodes.MSP_FC_VERSION:
CONFIG.flightControllerVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.' + data.getUint8(offset++);
break;
case MSPCodes.MSP_BUILD_INFO:
var dateLength = 11;
var buff = [];
8 years ago
for (i = 0; i < dateLength; i++) {
8 years ago
buff.push(data.getUint8(offset++));
}
buff.push(32); // ascii space
var timeLength = 8;
8 years ago
for (i = 0; i < timeLength; i++) {
8 years ago
buff.push(data.getUint8(offset++));
}
CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
break;
case MSPCodes.MSP_BOARD_INFO:
var identifier = '';
for (offset = 0; offset < 4; offset++) {
identifier += String.fromCharCode(data.getUint8(offset));
}
CONFIG.boardIdentifier = identifier;
CONFIG.boardVersion = data.getUint16(offset, 1);
8 years ago
offset += 2;
8 years ago
break;
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
console.log('Channel forwarding saved');
break;
case MSPCodes.MSP_CF_SERIAL_CONFIG:
8 years ago
SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 2 + 4;
var serialPortCount = data.byteLength / bytesPerPort;
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)]
};
8 years ago
8 years ago
offset += bytesPerPort;
SERIAL_CONFIG.ports.push(serialPort);
8 years ago
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
console.log('Serial config saved');
break;
case MSPCodes.MSP_MODE_RANGES:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
MODE_RANGES = []; // empty the array as new data is coming in
var modeRangeCount = data.byteLength / 4; // 4 bytes per item.
8 years ago
for (i = 0; offset < data.byteLength && i < modeRangeCount; i++) {
8 years ago
var modeRange = {
id: data.getUint8(offset++, 1),
auxChannelIndex: data.getUint8(offset++, 1),
range: {
start: 900 + (data.getUint8(offset++, 1) * 25),
end: 900 + (data.getUint8(offset++, 1) * 25)
}
};
MODE_RANGES.push(modeRange);
}
break;
case MSPCodes.MSP_ADJUSTMENT_RANGES:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
ADJUSTMENT_RANGES = []; // empty the array as new data is coming in
var adjustmentRangeCount = data.byteLength / 6; // 6 bytes per item.
8 years ago
for (i = 0; offset < data.byteLength && i < adjustmentRangeCount; i++) {
8 years ago
var adjustmentRange = {
slotIndex: data.getUint8(offset++, 1),
auxChannelIndex: data.getUint8(offset++, 1),
range: {
start: 900 + (data.getUint8(offset++, 1) * 25),
end: 900 + (data.getUint8(offset++, 1) * 25)
},
adjustmentFunction: data.getUint8(offset++, 1),
auxSwitchChannelIndex: data.getUint8(offset++, 1)
};
ADJUSTMENT_RANGES.push(adjustmentRange);
}
break;
case MSPCodes.MSP_CHANNEL_FORWARDING:
8 years ago
for (i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i++) {
8 years ago
var channelIndex = data.getUint8(i);
if (channelIndex < 255) {
SERVO_CONFIG[i].indexOfChannelToForward = channelIndex;
} else {
SERVO_CONFIG[i].indexOfChannelToForward = undefined;
}
}
break;
case MSPCodes.MSP_RX_CONFIG:
RX_CONFIG.serialrx_provider = data.getUint8(offset, 1);
offset++;
RX_CONFIG.maxcheck = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.midrc = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.mincheck = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.spektrum_sat_bind = data.getUint8(offset, 1);
offset++;
RX_CONFIG.rx_min_usec = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.rx_max_usec = data.getUint16(offset, 1);
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);
offset++;
RX_CONFIG.nrf24rx_id = data.getUint32(offset, 1);
offset += 4;
}
break;
case MSPCodes.MSP_FAILSAFE_CONFIG:
FAILSAFE_CONFIG.failsafe_delay = data.getUint8(offset, 1);
offset++;
FAILSAFE_CONFIG.failsafe_off_delay = data.getUint8(offset, 1);
offset++;
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1);
offset += 2;
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1);
offset++;
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1);
offset += 2;
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1);
offset++;
}
break;
case MSPCodes.MSP_RXFAIL_CONFIG:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
RXFAIL_CONFIG = []; // empty the array as new data is coming in
var channelCount = data.byteLength / 3;
8 years ago
for (i = 0; offset < data.byteLength && i < channelCount; i++, offset++) {
8 years ago
var rxfailChannel = {
8 years ago
mode: data.getUint8(offset++, 1),
8 years ago
value: data.getUint16(offset++, 1)
};
RXFAIL_CONFIG.push(rxfailChannel);
}
break;
case MSPCodes.MSP_LED_STRIP_CONFIG:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
LED_STRIP = [];
var ledCount = data.byteLength / 7; // v1.4.0 and below incorrectly reported 4 bytes per led.
if (semver.gte(CONFIG.apiVersion, "1.20.0"))
ledCount = data.byteLength / 4;
8 years ago
for (i = 0; offset < data.byteLength && i < ledCount; i++) {
8 years ago
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
8 years ago
var directionMask = data.getUint16(offset, 1);
offset += 2;
var directions = [];
for (var directionLetterIndex = 0; directionLetterIndex < MSP.ledDirectionLetters.length; directionLetterIndex++) {
if (bit_check(directionMask, directionLetterIndex)) {
directions.push(MSP.ledDirectionLetters[directionLetterIndex]);
}
}
var functionMask = data.getUint16(offset, 1);
offset += 2;
var functions = [];
for (var functionLetterIndex = 0; functionLetterIndex < MSP.ledFunctionLetters.length; functionLetterIndex++) {
if (bit_check(functionMask, functionLetterIndex)) {
functions.push(MSP.ledFunctionLetters[functionLetterIndex]);
}
}
var led = {
directions: directions,
functions: functions,
x: data.getUint8(offset++, 1),
y: data.getUint8(offset++, 1),
color: data.getUint8(offset++, 1)
};
LED_STRIP.push(led);
8 years ago
} else {
var mask = data.getUint32(offset, 1);
8 years ago
offset += 4;
8 years ago
var functionId = (mask >> 8) & 0xF;
var functions = [];
for (var baseFunctionLetterIndex = 0; baseFunctionLetterIndex < MSP.ledBaseFunctionLetters.length; baseFunctionLetterIndex++) {
if (functionId == baseFunctionLetterIndex) {
functions.push(MSP.ledBaseFunctionLetters[baseFunctionLetterIndex]);
break;
}
8 years ago
}
8 years ago
var overlayMask = (mask >> 12) & 0x3F;
for (var overlayLetterIndex = 0; overlayLetterIndex < MSP.ledOverlayLetters.length; overlayLetterIndex++) {
if (bit_check(overlayMask, overlayLetterIndex)) {
functions.push(MSP.ledOverlayLetters[overlayLetterIndex]);
}
}
var directionMask = (mask >> 22) & 0x3F;
var directions = [];
for (var directionLetterIndex = 0; directionLetterIndex < MSP.ledDirectionLetters.length; directionLetterIndex++) {
if (bit_check(directionMask, directionLetterIndex)) {
directions.push(MSP.ledDirectionLetters[directionLetterIndex]);
}
}
var led = {
y: (mask) & 0xF,
x: (mask >> 4) & 0xF,
functions: functions,
color: (mask >> 18) & 0xF,
directions: directions,
parameters: (mask >> 28) & 0xF
};
LED_STRIP.push(led);
}
}
break;
case MSPCodes.MSP_SET_LED_STRIP_CONFIG:
console.log('Led strip config saved');
break;
case MSPCodes.MSP_LED_COLORS:
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
LED_COLORS = [];
var colorCount = data.byteLength / 4;
8 years ago
for (i = 0; offset < data.byteLength && i < colorCount; i++) {
8 years ago
var h = data.getUint16(offset, 1);
var s = data.getUint8(offset + 2, 1);
var v = data.getUint8(offset + 3, 1);
offset += 4;
var color = {
h: h,
s: s,
v: v
};
LED_COLORS.push(color);
}
break;
case MSPCodes.MSP_SET_LED_COLORS:
console.log('Led strip colors saved');
break;
case MSPCodes.MSP_LED_STRIP_MODECOLOR:
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
8 years ago
//noinspection JSUndeclaredVariable
8 years ago
LED_MODE_COLORS = [];
var colorCount = data.byteLength / 3;
8 years ago
for (i = 0; offset < data.byteLength && i < colorCount; i++) {
8 years ago
var mode = data.getUint8(offset++, 1);
var direction = data.getUint8(offset++, 1);
var color = data.getUint8(offset++, 1);
var mode_color = {
mode: mode,
direction: direction,
color: color
};
LED_MODE_COLORS.push(mode_color);
}
}
break;
case MSPCodes.MSP_SET_LED_STRIP_MODECOLOR:
console.log('Led strip mode colors saved');
break;
case MSPCodes.MSP_DATAFLASH_SUMMARY:
if (data.byteLength >= 13) {
8 years ago
var flags = data.getUint8(0);
8 years ago
DATAFLASH.ready = (flags & 1) != 0;
DATAFLASH.supported = (flags & 2) != 0 || DATAFLASH.ready;
DATAFLASH.sectors = data.getUint32(1, 1);
DATAFLASH.totalSize = data.getUint32(5, 1);
DATAFLASH.usedSize = data.getUint32(9, 1);
} else {
// Firmware version too old to support MSP_DATAFLASH_SUMMARY
DATAFLASH.ready = false;
DATAFLASH.supported = false;
DATAFLASH.sectors = 0;
DATAFLASH.totalSize = 0;
DATAFLASH.usedSize = 0;
}
update_dataflash_global();
break;
case MSPCodes.MSP_DATAFLASH_READ:
// No-op, let callback handle it
break;
case MSPCodes.MSP_DATAFLASH_ERASE:
console.log("Data flash erase begun...");
break;
case MSPCodes.MSP_SDCARD_SUMMARY:
var flags = data.getUint8(0);
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);
break;
case MSPCodes.MSP_BLACKBOX_CONFIG:
BLACKBOX.supported = (data.getUint8(0) & 1) != 0;
BLACKBOX.blackboxDevice = data.getUint8(1);
BLACKBOX.blackboxRateNum = data.getUint8(2);
BLACKBOX.blackboxRateDenom = data.getUint8(3);
break;
case MSPCodes.MSP_SET_BLACKBOX_CONFIG:
console.log("Blackbox config saved");
break;
case MSPCodes.MSP_TRANSPONDER_CONFIG:
TRANSPONDER.supported = (data.getUint8(offset++) & 1) != 0;
TRANSPONDER.data = [];
var bytesRemaining = data.byteLength - offset;
8 years ago
for (i = 0; i < bytesRemaining; i++) {
8 years ago
TRANSPONDER.data.push(data.getUint8(offset++));
}
break;
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
console.log("Transponder config saved");
break;
case MSPCodes.MSP_ADVANCED_CONFIG:
ADVANCED_CONFIG.gyroSyncDenominator = data.getUint8(offset, 1);
offset++;
ADVANCED_CONFIG.pidProcessDenom = data.getUint8(offset, 1);
offset++;
ADVANCED_CONFIG.useUnsyncedPwm = data.getUint8(offset, 1);
offset++;
ADVANCED_CONFIG.motorPwmProtocol = data.getUint8(offset, 1);
offset++;
ADVANCED_CONFIG.motorPwmRate = data.getUint16(offset, 1);
offset += 2;
ADVANCED_CONFIG.servoPwmRate = data.getUint16(offset, 1);
offset += 2;
ADVANCED_CONFIG.gyroSync = data.getUint8(offset, 1);
break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
console.log("Advanced config saved");
break;
case MSPCodes.MSP_FILTER_CONFIG:
8 years ago
FILTER_CONFIG.gyroSoftLpfHz = data.getUint8(0, true);
FILTER_CONFIG.dtermLpfHz = data.getUint16(1, true);
FILTER_CONFIG.yawLpfHz = data.getUint16(3, true);
8 years ago
/*
8 years ago
sbufWriteU16(dst, 1); //masterConfig.gyro_soft_notch_hz_1
sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_1
sbufWriteU16(dst, 1); //BF: currentProfile->pidProfile.dterm_notch_hz
sbufWriteU16(dst, 1); //currentProfile->pidProfile.dterm_notch_cutoff
sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_hz_2
sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_2
*/
8 years ago
break;
case MSPCodes.MSP_SET_FILTER_CONFIG:
console.log("Filter config saved");
break;
case MSPCodes.MSP_PID_ADVANCED:
8 years ago
PID_ADVANCED.rollPitchItermIgnoreRate = data.getUint16(0, true);
PID_ADVANCED.yawItermIgnoreRate = data.getUint16(2, true);
PID_ADVANCED.yawPLimit = data.getUint16(4, true);
PID_ADVANCED.axisAccelerationLimitRollPitch = data.getUint16(13, true);
PID_ADVANCED.axisAccelerationLimitYaw = data.getUint16(15, true);
8 years ago
break;
case MSPCodes.MSP_SET_PID_ADVANCED:
console.log("PID advanced saved");
break;
case MSPCodes.MSP_INAV_PID:
INAV_PID_CONFIG.asynchronousMode = data.getUint8(0);
INAV_PID_CONFIG.accelerometerTaskFrequency = data.getUint16(1, true);
INAV_PID_CONFIG.attitudeTaskFrequency = data.getUint16(3, true);
INAV_PID_CONFIG.magHoldRateLimit = data.getUint8(5);
INAV_PID_CONFIG.magHoldErrorLpfFrequency = data.getUint8(6);
INAV_PID_CONFIG.yawJumpPreventionLimit = data.getUint16(7, true);
INAV_PID_CONFIG.gyroscopeLpf = data.getUint8(9);
INAV_PID_CONFIG.accSoftLpfHz = data.getUint8(10);
break;
case MSPCodes.MSP_SET_INAV_PID:
console.log("MSP_INAV_PID saved");
break;
case MSPCodes.MSP_SET_MODE_RANGE:
console.log('Mode range saved');
break;
case MSPCodes.MSP_SET_ADJUSTMENT_RANGE:
console.log('Adjustment range saved');
break;
case MSPCodes.MSP_SET_LOOP_TIME:
console.log('Looptime saved');
break;
case MSPCodes.MSP_SET_ARMING_CONFIG:
console.log('Arming config saved');
break;
case MSPCodes.MSP_SET_RESET_CURR_PID:
console.log('Current PID profile reset');
break;
case MSPCodes.MSP_SET_3D:
console.log('3D settings saved');
break;
case MSPCodes.MSP_SET_RC_DEADBAND:
console.log('Rc controls settings saved');
break;
case MSPCodes.MSP_SET_SENSOR_ALIGNMENT:
console.log('Sensor alignment saved');
break;
case MSPCodes.MSP_SET_RX_CONFIG:
console.log('Rx config saved');
break;
case MSPCodes.MSP_SET_RXFAIL_CONFIG:
console.log('Rxfail config saved');
break;
case MSPCodes.MSP_SET_FAILSAFE_CONFIG:
console.log('Failsafe config saved');
break;
case MSPCodes.MSP_OSD_CONFIG:
break;
8 years ago
case MSPCodes.MSP_SET_OSD_CONFIG:
console.log('OSD config set');
break;
case MSPCodes.MSP_OSD_CHAR_READ:
break;
case MSPCodes.MSP_OSD_CHAR_WRITE:
console.log('OSD char uploaded');
break;
8 years ago
default:
8 years ago
console.log('Unknown code detected: ' + dataHandler.code);
8 years ago
} else {
8 years ago
console.log('FC reports unsupported message error: ' + dataHandler.code);
8 years ago
}
// trigger callbacks, cleanup/remove callback after trigger
8 years ago
for (i = dataHandler.callbacks.length - 1; i >= 0; i--) { // iterating in reverse because we use .splice which modifies array length
if (i < dataHandler.callbacks.length) {
if (dataHandler.callbacks[i].code == dataHandler.code) {
8 years ago
// save callback reference
8 years ago
var callback = dataHandler.callbacks[i].callback;
8 years ago
// remove timeout
8 years ago
clearInterval(dataHandler.callbacks[i].timer);
8 years ago
// remove object from array
8 years ago
dataHandler.callbacks.splice(i, 1);
8 years ago
// fire callback
8 years ago
if (callback) callback({'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected});
8 years ago
}
}
}
8 years ago
};
8 years ago
8 years ago
self.crunch = function (code) {
var buffer = [],
i;
8 years ago
switch (code) {
case MSPCodes.MSP_SET_BF_CONFIG:
buffer.push(BF_CONFIG.mixerConfiguration);
buffer.push(specificByte(BF_CONFIG.features, 0));
buffer.push(specificByte(BF_CONFIG.features, 1));
buffer.push(specificByte(BF_CONFIG.features, 2));
buffer.push(specificByte(BF_CONFIG.features, 3));
buffer.push(BF_CONFIG.serialrx_type);
buffer.push(specificByte(BF_CONFIG.board_align_roll, 0));
buffer.push(specificByte(BF_CONFIG.board_align_roll, 1));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 0));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 1));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 0));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 1));
buffer.push(lowByte(BF_CONFIG.currentscale));
buffer.push(highByte(BF_CONFIG.currentscale));
buffer.push(lowByte(BF_CONFIG.currentoffset));
buffer.push(highByte(BF_CONFIG.currentoffset));
break;
case MSPCodes.MSP_SET_PID:
8 years ago
for (i = 0; i < PIDs.length; i++) {
8 years ago
buffer.push(parseInt(PIDs[i][0]));
buffer.push(parseInt(PIDs[i][1]));
buffer.push(parseInt(PIDs[i][2]));
}
break;
case MSPCodes.MSP_SET_RC_TUNING:
buffer.push(Math.round(RC_tuning.RC_RATE * 100));
buffer.push(Math.round(RC_tuning.RC_EXPO * 100));
if (semver.lt(CONFIG.apiVersion, "1.7.0")) {
buffer.push(Math.round(RC_tuning.roll_pitch_rate * 100));
buffer.push(Math.round(RC_tuning.yaw_rate * 100));
} else if (FC.isRatesInDps()) {
buffer.push(Math.round(RC_tuning.roll_rate / 10));
buffer.push(Math.round(RC_tuning.pitch_rate / 10));
buffer.push(Math.round(RC_tuning.yaw_rate / 10));
} else {
buffer.push(Math.round(RC_tuning.roll_rate * 100));
buffer.push(Math.round(RC_tuning.pitch_rate * 100));
buffer.push(Math.round(RC_tuning.yaw_rate * 100));
}
buffer.push(RC_tuning.dynamic_THR_PID);
buffer.push(Math.round(RC_tuning.throttle_MID * 100));
buffer.push(Math.round(RC_tuning.throttle_EXPO * 100));
if (semver.gte(CONFIG.apiVersion, "1.7.0")) {
buffer.push(lowByte(RC_tuning.dynamic_THR_breakpoint));
buffer.push(highByte(RC_tuning.dynamic_THR_breakpoint));
}
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
buffer.push(Math.round(RC_tuning.RC_YAW_EXPO * 100));
}
break;
8 years ago
8 years ago
case MSPCodes.MSP_SET_RX_MAP:
8 years ago
for (i = 0; i < RC_MAP.length; i++) {
8 years ago
buffer.push(RC_MAP[i]);
}
break;
case MSPCodes.MSP_SET_ACC_TRIM:
buffer.push(lowByte(CONFIG.accelerometerTrims[0]));
buffer.push(highByte(CONFIG.accelerometerTrims[0]));
buffer.push(lowByte(CONFIG.accelerometerTrims[1]));
buffer.push(highByte(CONFIG.accelerometerTrims[1]));
break;
case MSPCodes.MSP_SET_ARMING_CONFIG:
buffer.push(ARMING_CONFIG.auto_disarm_delay);
buffer.push(ARMING_CONFIG.disarm_kill_switch);
break;
case MSPCodes.MSP_SET_LOOP_TIME:
buffer.push(lowByte(FC_CONFIG.loopTime));
buffer.push(highByte(FC_CONFIG.loopTime));
break;
case MSPCodes.MSP_SET_MISC:
buffer.push(lowByte(MISC.midrc));
buffer.push(highByte(MISC.midrc));
buffer.push(lowByte(MISC.minthrottle));
buffer.push(highByte(MISC.minthrottle));
buffer.push(lowByte(MISC.maxthrottle));
buffer.push(highByte(MISC.maxthrottle));
buffer.push(lowByte(MISC.mincommand));
buffer.push(highByte(MISC.mincommand));
buffer.push(lowByte(MISC.failsafe_throttle));
buffer.push(highByte(MISC.failsafe_throttle));
buffer.push(MISC.gps_type);
buffer.push(MISC.gps_baudrate);
buffer.push(MISC.gps_ubx_sbas);
buffer.push(MISC.multiwiicurrentoutput);
buffer.push(MISC.rssi_channel);
buffer.push(MISC.placeholder2);
buffer.push(lowByte(Math.round(MISC.mag_declination * 10)));
buffer.push(highByte(Math.round(MISC.mag_declination * 10)));
buffer.push(MISC.vbatscale);
buffer.push(Math.round(MISC.vbatmincellvoltage * 10));
buffer.push(Math.round(MISC.vbatmaxcellvoltage * 10));
buffer.push(Math.round(MISC.vbatwarningcellvoltage * 10));
break;
case MSPCodes.MSP_SET_RX_CONFIG:
buffer.push(RX_CONFIG.serialrx_provider);
buffer.push(lowByte(RX_CONFIG.maxcheck));
buffer.push(highByte(RX_CONFIG.maxcheck));
buffer.push(lowByte(RX_CONFIG.midrc));
buffer.push(highByte(RX_CONFIG.midrc));
buffer.push(lowByte(RX_CONFIG.mincheck));
buffer.push(highByte(RX_CONFIG.mincheck));
buffer.push(RX_CONFIG.spektrum_sat_bind);
buffer.push(lowByte(RX_CONFIG.rx_min_usec));
buffer.push(highByte(RX_CONFIG.rx_min_usec));
buffer.push(lowByte(RX_CONFIG.rx_max_usec));
buffer.push(highByte(RX_CONFIG.rx_max_usec));
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
buffer.push(0); // 4 null bytes for betaflight compatibility
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(RX_CONFIG.nrf24rx_protocol);
buffer.push(RX_CONFIG.nrf24rx_id & 0xFF);
buffer.push((RX_CONFIG.nrf24rx_id >> 8) & 0xFF);
buffer.push((RX_CONFIG.nrf24rx_id >> 16) & 0xFF);
buffer.push((RX_CONFIG.nrf24rx_id >> 24) & 0xFF);
}
break;
case MSPCodes.MSP_SET_FAILSAFE_CONFIG:
buffer.push(FAILSAFE_CONFIG.failsafe_delay);
buffer.push(FAILSAFE_CONFIG.failsafe_off_delay);
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle));
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle));
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
}
break;
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
8 years ago
for (i = 0; i < TRANSPONDER.data.length; i++) {
8 years ago
buffer.push(TRANSPONDER.data[i]);
}
break;
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
8 years ago
for (i = 0; i < SERVO_CONFIG.length; i++) {
8 years ago
var out = SERVO_CONFIG[i].indexOfChannelToForward;
if (out == undefined) {
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
}
buffer.push(out);
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
8 years ago
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
8 years ago
8 years ago
buffer.push(serialPort.identifier);
8 years ago
8 years ago
var functionMask = mspHelper.SERIAL_PORT_FUNCTIONSToMask(serialPort.functions);
buffer.push(specificByte(functionMask, 0));
buffer.push(specificByte(functionMask, 1));
8 years ago
8 years ago
buffer.push(mspHelper.BAUD_RATES.indexOf(serialPort.msp_baudrate));
buffer.push(mspHelper.BAUD_RATES.indexOf(serialPort.gps_baudrate));
buffer.push(mspHelper.BAUD_RATES.indexOf(serialPort.telemetry_baudrate));
buffer.push(mspHelper.BAUD_RATES.indexOf(serialPort.blackbox_baudrate));
8 years ago
}
break;
case MSPCodes.MSP_SET_3D:
buffer.push(lowByte(_3D.deadband3d_low));
buffer.push(highByte(_3D.deadband3d_low));
buffer.push(lowByte(_3D.deadband3d_high));
buffer.push(highByte(_3D.deadband3d_high));
buffer.push(lowByte(_3D.neutral3d));
buffer.push(highByte(_3D.neutral3d));
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
buffer.push(lowByte(_3D.deadband3d_throttle));
buffer.push(highByte(_3D.deadband3d_throttle));
}
break;
case MSPCodes.MSP_SET_RC_DEADBAND:
buffer.push(RC_deadband.deadband);
buffer.push(RC_deadband.yaw_deadband);
buffer.push(RC_deadband.alt_hold_deadband);
break;
case MSPCodes.MSP_SET_SENSOR_ALIGNMENT:
buffer.push(SENSOR_ALIGNMENT.align_gyro);
buffer.push(SENSOR_ALIGNMENT.align_acc);
buffer.push(SENSOR_ALIGNMENT.align_mag);
break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
buffer.push(ADVANCED_CONFIG.gyroSyncDenominator);
buffer.push(ADVANCED_CONFIG.pidProcessDenom);
buffer.push(ADVANCED_CONFIG.useUnsyncedPwm);
buffer.push(ADVANCED_CONFIG.motorPwmProtocol);
buffer.push(lowByte(ADVANCED_CONFIG.motorPwmRate));
buffer.push(highByte(ADVANCED_CONFIG.motorPwmRate));
buffer.push(lowByte(ADVANCED_CONFIG.servoPwmRate));
buffer.push(highByte(ADVANCED_CONFIG.servoPwmRate));
buffer.push(ADVANCED_CONFIG.gyroSync);
break;
case MSPCodes.MSP_SET_INAV_PID:
buffer.push(INAV_PID_CONFIG.asynchronousMode);
buffer.push(lowByte(INAV_PID_CONFIG.accelerometerTaskFrequency));
buffer.push(highByte(INAV_PID_CONFIG.accelerometerTaskFrequency));
buffer.push(lowByte(INAV_PID_CONFIG.attitudeTaskFrequency));
buffer.push(highByte(INAV_PID_CONFIG.attitudeTaskFrequency));
buffer.push(INAV_PID_CONFIG.magHoldRateLimit);
buffer.push(INAV_PID_CONFIG.magHoldErrorLpfFrequency);
buffer.push(lowByte(INAV_PID_CONFIG.yawJumpPreventionLimit));
buffer.push(highByte(INAV_PID_CONFIG.yawJumpPreventionLimit));
buffer.push(INAV_PID_CONFIG.gyroscopeLpf);
buffer.push(INAV_PID_CONFIG.accSoftLpfHz);
buffer.push(0); //reserved
buffer.push(0); //reserved
buffer.push(0); //reserved
buffer.push(0); //reserved
break;
case MSPCodes.MSP_SET_FILTER_CONFIG:
buffer.push(FILTER_CONFIG.gyroSoftLpfHz);
buffer.push(lowByte(FILTER_CONFIG.dtermLpfHz));
buffer.push(highByte(FILTER_CONFIG.dtermLpfHz));
buffer.push(lowByte(FILTER_CONFIG.yawLpfHz));
buffer.push(highByte(FILTER_CONFIG.yawLpfHz));
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
buffer.push(0);
break;
case MSPCodes.MSP_SET_PID_ADVANCED:
buffer.push(lowByte(PID_ADVANCED.rollPitchItermIgnoreRate));
buffer.push(highByte(PID_ADVANCED.rollPitchItermIgnoreRate));
buffer.push(lowByte(PID_ADVANCED.yawItermIgnoreRate));
buffer.push(highByte(PID_ADVANCED.yawItermIgnoreRate));
buffer.push(lowByte(PID_ADVANCED.yawPLimit));
buffer.push(highByte(PID_ADVANCED.yawPLimit));
buffer.push(0); //BF: currentProfile->pidProfile.deltaMethod
buffer.push(0); //BF: currentProfile->pidProfile.vbatPidCompensation
buffer.push(0); //BF: currentProfile->pidProfile.setpointRelaxRatio
buffer.push(0); //BF: currentProfile->pidProfile.dtermSetpointWeight
buffer.push(0); // reserved
buffer.push(0); // reserved
buffer.push(0); //BF: currentProfile->pidProfile.itermThrottleGain
buffer.push(lowByte(PID_ADVANCED.axisAccelerationLimitRollPitch));
buffer.push(highByte(PID_ADVANCED.axisAccelerationLimitRollPitch));
buffer.push(lowByte(PID_ADVANCED.axisAccelerationLimitYaw));
buffer.push(highByte(PID_ADVANCED.axisAccelerationLimitYaw));
break;
default:
return false;
}
return buffer;
};
/**
* Set raw Rx values over MSP protocol.
*
* Channels is an array of 16-bit unsigned integer channel values to be sent. 8 channels is probably the maximum.
*/
8 years ago
self.setRawRx = function (channels) {
8 years ago
var buffer = [];
for (var i = 0; i < channels.length; i++) {
buffer.push(specificByte(channels[i], 0));
buffer.push(specificByte(channels[i], 1));
}
MSP.send_message(MSPCodes.MSP_SET_RAW_RC, buffer, false);
8 years ago
};
8 years ago
8 years ago
self.sendBlackboxConfiguration = function (onDataCallback) {
8 years ago
var message = [
BLACKBOX.blackboxDevice & 0xFF,
BLACKBOX.blackboxRateNum & 0xFF,
BLACKBOX.blackboxRateDenom & 0xFF
8 years ago
];
8 years ago
8 years ago
MSP.send_message(MSPCodes.MSP_SET_BLACKBOX_CONFIG, message, false, function (response) {
8 years ago
onDataCallback();
});
8 years ago
};
8 years ago
8 years ago
self.sendServoConfigurations = function (onCompleteCallback) {
8 years ago
var nextFunction = send_next_servo_configuration;
var servoIndex = 0;
if (SERVO_CONFIG.length == 0) {
onCompleteCallback();
} else {
nextFunction();
}
function send_next_servo_configuration() {
var buffer = [];
8 years ago
// send one at a time, with index
8 years ago
8 years ago
var servoConfiguration = SERVO_CONFIG[servoIndex];
8 years ago
8 years ago
buffer.push(servoIndex);
8 years ago
8 years ago
buffer.push(lowByte(servoConfiguration.min));
buffer.push(highByte(servoConfiguration.min));
8 years ago
8 years ago
buffer.push(lowByte(servoConfiguration.max));
buffer.push(highByte(servoConfiguration.max));
8 years ago
8 years ago
buffer.push(lowByte(servoConfiguration.middle));
buffer.push(highByte(servoConfiguration.middle));
8 years ago
8 years ago
buffer.push(lowByte(servoConfiguration.rate));
8 years ago
8 years ago
buffer.push(servoConfiguration.angleAtMin);
buffer.push(servoConfiguration.angleAtMax);
8 years ago
8 years ago
var out = servoConfiguration.indexOfChannelToForward;
if (out == undefined) {
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
}
buffer.push(out);
8 years ago
8 years ago
buffer.push(specificByte(servoConfiguration.reversedInputSources, 0));
buffer.push(specificByte(servoConfiguration.reversedInputSources, 1));
buffer.push(specificByte(servoConfiguration.reversedInputSources, 2));
buffer.push(specificByte(servoConfiguration.reversedInputSources, 3));
8 years ago
8 years ago
// prepare for next iteration
servoIndex++;
if (servoIndex == SERVO_CONFIG.length) {
nextFunction = onCompleteCallback;
8 years ago
}
MSP.send_message(MSPCodes.MSP_SET_SERVO_CONFIGURATION, buffer, false, nextFunction);
}
function send_channel_forwarding() {
var buffer = [];
for (var 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"
}
buffer.push(out);
}
nextFunction = onCompleteCallback;
MSP.send_message(MSPCodes.MSP_SET_CHANNEL_FORWARDING, buffer, false, nextFunction);
}
8 years ago
};
8 years ago
8 years ago
self.sendModeRanges = function (onCompleteCallback) {
8 years ago
var nextFunction = send_next_mode_range;
var modeRangeIndex = 0;
if (MODE_RANGES.length == 0) {
onCompleteCallback();
} else {
send_next_mode_range();
}
function send_next_mode_range() {
var modeRange = MODE_RANGES[modeRangeIndex];
var buffer = [];
buffer.push(modeRangeIndex);
buffer.push(modeRange.id);
buffer.push(modeRange.auxChannelIndex);
buffer.push((modeRange.range.start - 900) / 25);
buffer.push((modeRange.range.end - 900) / 25);
// prepare for next iteration
modeRangeIndex++;
if (modeRangeIndex == MODE_RANGES.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSPCodes.MSP_SET_MODE_RANGE, buffer, false, nextFunction);
}
8 years ago
};
8 years ago
/**
* Send a request to read a block of data from the dataflash at the given address and pass that address and a dataview
* of the returned data to the given callback (or null for the data if an error occured).
*/
8 years ago
self.dataflashRead = function (address, onDataCallback) {
8 years ago
MSP.send_message(MSPCodes.MSP_DATAFLASH_READ, [address & 0xFF, (address >> 8) & 0xFF, (address >> 16) & 0xFF, (address >> 24) & 0xFF],
8 years ago
false, function (response) {
var chunkAddress = response.data.getUint32(0, 1);
// Verify that the address of the memory returned matches what the caller asked for
if (chunkAddress == address) {
/* Strip that address off the front of the reply and deliver it separately so the caller doesn't have to
* figure out the reply format:
*/
onDataCallback(address, new DataView(response.data.buffer, response.data.byteOffset + 4, response.data.buffer.byteLength - 4));
} else {
// Report error
onDataCallback(address, null);
}
});
};
8 years ago
8 years ago
self.sendRxFailConfig = function (onCompleteCallback) {
8 years ago
var nextFunction = send_next_rxfail_config;
var rxFailIndex = 0;
if (RXFAIL_CONFIG.length == 0) {
onCompleteCallback();
} else {
send_next_rxfail_config();
}
function send_next_rxfail_config() {
var rxFail = RXFAIL_CONFIG[rxFailIndex];
var buffer = [];
buffer.push(rxFailIndex);
buffer.push(rxFail.mode);
buffer.push(lowByte(rxFail.value));
buffer.push(highByte(rxFail.value));
// prepare for next iteration
rxFailIndex++;
if (rxFailIndex == RXFAIL_CONFIG.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSPCodes.MSP_SET_RXFAIL_CONFIG, buffer, false, nextFunction);
}
8 years ago
};
8 years ago
8 years ago
/**
* @return {number}
*/
self.SERIAL_PORT_FUNCTIONSToMask = function (functions) {
8 years ago
var mask = 0;
for (var index = 0; index < functions.length; index++) {
var key = functions[index];
var bitIndex = mspHelper.SERIAL_PORT_FUNCTIONS[key];
if (bitIndex >= 0) {
mask = bit_set(mask, bitIndex);
}
}
return mask;
8 years ago
};
8 years ago
8 years ago
self.serialPortFunctionMaskToFunctions = function (functionMask) {
8 years ago
var functions = [];
var keys = Object.keys(mspHelper.SERIAL_PORT_FUNCTIONS);
for (var index = 0; index < keys.length; index++) {
var key = keys[index];
var bit = mspHelper.SERIAL_PORT_FUNCTIONS[key];
if (bit_check(functionMask, bit)) {
functions.push(key);
}
}
return functions;
8 years ago
};
8 years ago
8 years ago
self.sendServoMixRules = function (onCompleteCallback) {
8 years ago
// TODO implement
onCompleteCallback();
8 years ago
};
8 years ago
8 years ago
self.sendAdjustmentRanges = function (onCompleteCallback) {
8 years ago
var nextFunction = send_next_adjustment_range;
var adjustmentRangeIndex = 0;
if (ADJUSTMENT_RANGES.length == 0) {
onCompleteCallback();
} else {
send_next_adjustment_range();
}
function send_next_adjustment_range() {
var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex];
var buffer = [];
buffer.push(adjustmentRangeIndex);
buffer.push(adjustmentRange.slotIndex);
buffer.push(adjustmentRange.auxChannelIndex);
buffer.push((adjustmentRange.range.start - 900) / 25);
buffer.push((adjustmentRange.range.end - 900) / 25);
buffer.push(adjustmentRange.adjustmentFunction);
buffer.push(adjustmentRange.auxSwitchChannelIndex);
// prepare for next iteration
adjustmentRangeIndex++;
if (adjustmentRangeIndex == ADJUSTMENT_RANGES.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSPCodes.MSP_SET_ADJUSTMENT_RANGE, buffer, false, nextFunction);
}
8 years ago
};
8 years ago
8 years ago
self.sendLedStripColors = function (onCompleteCallback) {
8 years ago
if (LED_COLORS.length == 0) {
onCompleteCallback();
} else {
var buffer = [];
for (var colorIndex = 0; colorIndex < LED_COLORS.length; colorIndex++) {
var color = LED_COLORS[colorIndex];
buffer.push(specificByte(color.h, 0));
buffer.push(specificByte(color.h, 1));
buffer.push(color.s);
buffer.push(color.v);
}
MSP.send_message(MSPCodes.MSP_SET_LED_COLORS, buffer, false, onCompleteCallback);
}
8 years ago
};
8 years ago
8 years ago
self.sendLedStripConfig = function (onCompleteCallback) {
8 years ago
var nextFunction = send_next_led_strip_config;
var ledIndex = 0;
if (LED_STRIP.length == 0) {
onCompleteCallback();
} else {
send_next_led_strip_config();
}
function send_next_led_strip_config() {
var led = LED_STRIP[ledIndex];
/*
8 years ago
var led = {
directions: directions,
functions: functions,
x: data.getUint8(offset++, 1),
y: data.getUint8(offset++, 1),
color: data.getUint8(offset++, 1)
};
*/
8 years ago
var buffer = [];
buffer.push(ledIndex);
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
var directionMask = 0;
for (var directionLetterIndex = 0; directionLetterIndex < led.directions.length; directionLetterIndex++) {
var bitIndex = MSP.ledDirectionLetters.indexOf(led.directions[directionLetterIndex]);
if (bitIndex >= 0) {
directionMask = bit_set(directionMask, bitIndex);
}
}
buffer.push(specificByte(directionMask, 0));
buffer.push(specificByte(directionMask, 1));
var functionMask = 0;
for (var functionLetterIndex = 0; functionLetterIndex < led.functions.length; functionLetterIndex++) {
var bitIndex = MSP.ledFunctionLetters.indexOf(led.functions[functionLetterIndex]);
if (bitIndex >= 0) {
functionMask = bit_set(functionMask, bitIndex);
}
}
buffer.push(specificByte(functionMask, 0));
buffer.push(specificByte(functionMask, 1));
buffer.push(led.x);
buffer.push(led.y);
buffer.push(led.color);
} else {
var mask = 0;
/*
8 years ago
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
8 years ago
*/
mask |= (led.y << 0);
mask |= (led.x << 4);
for (var functionLetterIndex = 0; functionLetterIndex < led.functions.length; functionLetterIndex++) {
var fnIndex = MSP.ledBaseFunctionLetters.indexOf(led.functions[functionLetterIndex]);
if (fnIndex >= 0) {
mask |= (fnIndex << 8);
break;
}
}
for (var overlayLetterIndex = 0; overlayLetterIndex < led.functions.length; overlayLetterIndex++) {
var bitIndex = MSP.ledOverlayLetters.indexOf(led.functions[overlayLetterIndex]);
if (bitIndex >= 0) {
mask |= bit_set(mask, bitIndex + 12);
}
}
mask |= (led.color << 18);
for (var directionLetterIndex = 0; directionLetterIndex < led.directions.length; directionLetterIndex++) {
var bitIndex = MSP.ledDirectionLetters.indexOf(led.directions[directionLetterIndex]);
if (bitIndex >= 0) {
mask |= bit_set(mask, bitIndex + 22);
}
}
mask |= (0 << 28); // parameters
buffer.push(specificByte(mask, 0));
buffer.push(specificByte(mask, 1));
buffer.push(specificByte(mask, 2));
buffer.push(specificByte(mask, 3));
}
// prepare for next iteration
ledIndex++;
if (ledIndex == LED_STRIP.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSPCodes.MSP_SET_LED_STRIP_CONFIG, buffer, false, nextFunction);
}
8 years ago
};
8 years ago
8 years ago
self.sendLedStripModeColors = function (onCompleteCallback) {
8 years ago
var nextFunction = send_next_led_strip_mode_color;
var index = 0;
if (LED_MODE_COLORS.length == 0) {
onCompleteCallback();
} else {
send_next_led_strip_mode_color();
}
function send_next_led_strip_mode_color() {
var buffer = [];
var mode_color = LED_MODE_COLORS[index];
buffer.push(mode_color.mode);
buffer.push(mode_color.direction);
buffer.push(mode_color.color);
// prepare for next iteration
index++;
if (index == LED_MODE_COLORS.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSPCodes.MSP_SET_LED_STRIP_MODECOLOR, buffer, false, nextFunction);
}
8 years ago
};
8 years ago
return self;
8 years ago
})(GUI);