diff --git a/js/backup_restore.js b/js/backup_restore.js index 52298840..bedffd1b 100644 --- a/js/backup_restore.js +++ b/js/backup_restore.js @@ -13,35 +13,35 @@ function configuration_backup(callback) { }; var profileSpecificData = [ - MSP_codes.MSP_PID, - MSP_codes.MSP_RC_TUNING, - MSP_codes.MSP_ACC_TRIM, - MSP_codes.MSP_SERVO_CONFIGURATIONS, - MSP_codes.MSP_MODE_RANGES, - MSP_codes.MSP_ADJUSTMENT_RANGES + MSPCodes.MSP_PID, + MSPCodes.MSP_RC_TUNING, + MSPCodes.MSP_ACC_TRIM, + MSPCodes.MSP_SERVO_CONFIGURATIONS, + MSPCodes.MSP_MODE_RANGES, + MSPCodes.MSP_ADJUSTMENT_RANGES ]; function update_profile_specific_data_list() { if (semver.lt(CONFIG.apiVersion, "1.12.0")) { - profileSpecificData.push(MSP_codes.MSP_CHANNEL_FORWARDING); + profileSpecificData.push(MSPCodes.MSP_CHANNEL_FORWARDING); } else { - profileSpecificData.push(MSP_codes.MSP_SERVO_MIX_RULES); + profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES); } if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - profileSpecificData.push(MSP_codes.MSP_RC_DEADBAND); + profileSpecificData.push(MSPCodes.MSP_RC_DEADBAND); } } update_profile_specific_data_list(); - MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () { + MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () { activeProfile = CONFIG.profile; select_profile(); }); function select_profile() { if (activeProfile > 0) { - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [0], false, fetch_specific_data); + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [0], false, fetch_specific_data); } else { fetch_specific_data(); } @@ -76,11 +76,11 @@ function configuration_backup(callback) { codeKey = 0; fetchingProfile++; - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [fetchingProfile], false, fetch_specific_data_item); + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [fetchingProfile], false, fetch_specific_data_item); } }); } else { - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [activeProfile], false, fetch_unique_data); + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [activeProfile], false, fetch_unique_data); } } @@ -89,30 +89,30 @@ function configuration_backup(callback) { } var uniqueData = [ - MSP_codes.MSP_MISC, - MSP_codes.MSP_RX_MAP, - MSP_codes.MSP_BF_CONFIG, - MSP_codes.MSP_CF_SERIAL_CONFIG, - MSP_codes.MSP_LED_STRIP_CONFIG, - MSP_codes.MSP_LED_COLORS + MSPCodes.MSP_MISC, + MSPCodes.MSP_RX_MAP, + MSPCodes.MSP_BF_CONFIG, + MSPCodes.MSP_CF_SERIAL_CONFIG, + MSPCodes.MSP_LED_STRIP_CONFIG, + MSPCodes.MSP_LED_COLORS ]; function update_unique_data_list() { if (semver.gte(CONFIG.apiVersion, "1.8.0")) { - uniqueData.push(MSP_codes.MSP_LOOP_TIME); - uniqueData.push(MSP_codes.MSP_ARMING_CONFIG); + uniqueData.push(MSPCodes.MSP_LOOP_TIME); + uniqueData.push(MSPCodes.MSP_ARMING_CONFIG); } if (semver.gte(CONFIG.apiVersion, "1.14.0")) { - uniqueData.push(MSP_codes.MSP_3D); + uniqueData.push(MSPCodes.MSP_3D); } if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - uniqueData.push(MSP_codes.MSP_SENSOR_ALIGNMENT); - uniqueData.push(MSP_codes.MSP_RX_CONFIG); - uniqueData.push(MSP_codes.MSP_FAILSAFE_CONFIG); - uniqueData.push(MSP_codes.MSP_RXFAIL_CONFIG); + uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT); + uniqueData.push(MSPCodes.MSP_RX_CONFIG); + uniqueData.push(MSPCodes.MSP_FAILSAFE_CONFIG); + uniqueData.push(MSPCodes.MSP_RXFAIL_CONFIG); } if (semver.gte(CONFIG.apiVersion, "1.19.0")) { - uniqueData.push(MSP_codes.MSP_LED_STRIP_MODECOLOR); + uniqueData.push(MSPCodes.MSP_LED_STRIP_MODECOLOR); } } @@ -594,7 +594,7 @@ function configuration_restore(callback) { } if (!compareVersions(migratedVersion, '1.2.0')) { - + // LED_COLORS & LED_MODE_COLORS support was added. if (!configuration.LED_COLORS) { configuration.LED_COLORS = []; @@ -620,23 +620,23 @@ function configuration_restore(callback) { profilesN = 3; var profileSpecificData = [ - MSP_codes.MSP_SET_PID, - MSP_codes.MSP_SET_RC_TUNING, - MSP_codes.MSP_SET_ACC_TRIM + MSPCodes.MSP_SET_PID, + MSPCodes.MSP_SET_RC_TUNING, + MSPCodes.MSP_SET_ACC_TRIM ]; if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - profileSpecificData.push(MSP_codes.MSP_SET_RC_DEADBAND); + profileSpecificData.push(MSPCodes.MSP_SET_RC_DEADBAND); } - MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () { + MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () { activeProfile = CONFIG.profile; select_profile(); }); function select_profile() { if (activeProfile > 0) { - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [0], false, upload_specific_data); + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [0], false, upload_specific_data); } else { upload_specific_data(); } @@ -659,7 +659,7 @@ function configuration_restore(callback) { } function upload_using_specific_commands() { - MSP.send_message(profileSpecificData[codeKey], MSP.crunch(profileSpecificData[codeKey]), false, function () { + MSP.send_message(profileSpecificData[codeKey], mspHelper.crunch(profileSpecificData[codeKey]), false, function () { codeKey++; if (codeKey < profileSpecificData.length) { @@ -671,12 +671,12 @@ function configuration_restore(callback) { if (savingProfile < profilesN) { load_objects(savingProfile); - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [savingProfile], false, upload_using_specific_commands); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [savingProfile], false, upload_using_specific_commands); }); } else { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [activeProfile], false, upload_unique_data); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [activeProfile], false, upload_unique_data); }); } } @@ -684,19 +684,19 @@ function configuration_restore(callback) { } function upload_servo_mix_rules() { - MSP.sendServoMixRules(upload_servo_configuration); + mspHelper.sendServoMixRules(upload_servo_configuration); } function upload_servo_configuration() { - MSP.sendServoConfigurations(upload_mode_ranges); + mspHelper.sendServoConfigurations(upload_mode_ranges); } function upload_mode_ranges() { - MSP.sendModeRanges(upload_adjustment_ranges); + mspHelper.sendModeRanges(upload_adjustment_ranges); } function upload_adjustment_ranges() { - MSP.sendAdjustmentRanges(upload_using_specific_commands); + mspHelper.sendAdjustmentRanges(upload_using_specific_commands); } // start uploading load_objects(0); @@ -707,24 +707,24 @@ function configuration_restore(callback) { var codeKey = 0; var uniqueData = [ - MSP_codes.MSP_SET_MISC, - MSP_codes.MSP_SET_RX_MAP, - MSP_codes.MSP_SET_BF_CONFIG, - MSP_codes.MSP_SET_CF_SERIAL_CONFIG + MSPCodes.MSP_SET_MISC, + MSPCodes.MSP_SET_RX_MAP, + MSPCodes.MSP_SET_BF_CONFIG, + MSPCodes.MSP_SET_CF_SERIAL_CONFIG ]; function update_unique_data_list() { if (semver.gte(CONFIG.apiVersion, "1.8.0")) { - uniqueData.push(MSP_codes.MSP_SET_LOOP_TIME); - uniqueData.push(MSP_codes.MSP_SET_ARMING_CONFIG); + uniqueData.push(MSPCodes.MSP_SET_LOOP_TIME); + uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG); } if (semver.gte(CONFIG.apiVersion, "1.14.0")) { - uniqueData.push(MSP_codes.MSP_SET_3D); + uniqueData.push(MSPCodes.MSP_SET_3D); } if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - uniqueData.push(MSP_codes.MSP_SET_SENSOR_ALIGNMENT); - uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG); - uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG); + uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT); + uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG); + uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG); } } @@ -747,7 +747,7 @@ function configuration_restore(callback) { function send_unique_data_item() { if (codeKey < uniqueData.length) { - MSP.send_message(uniqueData[codeKey], MSP.crunch(uniqueData[codeKey]), false, function () { + MSP.send_message(uniqueData[codeKey], mspHelper.crunch(uniqueData[codeKey]), false, function () { codeKey++; send_unique_data_item(); }); @@ -765,37 +765,37 @@ function configuration_restore(callback) { } function send_led_strip_config() { - MSP.sendLedStripConfig(send_led_strip_colors); + mspHelper.sendLedStripConfig(send_led_strip_colors); } function send_led_strip_colors() { - MSP.sendLedStripColors(send_led_strip_mode_colors); + mspHelper.sendLedStripColors(send_led_strip_mode_colors); } function send_led_strip_mode_colors() { if (semver.gte(CONFIG.apiVersion, "1.19.0")) - MSP.sendLedStripModeColors(send_rxfail_config); + mspHelper.sendLedStripModeColors(send_rxfail_config); else send_rxfail_config(); } function send_rxfail_config() { if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - MSP.sendRxFailConfig(save_to_eeprom); + mspHelper.sendRxFailConfig(save_to_eeprom); } else { save_to_eeprom(); } } function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot); } function reboot() { GUI.log(chrome.i18n.getMessage('eeprom_saved_ok')); GUI.tab_switch_cleanup(function() { - MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize); + MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize); }); } @@ -803,7 +803,7 @@ function configuration_restore(callback) { GUI.log(chrome.i18n.getMessage('deviceRebooting')); GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { + MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { GUI.log(chrome.i18n.getMessage('deviceReady')); if (callback) callback(); diff --git a/js/msp.js b/js/msp.js index 91bf0dcb..85fba992 100644 --- a/js/msp.js +++ b/js/msp.js @@ -1,133 +1,5 @@ 'use strict'; -// MSP_codes needs to be re-integrated inside MSP object -var MSP_codes = { - MSP_API_VERSION: 1, - MSP_FC_VARIANT: 2, - MSP_FC_VERSION: 3, - MSP_BOARD_INFO: 4, - MSP_BUILD_INFO: 5, - - MSP_INAV_PID: 6, - MSP_SET_INAV_PID: 7, - - // MSP commands for Cleanflight original features - MSP_CHANNEL_FORWARDING: 32, - MSP_SET_CHANNEL_FORWARDING: 33, - MSP_MODE_RANGES: 34, - MSP_SET_MODE_RANGE: 35, - MSP_RX_CONFIG: 44, - MSP_SET_RX_CONFIG: 45, - MSP_LED_COLORS: 46, - MSP_SET_LED_COLORS: 47, - MSP_LED_STRIP_CONFIG: 48, - MSP_SET_LED_STRIP_CONFIG: 49, - MSP_ADJUSTMENT_RANGES: 52, - MSP_SET_ADJUSTMENT_RANGE: 53, - MSP_CF_SERIAL_CONFIG: 54, - MSP_SET_CF_SERIAL_CONFIG: 55, - MSP_SONAR: 58, - MSP_PID_CONTROLLER: 59, - MSP_SET_PID_CONTROLLER: 60, - MSP_ARMING_CONFIG: 61, - MSP_SET_ARMING_CONFIG: 62, - MSP_DATAFLASH_SUMMARY: 70, - MSP_DATAFLASH_READ: 71, - MSP_DATAFLASH_ERASE: 72, - MSP_LOOP_TIME: 73, - MSP_SET_LOOP_TIME: 74, - MSP_FAILSAFE_CONFIG: 75, - MSP_SET_FAILSAFE_CONFIG: 76, - MSP_RXFAIL_CONFIG: 77, - MSP_SET_RXFAIL_CONFIG: 78, - MSP_SDCARD_SUMMARY: 79, - MSP_BLACKBOX_CONFIG: 80, - MSP_SET_BLACKBOX_CONFIG: 81, - MSP_TRANSPONDER_CONFIG: 82, - MSP_SET_TRANSPONDER_CONFIG: 83, - MSP_OSD_CONFIG: 84, - - MSP_ADVANCED_CONFIG: 90, - MSP_SET_ADVANCED_CONFIG: 91, - MSP_FILTER_CONFIG: 92, - MSP_SET_FILTER_CONFIG: 93, - MSP_PID_ADVANCED: 94, - MSP_SET_PID_ADVANCED: 95, - - // Multiwii MSP commands - MSP_IDENT: 100, - MSP_STATUS: 101, - MSP_RAW_IMU: 102, - MSP_SERVO: 103, - MSP_MOTOR: 104, - MSP_RC: 105, - MSP_RAW_GPS: 106, - MSP_COMP_GPS: 107, - MSP_ATTITUDE: 108, - MSP_ALTITUDE: 109, - MSP_ANALOG: 110, - MSP_RC_TUNING: 111, - MSP_PID: 112, - MSP_BOX: 113, - MSP_MISC: 114, - MSP_MOTOR_PINS: 115, - MSP_BOXNAMES: 116, - MSP_PIDNAMES: 117, - MSP_WP: 118, - MSP_BOXIDS: 119, - MSP_SERVO_CONFIGURATIONS: 120, - MSP_3D: 124, - MSP_RC_DEADBAND: 125, - MSP_SENSOR_ALIGNMENT: 126, - MSP_LED_STRIP_MODECOLOR:127, - MSP_STATUS_EX: 150, - - MSP_SET_RAW_RC: 200, - MSP_SET_RAW_GPS: 201, - MSP_SET_PID: 202, - MSP_SET_BOX: 203, - MSP_SET_RC_TUNING: 204, - MSP_ACC_CALIBRATION: 205, - MSP_MAG_CALIBRATION: 206, - MSP_SET_MISC: 207, - MSP_RESET_CONF: 208, - MSP_SET_WP: 209, - MSP_SELECT_SETTING: 210, - MSP_SET_HEAD: 211, - MSP_SET_SERVO_CONFIGURATION: 212, - MSP_SET_MOTOR: 214, - MSP_SET_3D: 217, - MSP_SET_RC_DEADBAND: 218, - MSP_SET_RESET_CURR_PID: 219, - MSP_SET_SENSOR_ALIGNMENT: 220, - MSP_SET_LED_STRIP_MODECOLOR:221, - - // MSP_BIND: 240, - - MSP_SERVO_MIX_RULES: 241, - MSP_SET_SERVO_MIX_RULE: 242, - - MSP_EEPROM_WRITE: 250, - - MSP_DEBUGMSG: 253, - MSP_DEBUG: 254, - - // Additional baseflight commands that are not compatible with MultiWii - MSP_UID: 160, // Unique device ID - MSP_ACC_TRIM: 240, // get acc angle trim values - MSP_SET_ACC_TRIM: 239, // set acc angle trim values - MSP_GPS_SV_INFO: 164, // get Signal Strength - MSP_GPSSTATISTICS: 166, // GPS statistics - - // Additional private MSP for baseflight configurator (yes thats us \o/) - MSP_RX_MAP: 64, // get channel map (also returns number of channels total) - MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP - MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere - MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save - MSP_SET_REBOOT: 68, // reboot settings - MSP_BF_BUILD_INFO: 69 // build date as well as some space for future expansion -}; - var MSP = { state: 0, message_direction: 1, @@ -150,30 +22,6 @@ var MSP = { last_received_timestamp: null, analog_last_received_timestamp: null, - supportedBaudRates: [ // 0 based index. - 'AUTO', - '9600', - '19200', - '38400', - '57600', - '115200', - '230400', - '250000', - ], - - serialPortFunctions: { - '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, - 'TELEMETRY_IBUS': 9, - }, - read: function (readInfo) { var data = new Uint8Array(readInfo.data); @@ -239,7 +87,7 @@ var MSP = { case 6: if (this.message_checksum == data[i]) { // message received, process - this.process_data(this.code, this.message_buffer, this.message_length_expected); + mspHelper.processData(this.code, this.message_buffer, this.message_length_expected); } else { console.log('code: ' + this.code + ' - crc failed'); @@ -258,956 +106,7 @@ var MSP = { } this.last_received_timestamp = Date.now(); }, - process_data: function (code, message_buffer, message_length) { - var data = new DataView(message_buffer, 0); // DataView (allowing us to view arrayBuffer as struct/union) - if (!this.unsupported) switch (code) { - case MSP_codes.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 MSP_codes.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); - $('select[name="profilechange"]').val(CONFIG.profile); - - sensor_status(CONFIG.activeSensors); - $('span.i2c-error').text(CONFIG.i2cError); - $('span.cycle-time').text(CONFIG.cycleTime); - break; - case MSP_codes.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); - $('span.i2c-error').text(CONFIG.i2cError); - $('span.cycle-time').text(CONFIG.cycleTime); - $('span.cpu-load').text(chrome.i18n.getMessage('statusbar_cpu_load', [CONFIG.cpuload])); - break; - - case MSP_codes.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 MSP_codes.MSP_SERVO: - var servoCount = message_length / 2; - var needle = 0; - for (var i = 0; i < servoCount; i++) { - SERVO_DATA[i] = data.getUint16(needle, 1); - - needle += 2; - } - break; - case MSP_codes.MSP_MOTOR: - var motorCount = message_length / 2; - var needle = 0; - for (var i = 0; i < motorCount; i++) { - MOTOR_DATA[i] = data.getUint16(needle, 1); - - needle += 2; - } - break; - case MSP_codes.MSP_RC: - RC.active_channels = message_length / 2; - - for (var i = 0; i < RC.active_channels; i++) { - RC.channels[i] = data.getUint16((i * 2), 1); - } - break; - case MSP_codes.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 MSP_codes.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 MSP_codes.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 MSP_codes.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 MSP_codes.MSP_ALTITUDE: - SENSOR_DATA.altitude = parseFloat((data.getInt32(0, 1) / 100.0).toFixed(2)); // correct scale factor - break; - case MSP_codes.MSP_SONAR: - SENSOR_DATA.sonar = data.getInt32(0, 1); - break; - case MSP_codes.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 - this.analog_last_received_timestamp = Date.now(); - break; - case MSP_codes.MSP_RC_TUNING: - var offset = 0; - RC_tuning.RC_RATE = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); - RC_tuning.RC_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); - if (semver.lt(CONFIG.apiVersion, "1.7.0")) { - RC_tuning.roll_pitch_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); - RC_tuning.pitch_rate = 0; - RC_tuning.roll_rate = 0; - RC_tuning.yaw_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); - } else if (FC.isRatesInDps()) { - 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)); - if (semver.gte(CONFIG.apiVersion, "1.7.0")) { - RC_tuning.dynamic_THR_breakpoint = data.getUint16(offset, 1); - offset += 2; - } else { - RC_tuning.dynamic_THR_breakpoint = 0; - } - if (semver.gte(CONFIG.apiVersion, "1.10.0")) { - RC_tuning.RC_YAW_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); - } else { - RC_tuning.RC_YAW_EXPO = 0; - } - break; - case MSP_codes.MSP_PID: - // PID data arrived, we need to scale it and save to appropriate bank / array - for (var i = 0, needle = 0; i < (message_length / 3); i++, needle += 3) { - PIDs[i][0] = data.getUint8(needle); - PIDs[i][1] = data.getUint8(needle + 1); - PIDs[i][2] = data.getUint8(needle + 2); - } - break; - // Disabled, cleanflight does not use MSP_BOX. - /* - case MSP_codes.MSP_BOX: - AUX_CONFIG_values = []; // empty the array as new data is coming in - - // fill in current data - for (var i = 0; i < data.byteLength; i += 2) { // + 2 because uint16_t = 2 bytes - AUX_CONFIG_values.push(data.getUint16(i, 1)); - } - break; - */ - case MSP_codes.MSP_ARMING_CONFIG: - if (semver.gte(CONFIG.apiVersion, "1.8.0")) { - ARMING_CONFIG.auto_disarm_delay = data.getUint8(0, 1); - ARMING_CONFIG.disarm_kill_switch = data.getUint8(1); - } - break; - case MSP_codes.MSP_LOOP_TIME: - if (semver.gte(CONFIG.apiVersion, "1.8.0")) { - FC_CONFIG.loopTime = data.getInt16(0, 1); - } - break; - case MSP_codes.MSP_MISC: // 22 bytes - var offset = 0; - 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 MSP_codes.MSP_3D: - var offset = 0; - _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 MSP_codes.MSP_MOTOR_PINS: - console.log(data); - break; - case MSP_codes.MSP_BOXNAMES: - AUX_CONFIG = []; // empty the array as new data is coming in - - var buff = []; - for (var 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 - - // empty buffer - buff = []; - } else { - buff.push(data.getUint8(i)); - } - } - break; - case MSP_codes.MSP_PIDNAMES: - PID_names = []; // empty the array as new data is coming in - - var buff = []; - for (var i = 0; i < data.byteLength; i++) { - if (data.getUint8(i) == 0x3B) { // ; (delimeter char) - 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 MSP_codes.MSP_WP: - console.log(data); - break; - case MSP_codes.MSP_BOXIDS: - AUX_CONFIG_IDS = []; // empty the array as new data is coming in - - for (var i = 0; i < data.byteLength; i++) { - AUX_CONFIG_IDS.push(data.getUint8(i)); - } - break; - case MSP_codes.MSP_SERVO_MIX_RULES: - break; - - case MSP_codes.MSP_SERVO_CONFIGURATIONS: - SERVO_CONFIG = []; // empty the array as new data is coming in - - if (semver.gte(CONFIG.apiVersion, "1.12.0")) { - if (data.byteLength % 14 == 0) { - for (var 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) - }; - - SERVO_CONFIG.push(arr); - } - } - } else { - if (data.byteLength % 7 == 0) { - for (var i = 0; i < data.byteLength; i += 7) { - 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': 45, - 'angleAtMax': 45, - 'indexOfChannelToForward': undefined, - 'reversedInputSources': 0 - }; - - SERVO_CONFIG.push(arr); - } - } - - if (semver.eq(CONFIG.apiVersion, '1.10.0')) { - // drop two unused servo configurations due to MSP rx buffer to small) - while (SERVO_CONFIG.length > 8) { - SERVO_CONFIG.pop(); - } - } - } - break; - case MSP_codes.MSP_RC_DEADBAND: - var offset = 0; - 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 MSP_codes.MSP_SENSOR_ALIGNMENT: - var offset = 0; - 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 MSP_codes.MSP_SET_RAW_RC: - break; - case MSP_codes.MSP_SET_RAW_GPS: - break; - case MSP_codes.MSP_SET_PID: - console.log('PID settings saved'); - break; - /* - case MSP_codes.MSP_SET_BOX: - console.log('AUX Configuration saved'); - break; - */ - case MSP_codes.MSP_SET_RC_TUNING: - console.log('RC Tuning saved'); - break; - case MSP_codes.MSP_ACC_CALIBRATION: - console.log('Accel calibration executed'); - break; - case MSP_codes.MSP_MAG_CALIBRATION: - console.log('Mag calibration executed'); - break; - case MSP_codes.MSP_SET_MISC: - console.log('MISC Configuration saved'); - break; - case MSP_codes.MSP_RESET_CONF: - console.log('Settings Reset'); - break; - case MSP_codes.MSP_SELECT_SETTING: - console.log('Profile selected'); - break; - case MSP_codes.MSP_SET_SERVO_CONFIGURATION: - console.log('Servo Configuration saved'); - break; - case MSP_codes.MSP_EEPROM_WRITE: - console.log('Settings Saved in EEPROM'); - break; - case MSP_codes.MSP_DEBUGMSG: - break; - case MSP_codes.MSP_DEBUG: - for (var i = 0; i < 4; i++) - SENSOR_DATA.debug[i] = data.getInt16((2 * i), 1); - break; - case MSP_codes.MSP_SET_MOTOR: - console.log('Motor Speeds Updated'); - break; - // Additional baseflight commands that are not compatible with MultiWii - case MSP_codes.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 MSP_codes.MSP_ACC_TRIM: - CONFIG.accelerometerTrims[0] = data.getInt16(0, 1); // pitch - CONFIG.accelerometerTrims[1] = data.getInt16(2, 1); // roll - break; - case MSP_codes.MSP_SET_ACC_TRIM: - console.log('Accelerometer trimms saved.'); - break; - // Additional private MSP for baseflight configurator - case MSP_codes.MSP_RX_MAP: - RC_MAP = []; // empty the array as new data is coming in - - for (var i = 0; i < data.byteLength; i++) { - RC_MAP.push(data.getUint8(i)); - } - break; - case MSP_codes.MSP_SET_RX_MAP: - console.log('RCMAP saved'); - break; - case MSP_codes.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 MSP_codes.MSP_SET_BF_CONFIG: - break; - case MSP_codes.MSP_SET_REBOOT: - console.log('Reboot request accepted'); - break; - - // - // Cleanflight specific - // - - case MSP_codes.MSP_API_VERSION: - var offset = 0; - CONFIG.mspProtocolVersion = data.getUint8(offset++); - CONFIG.apiVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.0'; - break; - - case MSP_codes.MSP_FC_VARIANT: - var identifier = ''; - var offset; - for (offset = 0; offset < 4; offset++) { - identifier += String.fromCharCode(data.getUint8(offset)); - } - CONFIG.flightControllerIdentifier = identifier; - break; - - case MSP_codes.MSP_FC_VERSION: - var offset = 0; - CONFIG.flightControllerVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.' + data.getUint8(offset++); - break; - - case MSP_codes.MSP_BUILD_INFO: - var offset = 0; - - var dateLength = 11; - var buff = []; - for (var i = 0; i < dateLength; i++) { - buff.push(data.getUint8(offset++)); - } - buff.push(32); // ascii space - - var timeLength = 8; - for (var i = 0; i < timeLength; i++) { - buff.push(data.getUint8(offset++)); - } - CONFIG.buildInfo = String.fromCharCode.apply(null, buff); - break; - - case MSP_codes.MSP_BOARD_INFO: - var identifier = ''; - var offset; - for (offset = 0; offset < 4; offset++) { - identifier += String.fromCharCode(data.getUint8(offset)); - } - CONFIG.boardIdentifier = identifier; - CONFIG.boardVersion = data.getUint16(offset, 1); - offset+=2; - break; - - case MSP_codes.MSP_SET_CHANNEL_FORWARDING: - console.log('Channel forwarding saved'); - break; - - case MSP_codes.MSP_CF_SERIAL_CONFIG: - - if (semver.lt(CONFIG.apiVersion, "1.6.0")) { - SERIAL_CONFIG.ports = []; - var offset = 0; - var serialPortCount = (data.byteLength - (4 * 4)) / 2; - for (var i = 0; i < serialPortCount; i++) { - var serialPort = { - identifier: data.getUint8(offset++, 1), - scenario: data.getUint8(offset++, 1) - } - SERIAL_CONFIG.ports.push(serialPort); - } - SERIAL_CONFIG.mspBaudRate = data.getUint32(offset, 1); - offset+= 4; - SERIAL_CONFIG.cliBaudRate = data.getUint32(offset, 1); - offset+= 4; - SERIAL_CONFIG.gpsBaudRate = data.getUint32(offset, 1); - offset+= 4; - SERIAL_CONFIG.gpsPassthroughBaudRate = data.getUint32(offset, 1); - offset+= 4; - } else { - SERIAL_CONFIG.ports = []; - var offset = 0; - var bytesPerPort = 1 + 2 + (1 * 4); - var serialPortCount = data.byteLength / bytesPerPort; - - for (var i = 0; i < serialPortCount; i++) { - var serialPort = { - identifier: data.getUint8(offset, 1), - functions: MSP.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, 1)), - msp_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 3, 1)], - gps_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 4, 1)], - telemetry_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 5, 1)], - blackbox_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 6, 1)] - } - - offset += bytesPerPort; - SERIAL_CONFIG.ports.push(serialPort); - } - } - break; - - case MSP_codes.MSP_SET_CF_SERIAL_CONFIG: - console.log('Serial config saved'); - break; - - case MSP_codes.MSP_MODE_RANGES: - MODE_RANGES = []; // empty the array as new data is coming in - - var modeRangeCount = data.byteLength / 4; // 4 bytes per item. - - var offset = 0; - for (var i = 0; offset < data.byteLength && i < modeRangeCount; i++) { - 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 MSP_codes.MSP_ADJUSTMENT_RANGES: - ADJUSTMENT_RANGES = []; // empty the array as new data is coming in - - var adjustmentRangeCount = data.byteLength / 6; // 6 bytes per item. - - var offset = 0; - for (var i = 0; offset < data.byteLength && i < adjustmentRangeCount; i++) { - 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 MSP_codes.MSP_CHANNEL_FORWARDING: - for (var i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i ++) { - var channelIndex = data.getUint8(i); - if (channelIndex < 255) { - SERVO_CONFIG[i].indexOfChannelToForward = channelIndex; - } else { - SERVO_CONFIG[i].indexOfChannelToForward = undefined; - } - } - break; - - case MSP_codes.MSP_RX_CONFIG: - var offset = 0; - 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 MSP_codes.MSP_FAILSAFE_CONFIG: - var offset = 0; - 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 MSP_codes.MSP_RXFAIL_CONFIG: - RXFAIL_CONFIG = []; // empty the array as new data is coming in - - var channelCount = data.byteLength / 3; - - var offset = 0; - for (var i = 0; offset < data.byteLength && i < channelCount; i++, offset++) { - var rxfailChannel = { - mode: data.getUint8(offset++, 1), - value: data.getUint16(offset++, 1) - }; - RXFAIL_CONFIG.push(rxfailChannel); - } - break; - - - case MSP_codes.MSP_LED_STRIP_CONFIG: - 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; - - var offset = 0; - for (var i = 0; offset < data.byteLength && i < ledCount; i++) { - - if (semver.lt(CONFIG.apiVersion, "1.20.0")) { - 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); - } else { - var mask = data.getUint32(offset, 1); - offset +=4; - - 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; - } - } - - 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 MSP_codes.MSP_SET_LED_STRIP_CONFIG: - console.log('Led strip config saved'); - break; - case MSP_codes.MSP_LED_COLORS: - - LED_COLORS = []; - - var colorCount = data.byteLength / 4; - - var offset = 0; - for (var 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); - offset += 4; - - var color = { - h: h, - s: s, - v: v - }; - - LED_COLORS.push(color); - } - - break; - case MSP_codes.MSP_SET_LED_COLORS: - console.log('Led strip colors saved'); - break; - case MSP_codes.MSP_LED_STRIP_MODECOLOR: - if (semver.gte(CONFIG.apiVersion, "1.19.0")) { - - LED_MODE_COLORS = []; - - var colorCount = data.byteLength / 3; - - var offset = 0; - for (var 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_color = { - mode: mode, - direction: direction, - color: color - }; - - LED_MODE_COLORS.push(mode_color); - } - } - break; - case MSP_codes.MSP_SET_LED_STRIP_MODECOLOR: - console.log('Led strip mode colors saved'); - break; - - - - case MSP_codes.MSP_DATAFLASH_SUMMARY: - if (data.byteLength >= 13) { - var - flags = data.getUint8(0); - 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 MSP_codes.MSP_DATAFLASH_READ: - // No-op, let callback handle it - break; - case MSP_codes.MSP_DATAFLASH_ERASE: - console.log("Data flash erase begun..."); - break; - case MSP_codes.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 MSP_codes.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 MSP_codes.MSP_SET_BLACKBOX_CONFIG: - console.log("Blackbox config saved"); - break; - case MSP_codes.MSP_TRANSPONDER_CONFIG: - var offset = 0; - TRANSPONDER.supported = (data.getUint8(offset++) & 1) != 0; - TRANSPONDER.data = []; - var bytesRemaining = data.byteLength - offset; - for (var i = 0; i < bytesRemaining; i++) { - TRANSPONDER.data.push(data.getUint8(offset++)); - } - break; - case MSP_codes.MSP_SET_TRANSPONDER_CONFIG: - console.log("Transponder config saved"); - break; - - case MSP_codes.MSP_ADVANCED_CONFIG: - var offset = 0; - 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 MSP_codes.MSP_SET_ADVANCED_CONFIG: - console.log("Advanced config saved"); - break; - - case MSP_codes.MSP_FILTER_CONFIG: - FILTER_CONFIG.gyroSoftLpfHz = data.getUint8(0, true); - FILTER_CONFIG.dtermLpfHz = data.getUint16(1, true); - FILTER_CONFIG.yawLpfHz = data.getUint16(3, true); - /* - 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 - */ - break; - - case MSP_codes.MSP_SET_FILTER_CONFIG: - console.log("Filter config saved"); - break; - - case MSP_codes.MSP_PID_ADVANCED: - 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); - break; - - case MSP_codes.MSP_SET_PID_ADVANCED: - console.log("PID advanced saved"); - break; - - case MSP_codes.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 MSP_codes.MSP_SET_INAV_PID: - console.log("MSP_INAV_PID saved"); - break; - - case MSP_codes.MSP_SET_MODE_RANGE: - console.log('Mode range saved'); - break; - case MSP_codes.MSP_SET_ADJUSTMENT_RANGE: - console.log('Adjustment range saved'); - break; - case MSP_codes.MSP_SET_LOOP_TIME: - console.log('Looptime saved'); - break; - case MSP_codes.MSP_SET_ARMING_CONFIG: - console.log('Arming config saved'); - break; - case MSP_codes.MSP_SET_RESET_CURR_PID: - console.log('Current PID profile reset'); - break; - case MSP_codes.MSP_SET_3D: - console.log('3D settings saved'); - break; - case MSP_codes.MSP_SET_RC_DEADBAND: - console.log('Rc controls settings saved'); - break; - case MSP_codes.MSP_SET_SENSOR_ALIGNMENT: - console.log('Sensor alignment saved'); - break; - case MSP_codes.MSP_SET_RX_CONFIG: - console.log('Rx config saved'); - break; - case MSP_codes.MSP_SET_RXFAIL_CONFIG: - console.log('Rxfail config saved'); - break; - case MSP_codes.MSP_SET_FAILSAFE_CONFIG: - console.log('Failsafe config saved'); - break; - case MSP_codes.MSP_OSD_CONFIG: - break; - default: - console.log('Unknown code detected: ' + code); - } else { - console.log('FC reports unsupported message error: ' + code); - } - - // trigger callbacks, cleanup/remove callback after trigger - for (var i = this.callbacks.length - 1; i >= 0; i--) { // itterating in reverse because we use .splice which modifies array length - if (i < this.callbacks.length) { - if (this.callbacks[i].code == code) { - // save callback reference - var callback = this.callbacks[i].callback; - - // remove timeout - clearInterval(this.callbacks[i].timer); - - // remove object from array - this.callbacks.splice(i, 1); - - // fire callback - if (callback) callback({'command': code, 'data': data, 'length': message_length}); - } - } - } - }, send_message: function (code, data, callback_sent, callback_msp) { var bufferOut, bufView; @@ -1308,766 +207,6 @@ var MSP = { } }; -/** - * Encode the request body for the MSP request with the given code and return it as an array of bytes. - */ -MSP.crunch = function (code) { - var buffer = []; - - switch (code) { - case MSP_codes.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 MSP_codes.MSP_SET_PID: - for (var i = 0; i < PIDs.length; i++) { - buffer.push(parseInt(PIDs[i][0])); - buffer.push(parseInt(PIDs[i][1])); - buffer.push(parseInt(PIDs[i][2])); - } - break; - case MSP_codes.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; - // Disabled, cleanflight does not use MSP_SET_BOX. - /* - case MSP_codes.MSP_SET_BOX: - for (var i = 0; i < AUX_CONFIG_values.length; i++) { - buffer.push(lowByte(AUX_CONFIG_values[i])); - buffer.push(highByte(AUX_CONFIG_values[i])); - } - break; - */ - case MSP_codes.MSP_SET_RX_MAP: - for (var i = 0; i < RC_MAP.length; i++) { - buffer.push(RC_MAP[i]); - } - break; - case MSP_codes.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 MSP_codes.MSP_SET_ARMING_CONFIG: - buffer.push(ARMING_CONFIG.auto_disarm_delay); - buffer.push(ARMING_CONFIG.disarm_kill_switch); - break; - case MSP_codes.MSP_SET_LOOP_TIME: - buffer.push(lowByte(FC_CONFIG.loopTime)); - buffer.push(highByte(FC_CONFIG.loopTime)); - break; - case MSP_codes.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 MSP_codes.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 MSP_codes.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 MSP_codes.MSP_SET_TRANSPONDER_CONFIG: - for (var i = 0; i < TRANSPONDER.data.length; i++) { - buffer.push(TRANSPONDER.data[i]); - } - break; - - case MSP_codes.MSP_SET_CHANNEL_FORWARDING: - 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); - } - break; - case MSP_codes.MSP_SET_CF_SERIAL_CONFIG: - if (semver.lt(CONFIG.apiVersion, "1.6.0")) { - - for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) { - buffer.push(SERIAL_CONFIG.ports[i].scenario); - } - buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 0)); - buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 1)); - buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 2)); - buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 3)); - - buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 0)); - buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 1)); - buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 2)); - buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 3)); - - buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 0)); - buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 1)); - buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 2)); - buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 3)); - - buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 0)); - buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 1)); - buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 2)); - buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 3)); - } else { - for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) { - var serialPort = SERIAL_CONFIG.ports[i]; - - buffer.push(serialPort.identifier); - - var functionMask = MSP.serialPortFunctionsToMask(serialPort.functions); - buffer.push(specificByte(functionMask, 0)); - buffer.push(specificByte(functionMask, 1)); - - buffer.push(MSP.supportedBaudRates.indexOf(serialPort.msp_baudrate)); - buffer.push(MSP.supportedBaudRates.indexOf(serialPort.gps_baudrate)); - buffer.push(MSP.supportedBaudRates.indexOf(serialPort.telemetry_baudrate)); - buffer.push(MSP.supportedBaudRates.indexOf(serialPort.blackbox_baudrate)); - } - } - break; - - case MSP_codes.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 MSP_codes.MSP_SET_RC_DEADBAND: - buffer.push(RC_deadband.deadband); - buffer.push(RC_deadband.yaw_deadband); - buffer.push(RC_deadband.alt_hold_deadband); - break; - - case MSP_codes.MSP_SET_SENSOR_ALIGNMENT: - buffer.push(SENSOR_ALIGNMENT.align_gyro); - buffer.push(SENSOR_ALIGNMENT.align_acc); - buffer.push(SENSOR_ALIGNMENT.align_mag); - break; - - case MSP_codes.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 MSP_codes.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 MSP_codes.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 MSP_codes.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. - */ -MSP.setRawRx = function(channels) { - 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(MSP_codes.MSP_SET_RAW_RC, buffer, false); -} - -MSP.sendBlackboxConfiguration = function(onDataCallback) { - var - message = [ - BLACKBOX.blackboxDevice & 0xFF, - BLACKBOX.blackboxRateNum & 0xFF, - BLACKBOX.blackboxRateDenom & 0xFF - ]; - - MSP.send_message(MSP_codes.MSP_SET_BLACKBOX_CONFIG, message, false, function(response) { - onDataCallback(); - }); -} - -/** - * 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). - */ -MSP.dataflashRead = function(address, onDataCallback) { - MSP.send_message(MSP_codes.MSP_DATAFLASH_READ, [address & 0xFF, (address >> 8) & 0xFF, (address >> 16) & 0xFF, (address >> 24) & 0xFF], - 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); - } - }); -}; - -MSP.sendServoMixRules = function(onCompleteCallback) { - // TODO implement - onCompleteCallback(); -}; - -MSP.sendServoConfigurations = function(onCompleteCallback) { - var nextFunction = send_next_servo_configuration; - - var servoIndex = 0; - - if (SERVO_CONFIG.length == 0) { - onCompleteCallback(); - } else { - nextFunction(); - } - - - function send_next_servo_configuration() { - - var buffer = []; - - 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++) { - buffer.push(lowByte(SERVO_CONFIG[i].min)); - buffer.push(highByte(SERVO_CONFIG[i].min)); - - buffer.push(lowByte(SERVO_CONFIG[i].max)); - buffer.push(highByte(SERVO_CONFIG[i].max)); - - buffer.push(lowByte(SERVO_CONFIG[i].middle)); - buffer.push(highByte(SERVO_CONFIG[i].middle)); - - buffer.push(lowByte(SERVO_CONFIG[i].rate)); - } - - nextFunction = send_channel_forwarding; - } else { - // send one at a time, with index - - var servoConfiguration = SERVO_CONFIG[servoIndex]; - - buffer.push(servoIndex); - - buffer.push(lowByte(servoConfiguration.min)); - buffer.push(highByte(servoConfiguration.min)); - - buffer.push(lowByte(servoConfiguration.max)); - buffer.push(highByte(servoConfiguration.max)); - - buffer.push(lowByte(servoConfiguration.middle)); - buffer.push(highByte(servoConfiguration.middle)); - - buffer.push(lowByte(servoConfiguration.rate)); - - buffer.push(servoConfiguration.angleAtMin); - buffer.push(servoConfiguration.angleAtMax); - - var out = servoConfiguration.indexOfChannelToForward; - if (out == undefined) { - out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF" - } - buffer.push(out); - - buffer.push(specificByte(servoConfiguration.reversedInputSources, 0)); - buffer.push(specificByte(servoConfiguration.reversedInputSources, 1)); - buffer.push(specificByte(servoConfiguration.reversedInputSources, 2)); - buffer.push(specificByte(servoConfiguration.reversedInputSources, 3)); - - // prepare for next iteration - servoIndex++; - if (servoIndex == SERVO_CONFIG.length) { - nextFunction = onCompleteCallback; - } - } - MSP.send_message(MSP_codes.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(MSP_codes.MSP_SET_CHANNEL_FORWARDING, buffer, false, nextFunction); - } -}; - -MSP.sendModeRanges = function(onCompleteCallback) { - 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(MSP_codes.MSP_SET_MODE_RANGE, buffer, false, nextFunction); - } -}; - -MSP.sendAdjustmentRanges = function(onCompleteCallback) { - 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(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, buffer, false, nextFunction); - } -}; - -MSP.sendLedStripConfig = function(onCompleteCallback) { - - 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]; - /* - var led = { - directions: directions, - functions: functions, - x: data.getUint8(offset++, 1), - y: data.getUint8(offset++, 1), - color: data.getUint8(offset++, 1) - }; - */ - 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; - /* - 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 - - */ - 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(MSP_codes.MSP_SET_LED_STRIP_CONFIG, buffer, false, nextFunction); - } -} - -MSP.sendLedStripColors = function(onCompleteCallback) { - 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(MSP_codes.MSP_SET_LED_COLORS, buffer, false, onCompleteCallback); - } -} - -MSP.sendLedStripModeColors = function(onCompleteCallback) { - - 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(MSP_codes.MSP_SET_LED_STRIP_MODECOLOR, buffer, false, nextFunction); - } -} -MSP.serialPortFunctionMaskToFunctions = function(functionMask) { - var functions = []; - - var keys = Object.keys(MSP.serialPortFunctions); - for (var index = 0; index < keys.length; index++) { - var key = keys[index]; - var bit = MSP.serialPortFunctions[key]; - if (bit_check(functionMask, bit)) { - functions.push(key); - } - } - return functions; -} - -MSP.serialPortFunctionsToMask = function(functions) { - var mask = 0; - var keys = Object.keys(MSP.serialPortFunctions); - for (var index = 0; index < functions.length; index++) { - var key = functions[index]; - var bitIndex = MSP.serialPortFunctions[key]; - if (bitIndex >= 0) { - mask = bit_set(mask, bitIndex); - } - } - return mask; -} - -MSP.sendRxFailConfig = function(onCompleteCallback) { - 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(MSP_codes.MSP_SET_RXFAIL_CONFIG, buffer, false, nextFunction); - } -}; - MSP.SDCARD_STATE_NOT_PRESENT = 0; MSP.SDCARD_STATE_FATAL = 1; MSP.SDCARD_STATE_CARD_INIT = 2; diff --git a/js/msp/MSPCodes.js b/js/msp/MSPCodes.js new file mode 100644 index 00000000..6953eacd --- /dev/null +++ b/js/msp/MSPCodes.js @@ -0,0 +1,128 @@ +'use strict'; + +var MSPCodes = { + MSP_API_VERSION: 1, + MSP_FC_VARIANT: 2, + MSP_FC_VERSION: 3, + MSP_BOARD_INFO: 4, + MSP_BUILD_INFO: 5, + + MSP_INAV_PID: 6, + MSP_SET_INAV_PID: 7, + + // MSP commands for Cleanflight original features + MSP_CHANNEL_FORWARDING: 32, + MSP_SET_CHANNEL_FORWARDING: 33, + MSP_MODE_RANGES: 34, + MSP_SET_MODE_RANGE: 35, + MSP_RX_CONFIG: 44, + MSP_SET_RX_CONFIG: 45, + MSP_LED_COLORS: 46, + MSP_SET_LED_COLORS: 47, + MSP_LED_STRIP_CONFIG: 48, + MSP_SET_LED_STRIP_CONFIG: 49, + MSP_ADJUSTMENT_RANGES: 52, + MSP_SET_ADJUSTMENT_RANGE: 53, + MSP_CF_SERIAL_CONFIG: 54, + MSP_SET_CF_SERIAL_CONFIG: 55, + MSP_SONAR: 58, + MSP_PID_CONTROLLER: 59, + MSP_SET_PID_CONTROLLER: 60, + MSP_ARMING_CONFIG: 61, + MSP_SET_ARMING_CONFIG: 62, + MSP_DATAFLASH_SUMMARY: 70, + MSP_DATAFLASH_READ: 71, + MSP_DATAFLASH_ERASE: 72, + MSP_LOOP_TIME: 73, + MSP_SET_LOOP_TIME: 74, + MSP_FAILSAFE_CONFIG: 75, + MSP_SET_FAILSAFE_CONFIG: 76, + MSP_RXFAIL_CONFIG: 77, + MSP_SET_RXFAIL_CONFIG: 78, + MSP_SDCARD_SUMMARY: 79, + MSP_BLACKBOX_CONFIG: 80, + MSP_SET_BLACKBOX_CONFIG: 81, + MSP_TRANSPONDER_CONFIG: 82, + MSP_SET_TRANSPONDER_CONFIG: 83, + MSP_OSD_CONFIG: 84, + + MSP_ADVANCED_CONFIG: 90, + MSP_SET_ADVANCED_CONFIG: 91, + MSP_FILTER_CONFIG: 92, + MSP_SET_FILTER_CONFIG: 93, + MSP_PID_ADVANCED: 94, + MSP_SET_PID_ADVANCED: 95, + + // Multiwii MSP commands + MSP_IDENT: 100, + MSP_STATUS: 101, + MSP_RAW_IMU: 102, + MSP_SERVO: 103, + MSP_MOTOR: 104, + MSP_RC: 105, + MSP_RAW_GPS: 106, + MSP_COMP_GPS: 107, + MSP_ATTITUDE: 108, + MSP_ALTITUDE: 109, + MSP_ANALOG: 110, + MSP_RC_TUNING: 111, + MSP_PID: 112, + MSP_BOX: 113, + MSP_MISC: 114, + MSP_MOTOR_PINS: 115, + MSP_BOXNAMES: 116, + MSP_PIDNAMES: 117, + MSP_WP: 118, + MSP_BOXIDS: 119, + MSP_SERVO_CONFIGURATIONS: 120, + MSP_3D: 124, + MSP_RC_DEADBAND: 125, + MSP_SENSOR_ALIGNMENT: 126, + MSP_LED_STRIP_MODECOLOR:127, + MSP_STATUS_EX: 150, + + MSP_SET_RAW_RC: 200, + MSP_SET_RAW_GPS: 201, + MSP_SET_PID: 202, + MSP_SET_BOX: 203, + MSP_SET_RC_TUNING: 204, + MSP_ACC_CALIBRATION: 205, + MSP_MAG_CALIBRATION: 206, + MSP_SET_MISC: 207, + MSP_RESET_CONF: 208, + MSP_SET_WP: 209, + MSP_SELECT_SETTING: 210, + MSP_SET_HEAD: 211, + MSP_SET_SERVO_CONFIGURATION: 212, + MSP_SET_MOTOR: 214, + MSP_SET_3D: 217, + MSP_SET_RC_DEADBAND: 218, + MSP_SET_RESET_CURR_PID: 219, + MSP_SET_SENSOR_ALIGNMENT: 220, + MSP_SET_LED_STRIP_MODECOLOR:221, + + // MSP_BIND: 240, + + MSP_SERVO_MIX_RULES: 241, + MSP_SET_SERVO_MIX_RULE: 242, + + MSP_EEPROM_WRITE: 250, + + MSP_DEBUGMSG: 253, + MSP_DEBUG: 254, + + // Additional baseflight commands that are not compatible with MultiWii + MSP_UID: 160, // Unique device ID + MSP_ACC_TRIM: 240, // get acc angle trim values + MSP_SET_ACC_TRIM: 239, // set acc angle trim values + MSP_GPS_SV_INFO: 164, // get Signal Strength + MSP_GPSSTATISTICS: 166, // GPS statistics + + // Additional private MSP for baseflight configurator (yes thats us \o/) + MSP_RX_MAP: 64, // get channel map (also returns number of channels total) + MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP + MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere + MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save + MSP_SET_REBOOT: 68, // reboot settings + MSP_BF_BUILD_INFO: 69 // build date as well as some space for future expansion +}; diff --git a/js/msp/MSPHelper.js b/js/msp/MSPHelper.js new file mode 100644 index 00000000..ec1eacdf --- /dev/null +++ b/js/msp/MSPHelper.js @@ -0,0 +1,1739 @@ +'use strict' + +var mspHelper = (function () { + var self = {}; + + self.BAUD_RATES = [ + 'AUTO', + '9600', + '19200', + '38400', + '57600', + '115200', + '230400', + '250000', + ] + + 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, + 'TELEMETRY_IBUS': 9, + } + + self.processData: function (code, message_buffer, message_length) { + var data = new DataView(message_buffer, 0); // DataView (allowing us to view arrayBuffer as struct/union) + + if (!this.unsupported) switch (code) { + 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); + $('select[name="profilechange"]').val(CONFIG.profile); + + sensor_status(CONFIG.activeSensors); + $('span.i2c-error').text(CONFIG.i2cError); + $('span.cycle-time').text(CONFIG.cycleTime); + 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); + $('span.i2c-error').text(CONFIG.i2cError); + $('span.cycle-time').text(CONFIG.cycleTime); + $('span.cpu-load').text(chrome.i18n.getMessage('statusbar_cpu_load', [CONFIG.cpuload])); + 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: + var servoCount = message_length / 2; + var needle = 0; + for (var i = 0; i < servoCount; i++) { + SERVO_DATA[i] = data.getUint16(needle, 1); + + needle += 2; + } + break; + case MSPCodes.MSP_MOTOR: + var motorCount = message_length / 2; + var needle = 0; + for (var i = 0; i < motorCount; i++) { + MOTOR_DATA[i] = data.getUint16(needle, 1); + + needle += 2; + } + break; + case MSPCodes.MSP_RC: + RC.active_channels = message_length / 2; + + for (var i = 0; i < RC.active_channels; i++) { + 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 + this.analog_last_received_timestamp = Date.now(); + break; + case MSPCodes.MSP_RC_TUNING: + var offset = 0; + RC_tuning.RC_RATE = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); + RC_tuning.RC_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); + if (semver.lt(CONFIG.apiVersion, "1.7.0")) { + RC_tuning.roll_pitch_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); + RC_tuning.pitch_rate = 0; + RC_tuning.roll_rate = 0; + RC_tuning.yaw_rate = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); + } else if (FC.isRatesInDps()) { + 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)); + if (semver.gte(CONFIG.apiVersion, "1.7.0")) { + RC_tuning.dynamic_THR_breakpoint = data.getUint16(offset, 1); + offset += 2; + } else { + RC_tuning.dynamic_THR_breakpoint = 0; + } + if (semver.gte(CONFIG.apiVersion, "1.10.0")) { + RC_tuning.RC_YAW_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); + } else { + RC_tuning.RC_YAW_EXPO = 0; + } + 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 < (message_length / 3); i++, needle += 3) { + PIDs[i][0] = data.getUint8(needle); + PIDs[i][1] = data.getUint8(needle + 1); + PIDs[i][2] = data.getUint8(needle + 2); + } + break; + // Disabled, cleanflight does not use MSP_BOX. + /* + case MSPCodes.MSP_BOX: + AUX_CONFIG_values = []; // empty the array as new data is coming in + + // fill in current data + for (var i = 0; i < data.byteLength; i += 2) { // + 2 because uint16_t = 2 bytes + AUX_CONFIG_values.push(data.getUint16(i, 1)); + } + break; + */ + case MSPCodes.MSP_ARMING_CONFIG: + if (semver.gte(CONFIG.apiVersion, "1.8.0")) { + ARMING_CONFIG.auto_disarm_delay = data.getUint8(0, 1); + ARMING_CONFIG.disarm_kill_switch = data.getUint8(1); + } + break; + case MSPCodes.MSP_LOOP_TIME: + if (semver.gte(CONFIG.apiVersion, "1.8.0")) { + FC_CONFIG.loopTime = data.getInt16(0, 1); + } + break; + case MSPCodes.MSP_MISC: // 22 bytes + var offset = 0; + 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: + var offset = 0; + _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: + AUX_CONFIG = []; // empty the array as new data is coming in + + var buff = []; + for (var 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 + + // empty buffer + buff = []; + } else { + buff.push(data.getUint8(i)); + } + } + break; + case MSPCodes.MSP_PIDNAMES: + PID_names = []; // empty the array as new data is coming in + + var buff = []; + for (var i = 0; i < data.byteLength; i++) { + if (data.getUint8(i) == 0x3B) { // ; (delimeter char) + 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: + AUX_CONFIG_IDS = []; // empty the array as new data is coming in + + for (var i = 0; i < data.byteLength; i++) { + AUX_CONFIG_IDS.push(data.getUint8(i)); + } + break; + case MSPCodes.MSP_SERVO_MIX_RULES: + break; + + case MSPCodes.MSP_SERVO_CONFIGURATIONS: + SERVO_CONFIG = []; // empty the array as new data is coming in + + if (semver.gte(CONFIG.apiVersion, "1.12.0")) { + if (data.byteLength % 14 == 0) { + for (var 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) + }; + + SERVO_CONFIG.push(arr); + } + } + } else { + if (data.byteLength % 7 == 0) { + for (var i = 0; i < data.byteLength; i += 7) { + 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': 45, + 'angleAtMax': 45, + 'indexOfChannelToForward': undefined, + 'reversedInputSources': 0 + }; + + SERVO_CONFIG.push(arr); + } + } + + if (semver.eq(CONFIG.apiVersion, '1.10.0')) { + // drop two unused servo configurations due to MSP rx buffer to small) + while (SERVO_CONFIG.length > 8) { + SERVO_CONFIG.pop(); + } + } + } + break; + case MSPCodes.MSP_RC_DEADBAND: + var offset = 0; + 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: + var offset = 0; + 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_BOX: + console.log('AUX Configuration saved'); + break; + */ + case MSPCodes.MSP_SET_RC_TUNING: + console.log('RC Tuning saved'); + break; + case MSPCodes.MSP_ACC_CALIBRATION: + console.log('Accel calibration executed'); + 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: + for (var i = 0; i < 4; i++) + 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: + RC_MAP = []; // empty the array as new data is coming in + + for (var i = 0; i < data.byteLength; i++) { + 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: + var offset = 0; + CONFIG.mspProtocolVersion = data.getUint8(offset++); + CONFIG.apiVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.0'; + break; + + case MSPCodes.MSP_FC_VARIANT: + var identifier = ''; + var offset; + for (offset = 0; offset < 4; offset++) { + identifier += String.fromCharCode(data.getUint8(offset)); + } + CONFIG.flightControllerIdentifier = identifier; + break; + + case MSPCodes.MSP_FC_VERSION: + var offset = 0; + CONFIG.flightControllerVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.' + data.getUint8(offset++); + break; + + case MSPCodes.MSP_BUILD_INFO: + var offset = 0; + + var dateLength = 11; + var buff = []; + for (var i = 0; i < dateLength; i++) { + buff.push(data.getUint8(offset++)); + } + buff.push(32); // ascii space + + var timeLength = 8; + for (var i = 0; i < timeLength; i++) { + buff.push(data.getUint8(offset++)); + } + CONFIG.buildInfo = String.fromCharCode.apply(null, buff); + break; + + case MSPCodes.MSP_BOARD_INFO: + var identifier = ''; + var offset; + for (offset = 0; offset < 4; offset++) { + identifier += String.fromCharCode(data.getUint8(offset)); + } + CONFIG.boardIdentifier = identifier; + CONFIG.boardVersion = data.getUint16(offset, 1); + offset+=2; + break; + + case MSPCodes.MSP_SET_CHANNEL_FORWARDING: + console.log('Channel forwarding saved'); + break; + + case MSPCodes.MSP_CF_SERIAL_CONFIG: + + if (semver.lt(CONFIG.apiVersion, "1.6.0")) { + SERIAL_CONFIG.ports = []; + var offset = 0; + var serialPortCount = (data.byteLength - (4 * 4)) / 2; + for (var i = 0; i < serialPortCount; i++) { + var serialPort = { + identifier: data.getUint8(offset++, 1), + scenario: data.getUint8(offset++, 1) + } + SERIAL_CONFIG.ports.push(serialPort); + } + SERIAL_CONFIG.mspBaudRate = data.getUint32(offset, 1); + offset+= 4; + SERIAL_CONFIG.cliBaudRate = data.getUint32(offset, 1); + offset+= 4; + SERIAL_CONFIG.gpsBaudRate = data.getUint32(offset, 1); + offset+= 4; + SERIAL_CONFIG.gpsPassthroughBaudRate = data.getUint32(offset, 1); + offset+= 4; + } else { + SERIAL_CONFIG.ports = []; + var offset = 0; + var bytesPerPort = 1 + 2 + (1 * 4); + var serialPortCount = data.byteLength / bytesPerPort; + + for (var 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)] + } + + offset += bytesPerPort; + SERIAL_CONFIG.ports.push(serialPort); + } + } + break; + + case MSPCodes.MSP_SET_CF_SERIAL_CONFIG: + console.log('Serial config saved'); + 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. + + var offset = 0; + for (var i = 0; offset < data.byteLength && i < modeRangeCount; i++) { + 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: + ADJUSTMENT_RANGES = []; // empty the array as new data is coming in + + var adjustmentRangeCount = data.byteLength / 6; // 6 bytes per item. + + var offset = 0; + for (var i = 0; offset < data.byteLength && i < adjustmentRangeCount; i++) { + 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: + for (var i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i ++) { + 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: + var offset = 0; + 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: + var offset = 0; + 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: + RXFAIL_CONFIG = []; // empty the array as new data is coming in + + var channelCount = data.byteLength / 3; + + var offset = 0; + for (var i = 0; offset < data.byteLength && i < channelCount; i++, offset++) { + var rxfailChannel = { + mode: data.getUint8(offset++, 1), + value: data.getUint16(offset++, 1) + }; + RXFAIL_CONFIG.push(rxfailChannel); + } + break; + + + case MSPCodes.MSP_LED_STRIP_CONFIG: + 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; + + var offset = 0; + for (var i = 0; offset < data.byteLength && i < ledCount; i++) { + + if (semver.lt(CONFIG.apiVersion, "1.20.0")) { + 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); + } else { + var mask = data.getUint32(offset, 1); + offset +=4; + + 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; + } + } + + 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: + + LED_COLORS = []; + + var colorCount = data.byteLength / 4; + + var offset = 0; + for (var 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); + 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")) { + + LED_MODE_COLORS = []; + + var colorCount = data.byteLength / 3; + + var offset = 0; + for (var 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_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) { + var + flags = data.getUint8(0); + 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: + var offset = 0; + TRANSPONDER.supported = (data.getUint8(offset++) & 1) != 0; + TRANSPONDER.data = []; + var bytesRemaining = data.byteLength - offset; + for (var i = 0; i < bytesRemaining; i++) { + TRANSPONDER.data.push(data.getUint8(offset++)); + } + break; + case MSPCodes.MSP_SET_TRANSPONDER_CONFIG: + console.log("Transponder config saved"); + break; + + case MSPCodes.MSP_ADVANCED_CONFIG: + var offset = 0; + 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: + FILTER_CONFIG.gyroSoftLpfHz = data.getUint8(0, true); + FILTER_CONFIG.dtermLpfHz = data.getUint16(1, true); + FILTER_CONFIG.yawLpfHz = data.getUint16(3, true); + /* + 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 + */ + break; + + case MSPCodes.MSP_SET_FILTER_CONFIG: + console.log("Filter config saved"); + break; + + case MSPCodes.MSP_PID_ADVANCED: + 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); + 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; + default: + console.log('Unknown code detected: ' + code); + } else { + console.log('FC reports unsupported message error: ' + code); + } + + // trigger callbacks, cleanup/remove callback after trigger + for (var i = this.callbacks.length - 1; i >= 0; i--) { // itterating in reverse because we use .splice which modifies array length + if (i < this.callbacks.length) { + if (this.callbacks[i].code == code) { + // save callback reference + var callback = this.callbacks[i].callback; + + // remove timeout + clearInterval(this.callbacks[i].timer); + + // remove object from array + this.callbacks.splice(i, 1); + + // fire callback + if (callback) callback({'command': code, 'data': data, 'length': message_length}); + } + } + } + } + + self.crunch: function (code) { + var buffer = []; + + 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: + for (var i = 0; i < PIDs.length; i++) { + 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; + // Disabled, cleanflight does not use MSP_SET_BOX. + /* + case MSPCodes.MSP_SET_BOX: + for (var i = 0; i < AUX_CONFIG_values.length; i++) { + buffer.push(lowByte(AUX_CONFIG_values[i])); + buffer.push(highByte(AUX_CONFIG_values[i])); + } + break; + */ + case MSPCodes.MSP_SET_RX_MAP: + for (var i = 0; i < RC_MAP.length; i++) { + 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: + for (var i = 0; i < TRANSPONDER.data.length; i++) { + buffer.push(TRANSPONDER.data[i]); + } + break; + + case MSPCodes.MSP_SET_CHANNEL_FORWARDING: + 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); + } + break; + 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++) { + buffer.push(SERIAL_CONFIG.ports[i].scenario); + } + buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 0)); + buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 1)); + buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 2)); + buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 3)); + + buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 0)); + buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 1)); + buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 2)); + buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 3)); + + buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 0)); + buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 1)); + buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 2)); + buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 3)); + + buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 0)); + buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 1)); + buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 2)); + buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 3)); + } else { + for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) { + var serialPort = SERIAL_CONFIG.ports[i]; + + buffer.push(serialPort.identifier); + + var functionMask = mspHelper.SERIAL_PORT_FUNCTIONSToMask(serialPort.functions); + buffer.push(specificByte(functionMask, 0)); + buffer.push(specificByte(functionMask, 1)); + + 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)); + } + } + 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. + */ + self.setRawRx: function(channels) { + 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); + } + + self.sendBlackboxConfiguration: function(onDataCallback) { + var message = [ + BLACKBOX.blackboxDevice & 0xFF, + BLACKBOX.blackboxRateNum & 0xFF, + BLACKBOX.blackboxRateDenom & 0xFF + ]; + + MSP.send_message(MSPCodes.MSP_SET_BLACKBOX_CONFIG, message, false, function(response) { + onDataCallback(); + }); + } + + self.sendServoConfigurations: function(onCompleteCallback) { + var nextFunction = send_next_servo_configuration; + + var servoIndex = 0; + + if (SERVO_CONFIG.length == 0) { + onCompleteCallback(); + } else { + nextFunction(); + } + + + function send_next_servo_configuration() { + + var buffer = []; + + 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++) { + buffer.push(lowByte(SERVO_CONFIG[i].min)); + buffer.push(highByte(SERVO_CONFIG[i].min)); + + buffer.push(lowByte(SERVO_CONFIG[i].max)); + buffer.push(highByte(SERVO_CONFIG[i].max)); + + buffer.push(lowByte(SERVO_CONFIG[i].middle)); + buffer.push(highByte(SERVO_CONFIG[i].middle)); + + buffer.push(lowByte(SERVO_CONFIG[i].rate)); + } + + nextFunction = send_channel_forwarding; + } else { + // send one at a time, with index + + var servoConfiguration = SERVO_CONFIG[servoIndex]; + + buffer.push(servoIndex); + + buffer.push(lowByte(servoConfiguration.min)); + buffer.push(highByte(servoConfiguration.min)); + + buffer.push(lowByte(servoConfiguration.max)); + buffer.push(highByte(servoConfiguration.max)); + + buffer.push(lowByte(servoConfiguration.middle)); + buffer.push(highByte(servoConfiguration.middle)); + + buffer.push(lowByte(servoConfiguration.rate)); + + buffer.push(servoConfiguration.angleAtMin); + buffer.push(servoConfiguration.angleAtMax); + + var out = servoConfiguration.indexOfChannelToForward; + if (out == undefined) { + out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF" + } + buffer.push(out); + + buffer.push(specificByte(servoConfiguration.reversedInputSources, 0)); + buffer.push(specificByte(servoConfiguration.reversedInputSources, 1)); + buffer.push(specificByte(servoConfiguration.reversedInputSources, 2)); + buffer.push(specificByte(servoConfiguration.reversedInputSources, 3)); + + // prepare for next iteration + servoIndex++; + if (servoIndex == SERVO_CONFIG.length) { + nextFunction = onCompleteCallback; + } + } + 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); + } + } + + self.sendModeRanges: function(onCompleteCallback) { + 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); + } + } + + /** + * 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). + */ + self.dataflashRead: function(address, onDataCallback) { + MSP.send_message(MSPCodes.MSP_DATAFLASH_READ, [address & 0xFF, (address >> 8) & 0xFF, (address >> 16) & 0xFF, (address >> 24) & 0xFF], + 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); + } + }); + } + + self.sendRxFailConfig: function(onCompleteCallback) { + 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); + } + } + + self.SERIAL_PORT_FUNCTIONSToMask: function(functions) { + var mask = 0; + var keys = Object.keys(mspHelper.SERIAL_PORT_FUNCTIONS); + 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; + } + + self.serialPortFunctionMaskToFunctions: function(functionMask) { + 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; + } + + self.sendServoMixRules: function(onCompleteCallback) { + // TODO implement + onCompleteCallback(); + } + + self.sendAdjustmentRanges: function(onCompleteCallback) { + 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); + } + } + + self.sendLedStripColors: function(onCompleteCallback) { + 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); + } + } + + self.sendLedStripConfig: function(onCompleteCallback) { + + 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]; + /* + var led = { + directions: directions, + functions: functions, + x: data.getUint8(offset++, 1), + y: data.getUint8(offset++, 1), + color: data.getUint8(offset++, 1) + }; + */ + 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; + /* + 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 + + */ + 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); + } + } + + self.sendLedStripModeColors: function(onCompleteCallback) { + + 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); + } + } + + return self; +})(); diff --git a/js/serial_backend.js b/js/serial_backend.js index 6ca33347..44fdf5ce 100755 --- a/js/serial_backend.js +++ b/js/serial_backend.js @@ -187,31 +187,31 @@ function onOpen(openInfo) { FC.resetState(); // request configuration data - MSP.send_message(MSP_codes.MSP_API_VERSION, false, false, function () { + MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () { GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion])); if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.apiVersionAccepted)) { - MSP.send_message(MSP_codes.MSP_FC_VARIANT, false, false, function () { + MSP.send_message(MSPCodes.MSP_FC_VARIANT, false, false, function () { - MSP.send_message(MSP_codes.MSP_FC_VERSION, false, false, function () { + MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () { googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion); GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion])); if (CONFIG.flightControllerIdentifier == 'INAV') { - MSP.send_message(MSP_codes.MSP_BUILD_INFO, false, false, function () { + MSP.send_message(MSPCodes.MSP_BUILD_INFO, false, false, function () { googleAnalytics.sendEvent('Firmware', 'Using', CONFIG.buildInfo); GUI.log(chrome.i18n.getMessage('buildInfoReceived', [CONFIG.buildInfo])); - MSP.send_message(MSP_codes.MSP_BOARD_INFO, false, false, function () { + MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, function () { googleAnalytics.sendEvent('Board', 'Using', CONFIG.boardIdentifier + ',' + CONFIG.boardVersion); GUI.log(chrome.i18n.getMessage('boardInfoReceived', [CONFIG.boardIdentifier, CONFIG.boardVersion])); - MSP.send_message(MSP_codes.MSP_UID, false, false, function () { + MSP.send_message(MSPCodes.MSP_UID, false, false, function () { GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)])); // continue as usually @@ -269,12 +269,12 @@ function onConnect() { $('#tabs ul.mode-connected').show(); if (semver.gte(CONFIG.flightControllerVersion, "1.2.0")) { - MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false); + MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false); } else { - MSP.send_message(MSP_codes.MSP_STATUS, false, false); + MSP.send_message(MSPCodes.MSP_STATUS, false, false); } - MSP.send_message(MSP_codes.MSP_DATAFLASH_SUMMARY, false, false); + MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false); $('#sensor-status').show(); $('#portsinput').hide(); @@ -451,12 +451,12 @@ function update_live_status() { }); if (GUI.active_tab != 'cli') { - MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false); + MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false); if (semver.gte(CONFIG.flightControllerVersion, "1.2.0")) - MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false); + MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false); else - MSP.send_message(MSP_codes.MSP_STATUS, false, false); - MSP.send_message(MSP_codes.MSP_ANALOG, false, false); + MSP.send_message(MSPCodes.MSP_STATUS, false, false); + MSP.send_message(MSPCodes.MSP_ANALOG, false, false); } var active = ((Date.now() - MSP.analog_last_received_timestamp) < 300); diff --git a/main.html b/main.html index ce0508e4..b46559f3 100755 --- a/main.html +++ b/main.html @@ -48,6 +48,8 @@ + + diff --git a/main.js b/main.js index 46021fe4..58660cc4 100644 --- a/main.js +++ b/main.js @@ -354,7 +354,7 @@ $(document).ready(function () { profile_e.change(function () { var profile = parseInt($(this).val()); - MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [profile], false, function () { + MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [profile], false, function () { GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1])); updateActivatedTab(); }); diff --git a/tabs/adjustments.js b/tabs/adjustments.js index a6f5d1ba..c87f2e3f 100644 --- a/tabs/adjustments.js +++ b/tabs/adjustments.js @@ -7,44 +7,44 @@ TABS.adjustments.initialize = function (callback) { GUI.active_tab_ref = this; GUI.active_tab = 'adjustments'; googleAnalytics.sendAppView('Adjustments'); - + function get_adjustment_ranges() { - MSP.send_message(MSP_codes.MSP_ADJUSTMENT_RANGES, false, false, get_box_ids); + MSP.send_message(MSPCodes.MSP_ADJUSTMENT_RANGES, false, false, get_box_ids); } function get_box_ids() { - MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data); + MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data); } function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, load_html); + MSP.send_message(MSPCodes.MSP_RC, false, false, load_html); } function load_html() { $('#content').load("./tabs/adjustments.html", process_html); } - MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_adjustment_ranges); + MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_adjustment_ranges); function addAdjustment(adjustmentIndex, adjustmentRange, auxChannelCount) { var template = $('#tab-adjustments-templates').find('.adjustments .adjustment'); var newAdjustment = template.clone(); - + $(newAdjustment).attr('id', 'adjustment-' + adjustmentIndex); $(newAdjustment).data('index', adjustmentIndex); // // update selected slot // - + var channelList = $(newAdjustment).find('.adjustmentSlot .slot'); channelList.val(adjustmentRange.slotIndex); // // populate source channel select box // - + var channelList = $(newAdjustment).find('.channelInfo .channel'); var channelOptionTemplate = $(channelList).find('option'); channelOptionTemplate.remove(); @@ -59,13 +59,13 @@ TABS.adjustments.initialize = function (callback) { // // update selected function // - + var functionList = $(newAdjustment).find('.functionSelection .function'); - - // update list of selected functions + + // update list of selected functions var functionListOptions = $(functionList).find('option'); var availableFunctionCount = 13; - + if (semver.gte(CONFIG.flightControllerVersion, '1.8.0')) { availableFunctionCount += 2; // pitch and roll rate if (semver.gte(CONFIG.flightControllerVersion, '1.9.0')) { @@ -75,18 +75,18 @@ TABS.adjustments.initialize = function (callback) { } } } - + var functionListOptions = $(functionListOptions).slice(0,availableFunctionCount); functionList.empty().append(functionListOptions); - + functionList.val(adjustmentRange.adjustmentFunction); - - + + // // populate function channel select box // - + var channelList = $(newAdjustment).find('.functionSwitchChannel .channel'); var channelOptionTemplate = $(channelList).find('option'); channelOptionTemplate.remove(); @@ -101,12 +101,12 @@ TABS.adjustments.initialize = function (callback) { // // configure range // - + var channel_range = { 'min': [ 900 ], 'max': [ 2100 ] }; - + var defaultRangeValues = [1300, 1700]; var rangeValues = defaultRangeValues; if (adjustmentRange.range != undefined) { @@ -137,16 +137,16 @@ TABS.adjustments.initialize = function (callback) { density: 4, stepped: true }); - + // // add the enable/disable behavior // - + var enableElement = $(newAdjustment).find('.enable'); $(enableElement).data('adjustmentElement', newAdjustment); $(enableElement).change(function() { var adjustmentElement = $(this).data('adjustmentElement'); - if ($(this).prop("checked")) { + if ($(this).prop("checked")) { $(adjustmentElement).find(':input').prop("disabled", false); $(adjustmentElement).find('.channel-slider').removeAttr("disabled"); var rangeElement = $(adjustmentElement).find('.range .channel-slider'); @@ -163,10 +163,10 @@ TABS.adjustments.initialize = function (callback) { // keep this element enabled $(this).prop("disabled", false); }); - - var isEnabled = (adjustmentRange.range.start != adjustmentRange.range.end); + + var isEnabled = (adjustmentRange.range.start != adjustmentRange.range.end); $(enableElement).prop("checked", isEnabled).change(); - + return newAdjustment; } @@ -174,12 +174,12 @@ TABS.adjustments.initialize = function (callback) { var auxChannelCount = RC.active_channels - 4; - var modeTableBodyElement = $('.tab-adjustments .adjustments tbody') + var modeTableBodyElement = $('.tab-adjustments .adjustments tbody') for (var adjustmentIndex = 0; adjustmentIndex < ADJUSTMENT_RANGES.length; adjustmentIndex++) { var newAdjustment = addAdjustment(adjustmentIndex, ADJUSTMENT_RANGES[adjustmentIndex], auxChannelCount); modeTableBodyElement.append(newAdjustment); } - + // translate to user-selected language localize(); @@ -188,9 +188,9 @@ TABS.adjustments.initialize = function (callback) { // update internal data structures based on current UI elements var requiredAdjustmentRangeCount = ADJUSTMENT_RANGES.length; - + ADJUSTMENT_RANGES = []; - + var defaultAdjustmentRange = { slotIndex: 0, auxChannelIndex: 0, @@ -204,7 +204,7 @@ TABS.adjustments.initialize = function (callback) { $('.tab-adjustments .adjustments .adjustment').each(function () { var adjustmentElement = $(this); - + if ($(adjustmentElement).find('.enable').prop("checked")) { var rangeValues = $(this).find('.range .channel-slider').val(); var adjustmentRange = { @@ -222,18 +222,18 @@ TABS.adjustments.initialize = function (callback) { ADJUSTMENT_RANGES.push(defaultAdjustmentRange); } }); - + for (var adjustmentRangeIndex = ADJUSTMENT_RANGES.length; adjustmentRangeIndex < requiredAdjustmentRangeCount; adjustmentRangeIndex++) { ADJUSTMENT_RANGES.push(defaultAdjustmentRange); } - + // // send data to FC // - MSP.sendAdjustmentRanges(save_to_eeprom); - + mspHelper.sendAdjustmentRanges(save_to_eeprom); + function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { GUI.log(chrome.i18n.getMessage('adjustmentsEepromSaved')); }); } @@ -247,20 +247,20 @@ TABS.adjustments.initialize = function (callback) { channelPosition = 2100; } var percentage = (channelPosition - 900) / (2100-900) * 100; - + $('.adjustments .adjustment').each( function () { var auxChannelCandidateIndex = $(this).find('.channel').val(); if (auxChannelCandidateIndex != auxChannelIndex) { return; } - + $(this).find('.range .marker').css('left', percentage + '%'); }); } // data pulling functions used inside interval timer function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); + MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui); } function update_ui() { @@ -268,7 +268,7 @@ TABS.adjustments.initialize = function (callback) { for (var auxChannelIndex = 0; auxChannelIndex < auxChannelCount; auxChannelIndex++) { update_marker(auxChannelIndex, RC.channels[auxChannelIndex + 4]); - } + } } // update ui instantly on first load @@ -279,7 +279,7 @@ TABS.adjustments.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function () { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); @@ -288,4 +288,4 @@ TABS.adjustments.initialize = function (callback) { TABS.adjustments.cleanup = function (callback) { if (callback) callback(); -}; \ No newline at end of file +}; diff --git a/tabs/auxiliary.js b/tabs/auxiliary.js index 7135c943..0071dd9a 100644 --- a/tabs/auxiliary.js +++ b/tabs/auxiliary.js @@ -8,22 +8,22 @@ TABS.auxiliary.initialize = function (callback) { googleAnalytics.sendAppView('Auxiliary'); function get_mode_ranges() { - MSP.send_message(MSP_codes.MSP_MODE_RANGES, false, false, get_box_ids); + MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids); } function get_box_ids() { - MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data); + MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data); } function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, load_html); + MSP.send_message(MSPCodes.MSP_RC, false, false, load_html); } function load_html() { $('#content').load("./tabs/auxiliary.html", process_html); } - MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_mode_ranges); + MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges); function createMode(modeIndex, modeId) { var modeTemplate = $('#tab-auxiliary-templates .mode'); @@ -216,7 +216,7 @@ TABS.auxiliary.initialize = function (callback) { // // send data to FC // - MSP.sendModeRanges(save_to_eeprom); + mspHelper.sendModeRanges(save_to_eeprom); /* * Send some data to analytics @@ -227,7 +227,7 @@ TABS.auxiliary.initialize = function (callback) { } function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { GUI.log(chrome.i18n.getMessage('auxiliaryEepromSaved')); }); } @@ -257,7 +257,7 @@ TABS.auxiliary.initialize = function (callback) { // data pulling functions used inside interval timer function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); + MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui); } function update_ui() { @@ -292,7 +292,7 @@ TABS.auxiliary.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function () { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); diff --git a/tabs/cli.js b/tabs/cli.js index 1400b502..7160027f 100644 --- a/tabs/cli.js +++ b/tabs/cli.js @@ -172,7 +172,7 @@ TABS.cli.read = function (readInfo) { } else { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { + MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { GUI.log(chrome.i18n.getMessage('deviceReady')); if (!GUI.tab_switch_in_progress) { $('#tabs ul.mode-connected .tab_setup a').click(); diff --git a/tabs/configuration.js b/tabs/configuration.js index 0bccc08e..32b81fdc 100644 --- a/tabs/configuration.js +++ b/tabs/configuration.js @@ -11,30 +11,30 @@ TABS.configuration.initialize = function (callback, scrollPosition) { } function load_config() { - MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_serial_config); + MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_serial_config); } function load_serial_config() { var next_callback = load_rc_map; if (semver.lt(CONFIG.apiVersion, "1.6.0")) { - MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, next_callback); } else { next_callback(); } } function load_rc_map() { - MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_misc); + MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_misc); } function load_misc() { - MSP.send_message(MSP_codes.MSP_MISC, false, false, load_arming_config); + MSP.send_message(MSPCodes.MSP_MISC, false, false, load_arming_config); } function load_arming_config() { var next_callback = load_loop_time; if (semver.gte(CONFIG.apiVersion, "1.8.0")) { - MSP.send_message(MSP_codes.MSP_ARMING_CONFIG, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_ARMING_CONFIG, false, false, next_callback); } else { next_callback(); } @@ -43,7 +43,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_loop_time() { var next_callback = load_rx_config; if (semver.gte(CONFIG.apiVersion, "1.8.0")) { - MSP.send_message(MSP_codes.MSP_LOOP_TIME, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, next_callback); } else { next_callback(); } @@ -52,7 +52,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_rx_config() { var next_callback = load_3d; if (semver.gte(CONFIG.apiVersion, "1.21.0")) { - MSP.send_message(MSP_codes.MSP_RX_CONFIG, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, next_callback); } else { next_callback(); } @@ -61,7 +61,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_3d() { var next_callback = load_sensor_alignment; if (semver.gte(CONFIG.apiVersion, "1.14.0")) { - MSP.send_message(MSP_codes.MSP_3D, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback); } else { next_callback(); } @@ -70,7 +70,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function load_sensor_alignment() { var next_callback = loadAdvancedConfig; if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - MSP.send_message(MSP_codes.MSP_SENSOR_ALIGNMENT, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_SENSOR_ALIGNMENT, false, false, next_callback); } else { next_callback(); } @@ -79,7 +79,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function loadAdvancedConfig() { var next_callback = loadINAVPidConfig; if (semver.gte(CONFIG.flightControllerVersion, "1.3.0")) { - MSP.send_message(MSP_codes.MSP_ADVANCED_CONFIG, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback); } else { next_callback(); } @@ -88,7 +88,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function loadINAVPidConfig() { var next_callback = load_html; if (semver.gt(CONFIG.flightControllerVersion, "1.3.0")) { - MSP.send_message(MSP_codes.MSP_INAV_PID, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, next_callback); } else { next_callback(); } @@ -96,7 +96,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { //Update Analog/Battery Data function load_analog() { - MSP.send_message(MSP_codes.MSP_ANALOG, false, false, function () { + MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () { $('input[name="batteryvoltage"]').val([ANALOG.voltage.toFixed(1)]); $('input[name="batterycurrent"]').val([ANALOG.amperage.toFixed(2)]); }); @@ -106,7 +106,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('#content').load("./tabs/configuration.html", process_html); } - MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_config); + MSP.send_message(MSPCodes.MSP_IDENT, false, false, load_config); function process_html() { @@ -708,20 +708,20 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function save_serial_config() { if (semver.lt(CONFIG.apiVersion, "1.6.0")) { - MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc); + MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc); } else { save_misc(); } } function save_misc() { - MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_3d); + MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_3d); } function save_3d() { var next_callback = save_sensor_alignment; if(semver.gte(CONFIG.apiVersion, "1.14.0")) { - MSP.send_message(MSP_codes.MSP_SET_3D, MSP.crunch(MSP_codes.MSP_SET_3D), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_3D, mspHelper.crunch(MSPCodes.MSP_SET_3D), false, next_callback); } else { next_callback(); } @@ -730,29 +730,29 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function save_sensor_alignment() { var next_callback = save_acc_trim; if(semver.gte(CONFIG.apiVersion, "1.15.0")) { - MSP.send_message(MSP_codes.MSP_SET_SENSOR_ALIGNMENT, MSP.crunch(MSP_codes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback); } else { next_callback(); } } function save_acc_trim() { - MSP.send_message(MSP_codes.MSP_SET_ACC_TRIM, MSP.crunch(MSP_codes.MSP_SET_ACC_TRIM), false + MSP.send_message(MSPCodes.MSP_SET_ACC_TRIM, mspHelper.crunch(MSPCodes.MSP_SET_ACC_TRIM), false , semver.gte(CONFIG.apiVersion, "1.8.0") ? save_arming_config : save_to_eeprom); } function save_arming_config() { - MSP.send_message(MSP_codes.MSP_SET_ARMING_CONFIG, MSP.crunch(MSP_codes.MSP_SET_ARMING_CONFIG), false, save_looptime_config); + MSP.send_message(MSPCodes.MSP_SET_ARMING_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ARMING_CONFIG), false, save_looptime_config); } function save_looptime_config() { - MSP.send_message(MSP_codes.MSP_SET_LOOP_TIME, MSP.crunch(MSP_codes.MSP_SET_LOOP_TIME), false, save_rx_config); + MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, save_rx_config); } function save_rx_config() { var next_callback = saveAdvancedConfig; if(semver.gte(CONFIG.apiVersion, "1.21.0")) { - MSP.send_message(MSP_codes.MSP_SET_RX_CONFIG, MSP.crunch(MSP_codes.MSP_SET_RX_CONFIG), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, next_callback); } else { next_callback(); } @@ -761,7 +761,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function saveAdvancedConfig() { var next_callback = saveINAVPidConfig; if(semver.gte(CONFIG.flightControllerVersion, "1.3.0")) { - MSP.send_message(MSP_codes.MSP_SET_ADVANCED_CONFIG, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_CONFIG), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback); } else { next_callback(); } @@ -770,21 +770,21 @@ TABS.configuration.initialize = function (callback, scrollPosition) { function saveINAVPidConfig() { var next_callback = save_to_eeprom; if(semver.gt(CONFIG.flightControllerVersion, "1.3.0")) { - MSP.send_message(MSP_codes.MSP_SET_INAV_PID, MSP.crunch(MSP_codes.MSP_SET_INAV_PID), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_INAV_PID, mspHelper.crunch(MSPCodes.MSP_SET_INAV_PID), false, next_callback); } else { next_callback(); } } function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot); } function reboot() { GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.tab_switch_cleanup(function() { - MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize); + MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize); }); } @@ -799,7 +799,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { } else { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { + MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { GUI.log(chrome.i18n.getMessage('deviceReady')); TABS.configuration.initialize(false, $('#content').scrollTop()); }); @@ -807,12 +807,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) { } } - MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_serial_config); + MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_serial_config); }); // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.interval_add('config_load_analog', load_analog, 250, true); // 4 fps GUI.content_ready(callback); diff --git a/tabs/failsafe.js b/tabs/failsafe.js index 0cd23a9c..8fbebaec 100644 --- a/tabs/failsafe.js +++ b/tabs/failsafe.js @@ -11,40 +11,40 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { } function load_rx_config() { - MSP.send_message(MSP_codes.MSP_RX_CONFIG, false, false, load_failssafe_config); + MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, load_failssafe_config); } function load_failssafe_config() { - MSP.send_message(MSP_codes.MSP_FAILSAFE_CONFIG, false, false, load_rxfail_config); + MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_rxfail_config); } - + function load_rxfail_config() { - MSP.send_message(MSP_codes.MSP_RXFAIL_CONFIG, false, false, get_box_names); + MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false, get_box_names); } function get_box_names() { - MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_mode_ranges); + MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges); } function get_mode_ranges() { - MSP.send_message(MSP_codes.MSP_MODE_RANGES, false, false, get_box_ids); + MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids); } function get_box_ids() { - MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data); + MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data); } function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, load_config); + MSP.send_message(MSPCodes.MSP_RC, false, false, load_config); } // BEGIN Support for pre API version 1.15.0 function load_config() { - MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_misc); + MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc); } function load_misc() { - MSP.send_message(MSP_codes.MSP_MISC, false, false, load_html); + MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html); } // END (Support for pre API version 1.15.0 @@ -58,9 +58,9 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { //apiVersionGte1_15_0 = false; if(apiVersionGte1_15_0) { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_rx_config); + MSP.send_message(MSPCodes.MSP_IDENT, false, false, load_rx_config); } else { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_config); + MSP.send_message(MSPCodes.MSP_IDENT, false, false, load_config); } function process_html() { @@ -317,32 +317,32 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { } function save_failssafe_config() { - MSP.send_message(MSP_codes.MSP_SET_FAILSAFE_CONFIG, MSP.crunch(MSP_codes.MSP_SET_FAILSAFE_CONFIG), false, save_rxfail_config); + MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_rxfail_config); } function save_rxfail_config() { - MSP.sendRxFailConfig(save_bf_config); + mspHelper.sendRxFailConfig(save_bf_config); } function save_bf_config() { - MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_to_eeprom); + MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom); } // BEGIN pre API 1.15.0 save functions function save_misc() { - MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_to_eeprom); + MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_to_eeprom); } // END pre API 1.15.0 save functions function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot); } function reboot() { GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.tab_switch_cleanup(function() { - MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize); + MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize); }); } @@ -357,7 +357,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { } else { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { + MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { GUI.log(chrome.i18n.getMessage('deviceReady')); TABS.failsafe.initialize(false, $('#content').scrollTop()); }); @@ -366,15 +366,15 @@ TABS.failsafe.initialize = function (callback, scrollPosition) { } if(apiVersionGte1_15_0) { - MSP.send_message(MSP_codes.MSP_SET_RX_CONFIG, MSP.crunch(MSP_codes.MSP_SET_RX_CONFIG), false, save_failssafe_config); + MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, save_failssafe_config); } else { - MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_misc); + MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_misc); } }); // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); diff --git a/tabs/gps.js b/tabs/gps.js index 84a8f55a..65dc4764 100644 --- a/tabs/gps.js +++ b/tabs/gps.js @@ -13,7 +13,7 @@ TABS.gps.initialize = function (callback) { $('#content').load("./tabs/gps.html", process_html); } - MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_html); + MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_html); function set_online(){ $('#connect').hide(); @@ -32,15 +32,15 @@ TABS.gps.initialize = function (callback) { localize(); function get_raw_gps_data() { - MSP.send_message(MSP_codes.MSP_RAW_GPS, false, false, get_comp_gps_data); + MSP.send_message(MSPCodes.MSP_RAW_GPS, false, false, get_comp_gps_data); } function get_comp_gps_data() { - MSP.send_message(MSP_codes.MSP_COMP_GPS, false, false, get_gpsstatistics_data); + MSP.send_message(MSPCodes.MSP_COMP_GPS, false, false, get_gpsstatistics_data); } function get_gpsstatistics_data() { - MSP.send_message(MSP_codes.MSP_GPSSTATISTICS, false, false, update_ui); + MSP.send_message(MSPCodes.MSP_GPSSTATISTICS, false, false, update_ui); } function update_ui() { @@ -113,7 +113,7 @@ TABS.gps.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); diff --git a/tabs/led_strip.js b/tabs/led_strip.js index 33532d2c..a31bd6ca 100644 --- a/tabs/led_strip.js +++ b/tabs/led_strip.js @@ -29,30 +29,30 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } function load_led_config() { - MSP.send_message(MSP_codes.MSP_LED_STRIP_CONFIG, false, false, load_led_colors); + MSP.send_message(MSPCodes.MSP_LED_STRIP_CONFIG, false, false, load_led_colors); } function load_led_colors() { - MSP.send_message(MSP_codes.MSP_LED_COLORS, false, false, load_led_mode_colors); + MSP.send_message(MSPCodes.MSP_LED_COLORS, false, false, load_led_mode_colors); } function load_led_mode_colors() { if (semver.gte(CONFIG.apiVersion, "1.19.0")) - MSP.send_message(MSP_codes.MSP_LED_STRIP_MODECOLOR, false, false, load_html); + MSP.send_message(MSPCodes.MSP_LED_STRIP_MODECOLOR, false, false, load_html); else load_html(); } - - - + + + function load_html() { $('#content').load("./tabs/led_strip.html", process_html); } load_led_config(); - + function buildUsedWireNumbers() { var usedWireNumbers = []; @@ -65,9 +65,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { usedWireNumbers.sort(function(a,b){return a - b}); return usedWireNumbers; } - + function process_html() { - + localize(); // Build Grid @@ -145,7 +145,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { updateBulkCmd(); } }); - + // Mode Color Buttons $('.mode_colors').on('click', 'button', function() { var that = this; @@ -166,7 +166,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $(className).addClass('btnOn'); selectedColorIndex = colorIndex; setColorSliders(colorIndex); - + } else { $(className).removeClass('btnOn'); } @@ -180,15 +180,15 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { if (! $(this).is($(that))) { if ($(this).is('.btnOn')) { $(this).removeClass('btnOn'); - } + } } }); }); - + updateBulkCmd(); - + }); - + // Color sliders var ip = $('div.colorDefineSliders input'); ip.eq(0).on("input change", function() { updateColors($(this).val(), 0); }); @@ -202,12 +202,12 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('.colors').on('click', 'button', function(e) { var that = this; var colorButtons = $(this).parent().find('button'); - + for (var colorIndex = 0; colorIndex < 16; colorIndex++) { colorButtons.removeClass('btnOn'); if (selectedModeColor == undefined) $('.ui-selected').removeClass('color-' + colorIndex); - + if ($(that).is('.color-' + colorIndex)) { selectedColorIndex = colorIndex; if (selectedModeColor == undefined) @@ -217,7 +217,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { setColorSliders(selectedColorIndex); - + $(this).addClass('btnOn'); if (selectedModeColor) { @@ -226,28 +226,28 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { drawColorBoxesInColorLedPoints(); - // refresh color buttons + // refresh color buttons $('.colors').children().each(function() { setBackgroundColor($(this)); }); $('.overlay-color').each(function() { setBackgroundColor($(this)); }); - + $('.mode_colors').each(function() { setModeBackgroundColor($(this)); }); $('.special_colors').each(function() { setModeBackgroundColor($(this)); }); - + updateBulkCmd(); }); - + $('.colors').on('dblclick', 'button', function(e) { var pp = $('.tab-led-strip').position(); var moveLeft = $('.tab-led-strip').position().left + ($('.colorDefineSliders').width() / 2); var moveUp = $('.tab-led-strip').position().top + $('.colorDefineSliders').height() + 20; - + $('.colorDefineSliders').css('left', e.pageX - e.offsetX - moveLeft); $('.colorDefineSliders').css('top', e.pageY - e.offsetY - moveUp); $('.colorDefineSliders').show(); - + }); - + $('.colorDefineSliders').on({ mouseleave: function () { $('.colorDefineSliders').hide(); @@ -260,10 +260,10 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('.colorDefineSliders').hide(); } }); - + $('.funcWire').click(function() { $(this).toggleClass('btnOn'); - TABS.led_strip.wireMode = $(this).hasClass('btnOn'); + TABS.led_strip.wireMode = $(this).hasClass('btnOn'); $('.mainGrid').toggleClass('gridWire'); }); @@ -292,16 +292,16 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { var that; $('.ui-selected').each(function() { - + var usedWireNumbers = buildUsedWireNumbers(); - + var nextWireNumber = 0; for (var nextWireNumber = 0; nextWireNumber < usedWireNumbers.length; nextWireNumber++) { if (usedWireNumbers[nextWireNumber] != nextWireNumber) { break; } } - + if (TABS.led_strip.wireMode) { if ($(this).find('.wire').html() == '' && nextWireNumber < LED_STRIP.length) { $(this).find('.wire').html(nextWireNumber); @@ -319,14 +319,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { directionsInSelection.push(className); } }); - + TABS.led_strip.baseFuncs.forEach(function(letter) { var className = '.function-' + letter; if ($(that).is(className)) { functionsInSelection.push(className); } }); - + TABS.led_strip.overlays.forEach(function(letter) { var className = '.function-' + letter; if ($(that).is(className)) { @@ -345,47 +345,47 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('select.functionSelect').removeClass(className); } }); - + selectedColorIndex = 0; - + if (uiSelectedLast) { - + // set active color for (var colorIndex = 0; colorIndex < 16; colorIndex++) { var className = '.color-' + colorIndex; if ($(uiSelectedLast).is(className)) { $(className).addClass('btnOn'); selectedColorIndex = colorIndex; - + } else { $(className).removeClass('btnOn'); } } - + // set checkbox values TABS.led_strip.overlays.forEach(function(letter) { var feature_o = $('.checkbox').find('input.function-' + letter); - + var newVal = ($(uiSelectedLast).is('.function-' + letter)); - + if (feature_o.is(':checked') != newVal) { feature_o.prop('checked', newVal); feature_o.change(); } }); - + // Update active function in combobox TABS.led_strip.baseFuncs.forEach(function(letter) { if ($(uiSelectedLast).is('.function-' + letter)) { $('select.functionSelect').val("function-" + letter); $('select.functionSelect').addClass("function-" + letter); } - }); + }); } updateBulkCmd(); - + setColorSliders(selectedColorIndex); - + setOptionalGroupsVisibility(); $('.directions button').removeClass('btnOn'); @@ -408,7 +408,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('.modeSelect').on('change', function() { var that = this; - + var mode = Number($(that).val()); $('.mode_colors').find('button').each(function() { for (var i = 0; i < 6; i++) @@ -421,13 +421,13 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('.mode_colors').each(function() { setModeBackgroundColor($(this)); }); }); - + function toggleSwitch(that, letter) { if ($(that).is(':checked')) { $('.ui-selected').find('.wire').each(function() { if ($(this).text() != "") { - + var p = $(this).parent(); TABS.led_strip.functions.forEach(function(f) { @@ -464,21 +464,21 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } return $(that).is(':checked'); } - + // UI: check-box toggle - $('.checkbox').change(function(e) { + $('.checkbox').change(function(e) { if (e.originalEvent) { // user-triggered event var that = $(this).find('input'); if ($('.ui-selected').length > 0) { - + TABS.led_strip.overlays.forEach(function(letter) { if ($(that).is('.function-' + letter)) { var ret = toggleSwitch(that, letter); - + var cbn = $('.checkbox .function-n'); // blink on landing var cbb = $('.checkbox .function-b'); // blink - + if (ret) { if (letter == 'b' && cbn.is(':checked')) { cbn.prop('checked', false); @@ -488,11 +488,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { cbb.prop('checked', false); cbb.change(); toggleSwitch(cbb, 'b'); - } + } } } }); - + clearModeColorSelection(); updateBulkCmd(); setOptionalGroupsVisibility(); @@ -501,9 +501,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { // code-triggered event } }); - - + + $('.mainGrid').disableSelection(); $('.gPoint').each(function(){ @@ -513,50 +513,50 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { if (col < 0) { col = 15; } - + var ledResult = findLed(col, row); if (!ledResult) { return; } - + var ledIndex = ledResult.index; var led = ledResult.led; - + if (led.functions[0] == 'c' && led.functions.length == 1 && led.directions.length == 0 && led.color == 0 && led.x == 0 && led.y == 0) { return; } - + $(this).find('.wire').html(ledIndex); for (var modeIndex = 0; modeIndex < led.functions.length; modeIndex++) { $(this).addClass('function-' + led.functions[modeIndex]); } - + for (var directionIndex = 0; directionIndex < led.directions.length; directionIndex++) { $(this).addClass('dir-' + led.directions[directionIndex]); } - + $(this).addClass('color-' + led.color); }); $('a.save').click(function () { - MSP.sendLedStripConfig(send_led_strip_colors); - + mspHelper.sendLedStripConfig(send_led_strip_colors); + function send_led_strip_colors() { - MSP.sendLedStripColors(send_led_strip_mode_colors); + mspHelper.sendLedStripColors(send_led_strip_mode_colors); } - + function send_led_strip_mode_colors() { if (semver.gte(CONFIG.apiVersion, "1.19.0")) - MSP.sendLedStripModeColors(save_to_eeprom); + mspHelper.sendLedStripModeColors(save_to_eeprom); else save_to_eeprom(); } - + function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() { + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function() { GUI.log(chrome.i18n.getMessage('ledStripEepromSaved')); }); } @@ -564,19 +564,19 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { }); $('.colorDefineSliders').hide(); - + applyFunctionToSelectedLeds(); drawColorBoxesInColorLedPoints(); setOptionalGroupsVisibility(); - + updateBulkCmd(); - + GUI.content_ready(callback); } - - - - + + + + @@ -589,8 +589,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } return undefined; } - - + + function updateBulkCmd() { var counter = 0; @@ -598,9 +598,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { var ledStripLength = LED_STRIP.length; var ledColorsLength = LED_COLORS.length; var ledModeColorsLenggth = LED_MODE_COLORS.length; - + LED_STRIP = []; - + $('.gPoint').each(function(){ if ($(this).is('[class*="function"]')) { var gridNumber = ($(this).index() + 1); @@ -613,7 +613,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { var directions = ''; var colorIndex = 0; var that = this; - + var match = $(this).attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/); if (match) { colorIndex = match[2]; @@ -644,7 +644,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { functions: functions, color: colorIndex } - + LED_STRIP[wireNumber] = led; } counter++; @@ -657,28 +657,28 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { directions: '', functions: '' }; - + for (var i = 0; i < ledStripLength; i++) { if (LED_STRIP[i]) { continue; } LED_STRIP[i] = defaultLed; } - + var usedWireNumbers = buildUsedWireNumbers(); var remaining = LED_STRIP.length - usedWireNumbers.length; - + $('.wires-remaining div').html(remaining); } // refresh mode color buttons function setModeBackgroundColor(element) { if (semver.gte(CONFIG.apiVersion, "1.19.0")) { - element.find('[class*="mode_color"]').each(function() { + element.find('[class*="mode_color"]').each(function() { var m = 0; var d = 0; - + var match = $(this).attr("class").match(/(^|\s)mode_color-([0-9]+)-([0-9]+)(\s|$)/); if (match) { m = Number(match[2]); @@ -688,11 +688,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { }); } } - + function setBackgroundColor(element) { if (element.is('[class*="color"]')) { var colorIndex = 0; - + var match = element.attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/); if (match) { colorIndex = match[2]; @@ -700,11 +700,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } } } - + function areModifiersActive(activeFunction) { switch (activeFunction) { - case "function-c": - case "function-a": + case "function-c": + case "function-a": case "function-f": return true; break; @@ -715,8 +715,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { function areOverlaysActive(activeFunction) { if (semver.lt(CONFIG.apiVersion, "1.20.0")) { switch (activeFunction) { - case "function-c": - case "function-a": + case "function-c": + case "function-a": case "function-f": case "function-g": return true; @@ -724,13 +724,13 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } } else { switch (activeFunction) { - case "": - case "function-c": - case "function-a": + case "": + case "function-c": + case "function-a": case "function-f": case "function-s": case "function-l": - case "function-r": + case "function-r": case "function-o": case "function-g": return true; @@ -743,8 +743,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { function areBlinkersActive(activeFunction) { if (semver.gte(CONFIG.apiVersion, "1.20.0")) { switch (activeFunction) { - case "function-c": - case "function-a": + case "function-c": + case "function-a": case "function-f": return true; break; @@ -755,7 +755,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { function isWarningActive(activeFunction) { switch (activeFunction) { - case "function-l": + case "function-l": case "function-s": case "function-g": return false; @@ -765,26 +765,26 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { if (semver.lt(CONFIG.apiVersion, "1.20.0")) return false; break; - default: + default: return true; - break; + break; } } - + function setOptionalGroupsVisibility() { - + var activeFunction = $('select.functionSelect').val(); $('select.functionSelect').addClass(activeFunction); - - if (semver.lte(CONFIG.apiVersion, "1.18.0")) { + + if (semver.lte(CONFIG.apiVersion, "1.18.0")) { // <= 18 // Hide GPS (Func) // Hide RSSI (O/L), Blink (Func) // Hide Battery, RSSI (Func), Larson (O/L), Blink (O/L), Landing (O/L) $(".extra_functions20").hide(); $(".mode_colors").hide(); - } else { + } else { // >= 20 // Show GPS (Func) // Hide RSSI (O/L), Blink (Func) @@ -792,14 +792,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $(".extra_functions20").show(); $(".mode_colors").show(); } - - + + // set color modifiers (check-boxes) visibility $('.overlays').hide(); $('.modifiers').hide(); $('.blinkers').hide(); $('.warningOverlay').hide(); - + if (areOverlaysActive(activeFunction)) $('.overlays').show(); @@ -812,7 +812,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { if (isWarningActive(activeFunction)) $('.warningOverlay').show(); - + // set directions visibility if (semver.lt(CONFIG.apiVersion, "1.20.0")) { @@ -821,21 +821,21 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('.indicatorOverlay').hide(); $('.directions').hide(); break; - default: + default: $('.indicatorOverlay').show(); $('.directions').show(); - break; + break; } } - + $('.mode_colors').hide(); - if (semver.gte(CONFIG.apiVersion, "1.19.0")) { + if (semver.gte(CONFIG.apiVersion, "1.19.0")) { // set mode colors visibility if (semver.gte(CONFIG.apiVersion, "1.20.0")) if (activeFunction == "function-f") - $('.mode_colors').show(); - + $('.mode_colors').show(); + // set special colors visibility $('.special_colors').show(); $('.mode_color-6-0').hide(); @@ -846,11 +846,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { $('.mode_color-6-5').hide(); $('.mode_color-6-6').hide(); $('.mode_color-6-7').hide(); - + switch (activeFunction) { case "": // none case "function-f": // Modes & Orientation - case "function-l": // Battery + case "function-l": // Battery // $('.mode_color-6-3').show(); // background $('.special_colors').hide(); break; @@ -861,47 +861,47 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { // $('.mode_color-6-3').show(); // background break; case "function-b": // Blink - $('.mode_color-6-4').show(); // blink background + $('.mode_color-6-4').show(); // blink background break; case "function-a": // Arm state - $('.mode_color-6-0').show(); // disarmed - $('.mode_color-6-1').show(); // armed + $('.mode_color-6-0').show(); // disarmed + $('.mode_color-6-1').show(); // armed break; - + case "function-r": // Ring default: $('.special_colors').hide(); - break; + break; } } } - + function applyFunctionToSelectedLeds() { var activeFunction = $('select.functionSelect').val(); TABS.led_strip.baseFuncs.forEach(function(letter) { - + if (activeFunction == 'function-' + letter) { $('select.functionSelect').addClass('function-' + letter); - + $('.ui-selected').find('.wire').each(function() { if ($(this).text() != "") $(this).parent().addClass('function-' + letter); }); - + unselectOverlays(letter); } else { $('select.functionSelect').removeClass('function-' + letter); $('.ui-selected').removeClass('function-' + letter); } - + if (activeFunction == '') { unselectOverlays(activeFunction); } }); } - + function unselectOverlays(letter) { if (semver.lt(CONFIG.apiVersion, "1.20.0")) { if (letter == 'b' || letter == 'r') { @@ -929,7 +929,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } } } - + function unselectOverlay(func, overlay) { $('input.function-' + overlay).prop('checked', false); $('input.function-' + overlay).change(); @@ -939,12 +939,12 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } }); } - + function updateColors(value, hsvIndex) { var change = false; - + value = Number(value); - + var className = '.color-' + selectedColorIndex; if ($(className).hasClass('btnOn')) { switch (hsvIndex) { @@ -955,40 +955,40 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { change = true } break; - case 1: + case 1: if (LED_COLORS[selectedColorIndex].s != value) { LED_COLORS[selectedColorIndex].s = value; $('.colorDefineSliderValue.Svalue').text(LED_COLORS[selectedColorIndex].s); change = true } break; - case 2: + case 2: if (LED_COLORS[selectedColorIndex].v != value) { LED_COLORS[selectedColorIndex].v = value; $('.colorDefineSliderValue.Vvalue').text(LED_COLORS[selectedColorIndex].v); change = true } break; - } + } } - - // refresh color buttons + + // refresh color buttons $('.colors').children().each(function() { setBackgroundColor($(this)); }); $('.overlay-color').each(function() { setBackgroundColor($(this)); }); - + $('.mode_colors').each(function() { setModeBackgroundColor($(this)); }); $('.special_colors').each(function() { setModeBackgroundColor($(this)); }); - + if (change) updateBulkCmd(); } - + function drawColorBoxesInColorLedPoints() { $('.gPoint').each(function() { if ($(this).is('.function-c') || $(this).is('.function-r') || $(this).is('.function-b')) { $(this).find('.overlay-color').show(); - + for (var colorIndex = 0; colorIndex < 16; colorIndex++) { var className = 'color-' + colorIndex; if ($(this).is('.' + className)) { @@ -1004,27 +1004,27 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } }); } - + function setColorSliders(colorIndex) { var sliders = $('div.colorDefineSliders input'); var change = false; - + if (!LED_COLORS[colorIndex]) return; - + if (LED_COLORS[colorIndex].h != Number(sliders.eq(0).val())) { sliders.eq(0).val(LED_COLORS[colorIndex].h); $('.colorDefineSliderValue.Hvalue').text(LED_COLORS[colorIndex].h); change = true; } - + if (LED_COLORS[colorIndex].s != Number(sliders.eq(1).val())) { sliders.eq(1).val(LED_COLORS[colorIndex].s); $('.colorDefineSliderValue.Svalue').text(LED_COLORS[colorIndex].s); change = true; } - + if (LED_COLORS[colorIndex].v != Number(sliders.eq(2).val())) { sliders.eq(2).val(LED_COLORS[colorIndex].v); $('.colorDefineSliderValue.Vvalue').text(LED_COLORS[colorIndex].v); @@ -1034,25 +1034,25 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { // only fire events when all values are set if (change) sliders.trigger('input'); - + } - + function HsvToColor(input) { if (input == undefined) return ""; - + var HSV = { h:Number(input.h), s:Number(input.s), v:Number(input.v) }; - + if (HSV.s == 0 && HSV.v == 0) return ""; - + HSV = { h:HSV.h, s:1 - HSV.s / 255, v:HSV.v / 255 }; - + var HSL = { h:0, s:0, v:0}; HSL.h = HSV.h; HSL.l = (2 - HSV.s) * HSV.v / 2; HSL.s = HSL.l && HSL.l < 1 ? HSV.s * HSV.v / (HSL.l < 0.5 ? HSL.l * 2 : 2 - HSL.l * 2) : HSL.s; - + var ret = 'hsl(' + HSL.h + ', ' + HSL.s * 100 + '%, ' + HSL.l * 100 + '%)'; return ret; } @@ -1076,14 +1076,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { } return 0; } - + function clearModeColorSelection() { selectedModeColor = null; $('.mode_colors').each(function() { $(this).children().each(function() { if ($(this).is('.btnOn')) { $(this).removeClass('btnOn'); - } + } }); }); } @@ -1091,4 +1091,4 @@ TABS.led_strip.initialize = function (callback, scrollPosition) { TABS.led_strip.cleanup = function (callback) { if (callback) callback(); -}; \ No newline at end of file +}; diff --git a/tabs/logging.js b/tabs/logging.js index d85a54ab..38f081fd 100644 --- a/tabs/logging.js +++ b/tabs/logging.js @@ -16,14 +16,14 @@ TABS.logging.initialize = function (callback) { if (CONFIGURATOR.connectionValid) { var get_motor_data = function () { - MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); + MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_html); } var load_html = function () { $('#content').load("./tabs/logging.html", process_html); } - MSP.send_message(MSP_codes.MSP_RC, false, false, get_motor_data); + MSP.send_message(MSPCodes.MSP_RC, false, false, get_motor_data); } function process_html() { @@ -61,7 +61,7 @@ TABS.logging.initialize = function (callback) { // request new for (var i = 0; i < requested_properties.length; i++, requests++) { - MSP.send_message(MSP_codes[requested_properties[i]]); + MSP.send_message(MSPCodes[requested_properties[i]]); } } diff --git a/tabs/modes.js b/tabs/modes.js index ce57b792..c934f91b 100644 --- a/tabs/modes.js +++ b/tabs/modes.js @@ -12,22 +12,22 @@ TABS.modes.initialize = function (callback) { } function get_box_data() { - MSP.send_message(MSP_codes.MSP_BOX, false, false, get_box_ids); + MSP.send_message(MSPCodes.MSP_BOX, false, false, get_box_ids); } function get_box_ids() { - MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data); + MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data); } function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, load_html); + MSP.send_message(MSPCodes.MSP_RC, false, false, load_html); } function load_html() { $('#content').load("./tabs/modes.html", process_html); } - MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_box_data); + MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_box_data); function process_html() { // generate heads according to RC count @@ -87,12 +87,12 @@ TABS.modes.initialize = function (callback) { }); function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { GUI.log(chrome.i18n.getMessage('auxiliaryEepromSaved')); }); } - MSP.send_message(MSP_codes.MSP_SET_BOX, MSP.crunch(MSP_codes.MSP_SET_BOX), false, save_to_eeprom); + MSP.send_message(MSPCodes.MSP_SET_BOX, mspHelper.crunch(MSPCodes.MSP_SET_BOX), false, save_to_eeprom); }); // val = channel value @@ -116,7 +116,7 @@ TABS.modes.initialize = function (callback) { // data pulling functions used inside interval timer function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); + MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui); } function update_ui() { @@ -146,7 +146,7 @@ TABS.modes.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); diff --git a/tabs/motors.js b/tabs/motors.js index 641428ca..af5729d0 100644 --- a/tabs/motors.js +++ b/tabs/motors.js @@ -18,18 +18,18 @@ TABS.motors.initialize = function (callback) { } function get_arm_status() { - MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_config); + MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_config); } function load_config() { - MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_3d); + MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_3d); } function load_3d() { var next_callback = get_motor_data; if (semver.gte(CONFIG.apiVersion, "1.14.0")) { self.feature3DSupported = true; - MSP.send_message(MSP_codes.MSP_3D, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback); } else { next_callback(); } @@ -38,14 +38,14 @@ TABS.motors.initialize = function (callback) { function get_motor_data() { update_arm_status(); - MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); + MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_html); } function load_html() { $('#content').load("./tabs/motors.html", process_html); } - MSP.send_message(MSP_codes.MSP_MISC, false, false, get_arm_status); + MSP.send_message(MSPCodes.MSP_MISC, false, false, get_arm_status); function update_arm_status() { self.armed = bit_check(CONFIG.mode, 0); @@ -246,7 +246,7 @@ TABS.motors.initialize = function (callback) { GUI.interval_kill_all(['motor_and_status_pull']); GUI.interval_add('IMU_pull', function imu_data_pull() { - MSP.send_message(MSP_codes.MSP_RAW_IMU, false, false, update_accel_graph); + MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_accel_graph); }, rate, true); function update_accel_graph() { @@ -366,7 +366,7 @@ TABS.motors.initialize = function (callback) { buffer_delay = setTimeout(function () { buffer = buffering_set_motor.pop(); - MSP.send_message(MSP_codes.MSP_SET_MOTOR, buffer); + MSP.send_message(MSPCodes.MSP_SET_MOTOR, buffer); buffering_set_motor = []; buffer_delay = false; @@ -456,15 +456,15 @@ TABS.motors.initialize = function (callback) { function get_status() { // status needed for arming flag - MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_motor_data); + MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_motor_data); } function get_motor_data() { - MSP.send_message(MSP_codes.MSP_MOTOR, false, false, get_servo_data); + MSP.send_message(MSPCodes.MSP_MOTOR, false, false, get_servo_data); } function get_servo_data() { - MSP.send_message(MSP_codes.MSP_SERVO, false, false, update_ui); + MSP.send_message(MSPCodes.MSP_SERVO, false, false, update_ui); } var full_block_scale = MISC.maxthrottle - MISC.mincommand; diff --git a/tabs/onboard_logging.js b/tabs/onboard_logging.js index e0687d16..ef9afa91 100644 --- a/tabs/onboard_logging.js +++ b/tabs/onboard_logging.js @@ -7,7 +7,7 @@ TABS.onboard_logging = { }; TABS.onboard_logging.initialize = function (callback) { - var + var self = this, saveCancelled, eraseCancelled; @@ -17,11 +17,11 @@ TABS.onboard_logging.initialize = function (callback) { } if (CONFIGURATOR.connectionValid) { - MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, function() { - MSP.send_message(MSP_codes.MSP_DATAFLASH_SUMMARY, false, false, function() { + MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() { + MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() { if (semver.gte(CONFIG.flightControllerVersion, "1.2.0")) { - MSP.send_message(MSP_codes.MSP_SDCARD_SUMMARY, false, false, function() { - MSP.send_message(MSP_codes.MSP_BLACKBOX_CONFIG, false, false, load_html); + MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() { + MSP.send_message(MSPCodes.MSP_BLACKBOX_CONFIG, false, false, load_html); }); } else { load_html(); @@ -29,23 +29,23 @@ TABS.onboard_logging.initialize = function (callback) { }); }); } - + function gcd(a, b) { if (b == 0) return a; - + return gcd(b, a % b); } - + function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot); } function reboot() { GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.tab_switch_cleanup(function() { - MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize); + MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize); }); } @@ -60,29 +60,29 @@ TABS.onboard_logging.initialize = function (callback) { } else { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { + MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { GUI.log(chrome.i18n.getMessage('deviceReady')); TABS.onboard_logging.initialize(false, $('#content').scrollTop()); }); },1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts } } - + function load_html() { $('#content').load("./tabs/onboard_logging.html", function() { // translate to user-selected language localize(); - - var + + var dataflashPresent = DATAFLASH.totalSize > 0, blackboxSupport; - - /* + + /* * Pre-1.11.0 firmware supported DATAFLASH API (on targets with SPI flash) but not the BLACKBOX config API. - * + * * The best we can do on those targets is check the BLACKBOX feature bit to identify support for Blackbox instead. */ - if (BLACKBOX.supported || DATAFLASH.supported + if (BLACKBOX.supported || DATAFLASH.supported || semver.gte(CONFIG.flightControllerVersion, "1.5.0") && semver.lte(CONFIG.flightControllerVersion, "1.10.0") && bit_check(BF_CONFIG.features, 19)) { blackboxSupport = 'yes'; } else if (semver.gte(CONFIG.flightControllerVersion, "1.5.0") && semver.lte(CONFIG.flightControllerVersion, "1.10.0")) { @@ -90,14 +90,14 @@ TABS.onboard_logging.initialize = function (callback) { } else { blackboxSupport = 'no'; } - + $(".tab-onboard_logging") .addClass("serial-supported") .toggleClass("dataflash-supported", DATAFLASH.supported) .toggleClass("dataflash-present", dataflashPresent) .toggleClass("sdcard-supported", SDCARD.supported) .toggleClass("blackbox-config-supported", BLACKBOX.supported) - + .toggleClass("blackbox-supported", blackboxSupport == 'yes') .toggleClass("blackbox-maybe-supported", blackboxSupport == 'maybe') .toggleClass("blackbox-unsupported", blackboxSupport == 'no'); @@ -105,40 +105,40 @@ TABS.onboard_logging.initialize = function (callback) { if (dataflashPresent) { // UI hooks $('.tab-onboard_logging a.erase-flash').click(ask_to_erase_flash); - + $('.tab-onboard_logging a.erase-flash-confirm').click(flash_erase); $('.tab-onboard_logging a.erase-flash-cancel').click(flash_erase_cancel); - + $('.tab-onboard_logging a.save-flash').click(flash_save_begin); $('.tab-onboard_logging a.save-flash-cancel').click(flash_save_cancel); $('.tab-onboard_logging a.save-flash-dismiss').click(dismiss_saving_dialog); } - + if (BLACKBOX.supported) { $(".tab-onboard_logging a.save-settings").click(function() { var rate = $(".blackboxRate select").val().split('/'); - + BLACKBOX.blackboxRateNum = parseInt(rate[0], 10); BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10); BLACKBOX.blackboxDevice = parseInt($(".blackboxDevice select").val(), 10); - - MSP.sendBlackboxConfiguration(save_to_eeprom); + + mspHelper.sendBlackboxConfiguration(save_to_eeprom); }); } - + populateLoggingRates(); populateDevices(); - + update_html(); - + GUI.content_ready(callback); }); } - + function populateDevices() { var deviceSelect = $(".blackboxDevice select").empty(); - + deviceSelect.append(''); if (DATAFLASH.ready) { deviceSelect.append(''); @@ -146,17 +146,17 @@ TABS.onboard_logging.initialize = function (callback) { if (SDCARD.supported) { deviceSelect.append(''); } - + deviceSelect.val(BLACKBOX.blackboxDevice); } - + function populateLoggingRates() { var userRateGCD = gcd(BLACKBOX.blackboxRateNum, BLACKBOX.blackboxRateDenom), userRate = {num: BLACKBOX.blackboxRateNum / userRateGCD, denom: BLACKBOX.blackboxRateDenom / userRateGCD}; - + // Offer a reasonable choice of logging rates (if people want weird steps they can use CLI) - var + var loggingRates = [ {num: 1, denom: 32}, {num: 1, denom: 16}, @@ -172,58 +172,58 @@ TABS.onboard_logging.initialize = function (callback) { {num: 1, denom: 1}, ], loggingRatesSelect = $(".blackboxRate select"); - + var addedCurrentValue = false; - + for (var i = 0; i < loggingRates.length; i++) { if (!addedCurrentValue && userRate.num / userRate.denom <= loggingRates[i].num / loggingRates[i].denom) { if (userRate.num / userRate.denom < loggingRates[i].num / loggingRates[i].denom) { - loggingRatesSelect.append(''); } addedCurrentValue = true; } - - loggingRatesSelect.append(''); - + } loggingRatesSelect.val(userRate.num + '/' + userRate.denom); } - + function formatFilesizeKilobytes(kilobytes) { if (kilobytes < 1024) { return Math.round(kilobytes) + "kB"; } - - var + + var megabytes = kilobytes / 1024, gigabytes; - + if (megabytes < 900) { return megabytes.toFixed(1) + "MB"; } else { gigabytes = megabytes / 1024; - + return gigabytes.toFixed(1) + "GB"; } } - + function formatFilesizeBytes(bytes) { if (bytes < 1024) { return bytes + "B"; } return formatFilesizeKilobytes(bytes / 1024); } - + function update_bar_width(bar, value, total, label, valuesAreKilobytes) { if (value > 0) { bar.css({ width: (value / total * 100) + "%", display: 'block' }); - + $("div", bar).text((label ? label + " " : "") + (valuesAreKilobytes ? formatFilesizeKilobytes(value) : formatFilesizeBytes(value))); } else { bar.css({ @@ -231,7 +231,7 @@ TABS.onboard_logging.initialize = function (callback) { }); } } - + function update_html() { update_bar_width($(".tab-onboard_logging .dataflash-used"), DATAFLASH.usedSize, DATAFLASH.totalSize, "Used space", false); update_bar_width($(".tab-onboard_logging .dataflash-free"), DATAFLASH.totalSize - DATAFLASH.usedSize, DATAFLASH.totalSize, "Free space", false); @@ -240,12 +240,12 @@ TABS.onboard_logging.initialize = function (callback) { update_bar_width($(".tab-onboard_logging .sdcard-free"), SDCARD.freeSizeKB, SDCARD.totalSizeKB, "Free space for logs", true); $(".btn a.erase-flash, .btn a.save-flash").toggleClass("disabled", DATAFLASH.usedSize == 0); - + $(".tab-onboard_logging") .toggleClass("sdcard-error", SDCARD.state == MSP.SDCARD_STATE_FATAL) .toggleClass("sdcard-initializing", SDCARD.state == MSP.SDCARD_STATE_CARD_INIT || SDCARD.state == MSP.SDCARD_STATE_FS_INIT) .toggleClass("sdcard-ready", SDCARD.state == MSP.SDCARD_STATE_READY); - + switch (SDCARD.state) { case MSP.SDCARD_STATE_NOT_PRESENT: $(".sdcard-status").text("No card inserted"); @@ -265,85 +265,85 @@ TABS.onboard_logging.initialize = function (callback) { default: $(".sdcard-status").text("Unknown state " + SDCARD.state); } - + if (SDCARD.supported && !sdcardTimer) { // Poll for changes in SD card status sdcardTimer = setTimeout(function() { sdcardTimer = false; if (CONFIGURATOR.connectionValid) { - MSP.send_message(MSP_codes.MSP_SDCARD_SUMMARY, false, false, function() { + MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() { update_html(); }); } }, 2000); } } - + // IO related methods function zeroPad(value, width) { value = "" + value; - + while (value.length < width) { value = "0" + value; } - + return value; } - + function flash_save_cancel() { saveCancelled = true; } - + function show_saving_dialog() { $(".dataflash-saving progress").attr("value", 0); saveCancelled = false; $(".dataflash-saving").removeClass("done"); - + $(".dataflash-saving")[0].showModal(); } - + function dismiss_saving_dialog() { $(".dataflash-saving")[0].close(); } - + function mark_saving_dialog_done() { $(".dataflash-saving").addClass("done"); } - + function flash_update_summary(onDone) { - MSP.send_message(MSP_codes.MSP_DATAFLASH_SUMMARY, false, false, function() { + MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() { update_html(); - + if (onDone) { onDone(); } }); } - + function flash_save_begin() { if (GUI.connected_to) { // Begin by refreshing the occupied size in case it changed while the tab was open flash_update_summary(function() { var maxBytes = DATAFLASH.usedSize; - + prepare_file(function(fileWriter) { var nextAddress = 0; - + show_saving_dialog(); - + function onChunkRead(chunkAddress, chunkDataView) { if (chunkDataView != null) { // Did we receive any data? if (chunkDataView.byteLength > 0) { nextAddress += chunkDataView.byteLength; - + $(".dataflash-saving progress").attr("value", nextAddress / maxBytes * 100); - - var + + var blob = new Blob([chunkDataView]); - + fileWriter.onwriteend = function(e) { if (saveCancelled || nextAddress >= maxBytes) { if (saveCancelled) { @@ -352,10 +352,10 @@ TABS.onboard_logging.initialize = function (callback) { mark_saving_dialog_done(); } } else { - MSP.dataflashRead(nextAddress, onChunkRead); + mspHelper.dataflashRead(nextAddress, onChunkRead); } }; - + fileWriter.write(blob); } else { // A zero-byte block indicates end-of-file, so we're done @@ -363,37 +363,37 @@ TABS.onboard_logging.initialize = function (callback) { } } else { // There was an error with the received block (address didn't match the one we asked for), retry - MSP.dataflashRead(nextAddress, onChunkRead); + mspHelper.dataflashRead(nextAddress, onChunkRead); } } - + // Fetch the initial block - MSP.dataflashRead(nextAddress, onChunkRead); + mspHelper.dataflashRead(nextAddress, onChunkRead); }); }); } } - + function prepare_file(onComplete) { - var + var date = new Date(), - filename = 'blackbox_log_' + date.getFullYear() + '-' + zeroPad(date.getMonth() + 1, 2) + '-' - + zeroPad(date.getDate(), 2) + '_' + zeroPad(date.getHours(), 2) + zeroPad(date.getMinutes(), 2) + filename = 'blackbox_log_' + date.getFullYear() + '-' + zeroPad(date.getMonth() + 1, 2) + '-' + + zeroPad(date.getDate(), 2) + '_' + zeroPad(date.getHours(), 2) + zeroPad(date.getMinutes(), 2) + zeroPad(date.getSeconds(), 2); - - chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename, + + chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename, accepts: [{extensions: ['TXT']}]}, function(fileEntry) { var error = chrome.runtime.lastError; - + if (error) { console.error(error.message); - + if (error.message != "User cancelled") { GUI.log(chrome.i18n.getMessage('dataflashFileWriteFailed')); } return; } - + // echo/console log path specified chrome.fileSystem.getDisplayPath(fileEntry, function(path) { console.log('Dataflash dump file path: ' + path); @@ -414,12 +414,12 @@ TABS.onboard_logging.initialize = function (callback) { }); }); } - + function ask_to_erase_flash() { eraseCancelled = false; $(".dataflash-confirm-erase").removeClass('erasing'); - $(".dataflash-confirm-erase")[0].showModal(); + $(".dataflash-confirm-erase")[0].showModal(); } function poll_for_erase_completion() { @@ -433,13 +433,13 @@ TABS.onboard_logging.initialize = function (callback) { } }); } - + function flash_erase() { $(".dataflash-confirm-erase").addClass('erasing'); - - MSP.send_message(MSP_codes.MSP_DATAFLASH_ERASE, false, false, poll_for_erase_completion); + + MSP.send_message(MSPCodes.MSP_DATAFLASH_ERASE, false, false, poll_for_erase_completion); } - + function flash_erase_cancel() { eraseCancelled = true; $(".dataflash-confirm-erase")[0].close(); @@ -451,8 +451,8 @@ TABS.onboard_logging.cleanup = function (callback) { clearTimeout(sdcardTimer); sdcardTimer = false; } - + if (callback) { callback(); } -}; \ No newline at end of file +}; diff --git a/tabs/osd.js b/tabs/osd.js index 5e503744..c99c0fc3 100644 --- a/tabs/osd.js +++ b/tabs/osd.js @@ -22,12 +22,8 @@ SYM.METRE = 0xC; SYM.FEET = 0xF; SYM.GPS_SAT = 0x1F; - var FONT = FONT || {}; -//FIXME This is hack! -var MSPCodes = MSP_codes; - FONT.initData = function () { if (FONT.data) { return; diff --git a/tabs/pid_tuning.js b/tabs/pid_tuning.js index 4d87aaa0..ddf5eeef 100755 --- a/tabs/pid_tuning.js +++ b/tabs/pid_tuning.js @@ -13,21 +13,21 @@ TABS.pid_tuning.initialize = function (callback) { } function get_pid_names() { - MSP.send_message(MSP_codes.MSP_PIDNAMES, false, false, get_pid_data); + MSP.send_message(MSPCodes.MSP_PIDNAMES, false, false, get_pid_data); } function get_pid_data() { - MSP.send_message(MSP_codes.MSP_PID, false, false, get_rc_tuning_data); + MSP.send_message(MSPCodes.MSP_PID, false, false, get_rc_tuning_data); } function get_rc_tuning_data() { - MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, loadINAVPidConfig); + MSP.send_message(MSPCodes.MSP_RC_TUNING, false, false, loadINAVPidConfig); } function loadINAVPidConfig() { var next_callback = loadPidAdvanced; if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { - MSP.send_message(MSP_codes.MSP_INAV_PID, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, next_callback); } else { next_callback(); } @@ -36,7 +36,7 @@ TABS.pid_tuning.initialize = function (callback) { function loadPidAdvanced() { var next_callback = loadFilterConfig; if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { - MSP.send_message(MSP_codes.MSP_PID_ADVANCED, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_PID_ADVANCED, false, false, next_callback); } else { next_callback(); } @@ -45,7 +45,7 @@ TABS.pid_tuning.initialize = function (callback) { function loadFilterConfig() { var next_callback = load_html; if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { - MSP.send_message(MSP_codes.MSP_FILTER_CONFIG, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_FILTER_CONFIG, false, false, next_callback); } else { next_callback(); } @@ -57,7 +57,7 @@ TABS.pid_tuning.initialize = function (callback) { } // requesting MSP_STATUS manually because it contains CONFIG.profile - MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names); + MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_pid_names); var sectionClasses = [ 'ROLL', // 0 @@ -165,7 +165,7 @@ TABS.pid_tuning.initialize = function (callback) { }); $('#resetPIDs').on('click', function(){ - MSP.send_message(MSP_codes.MSP_SET_RESET_CURR_PID, false, false, false); + MSP.send_message(MSPCodes.MSP_SET_RESET_CURR_PID, false, false, false); updateActivatedTab(); }); @@ -277,17 +277,17 @@ TABS.pid_tuning.initialize = function (callback) { form_to_pid_and_rc(); function send_pids() { - MSP.send_message(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID), false, send_rc_tuning_changes); + MSP.send_message(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID), false, send_rc_tuning_changes); } function send_rc_tuning_changes() { - MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING), false, saveINAVPidConfig); + MSP.send_message(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING), false, saveINAVPidConfig); } function saveINAVPidConfig() { var next_callback = savePidAdvanced; if(semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { - MSP.send_message(MSP_codes.MSP_SET_INAV_PID, MSP.crunch(MSP_codes.MSP_SET_INAV_PID), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_INAV_PID, mspHelper.crunch(MSPCodes.MSP_SET_INAV_PID), false, next_callback); } else { next_callback(); } @@ -296,7 +296,7 @@ TABS.pid_tuning.initialize = function (callback) { function savePidAdvanced() { var next_callback = saveFilterConfig; if(semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { - MSP.send_message(MSP_codes.MSP_SET_PID_ADVANCED, MSP.crunch(MSP_codes.MSP_SET_PID_ADVANCED), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, next_callback); } else { next_callback(); } @@ -305,14 +305,14 @@ TABS.pid_tuning.initialize = function (callback) { function saveFilterConfig() { var next_callback = save_to_eeprom; if(semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { - MSP.send_message(MSP_codes.MSP_SET_FILTER_CONFIG, MSP.crunch(MSP_codes.MSP_SET_FILTER_CONFIG), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_FILTER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FILTER_CONFIG), false, next_callback); } else { next_callback(); } } function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved')); }); } @@ -322,7 +322,7 @@ TABS.pid_tuning.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); diff --git a/tabs/ports.js b/tabs/ports.js index e885bb2a..11ae95ec 100644 --- a/tabs/ports.js +++ b/tabs/ports.js @@ -84,7 +84,7 @@ TABS.ports.initialize = function (callback, scrollPosition) { load_configuration_from_fc(); function load_configuration_from_fc() { - MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler); + MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler); function on_configuration_loaded_handler() { $('#content').load("./tabs/ports.html", on_tab_loaded_handler); @@ -221,7 +221,7 @@ TABS.ports.initialize = function (callback, scrollPosition) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); @@ -258,17 +258,17 @@ TABS.ports.initialize = function (callback, scrollPosition) { SERIAL_CONFIG.ports.push(serialPort); }); - MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom); + MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom); function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, on_saved_handler); + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, on_saved_handler); } function on_saved_handler() { GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.tab_switch_cleanup(function() { - MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, on_reboot_success_handler); + MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, on_reboot_success_handler); }); } @@ -282,7 +282,7 @@ TABS.ports.initialize = function (callback, scrollPosition) { },2500); } else { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { - MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { + MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { GUI.log(chrome.i18n.getMessage('deviceReady')); TABS.ports.initialize(false, $('#content').scrollTop()); }); diff --git a/tabs/receiver.js b/tabs/receiver.js index e5b5cd6b..a605f818 100644 --- a/tabs/receiver.js +++ b/tabs/receiver.js @@ -13,26 +13,26 @@ TABS.receiver.initialize = function (callback) { } function get_misc_data() { - MSP.send_message(MSP_codes.MSP_MISC, false, false, get_rc_data); + MSP.send_message(MSPCodes.MSP_MISC, false, false, get_rc_data); } function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, get_rc_map); + MSP.send_message(MSPCodes.MSP_RC, false, false, get_rc_map); } function get_rc_map() { - MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_config); + MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_config); } // Fetch features so we can check if RX_MSP is enabled: function load_config() { - MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_rc_configs); + MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_rc_configs); } - + function load_rc_configs() { var next_callback = load_html; if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - MSP.send_message(MSP_codes.MSP_RC_DEADBAND, false, false, next_callback); + MSP.send_message(MSPCodes.MSP_RC_DEADBAND, false, false, next_callback); } else { next_callback(); } @@ -42,7 +42,7 @@ TABS.receiver.initialize = function (callback) { $('#content').load("./tabs/receiver.html", process_html); } - MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, get_misc_data); + MSP.send_message(MSPCodes.MSP_RC_TUNING, false, false, get_misc_data); function process_html() { // translate to user-selected language @@ -283,7 +283,7 @@ TABS.receiver.initialize = function (callback) { }).trigger('input'); $('a.refresh').click(function () { - MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, function () { + MSP.send_message(MSPCodes.MSP_RC_TUNING, false, false, function () { GUI.log(chrome.i18n.getMessage('receiverDataRefreshed')); // fill in data from RC_tuning @@ -312,7 +312,7 @@ TABS.receiver.initialize = function (callback) { RC_deadband.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val()); RC_deadband.deadband = parseInt($('.deadband input[name="deadband"]').val()); } - + // catch rc map var RC_MAP_Letters = ['A', 'E', 'R', 'T', '1', '2', '3', '4']; var strBuffer = $('input[name="rcmap"]').val().split(''); @@ -325,29 +325,29 @@ TABS.receiver.initialize = function (callback) { MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val()); function save_rc_map() { - MSP.send_message(MSP_codes.MSP_SET_RX_MAP, MSP.crunch(MSP_codes.MSP_SET_RX_MAP), false, save_misc); + MSP.send_message(MSPCodes.MSP_SET_RX_MAP, mspHelper.crunch(MSPCodes.MSP_SET_RX_MAP), false, save_misc); } function save_misc() { - MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_rc_configs); + MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_rc_configs); } - + function save_rc_configs() { var next_callback = save_to_eeprom; if (semver.gte(CONFIG.apiVersion, "1.15.0")) { - MSP.send_message(MSP_codes.MSP_SET_RC_DEADBAND, MSP.crunch(MSP_codes.MSP_SET_RC_DEADBAND), false, next_callback); + MSP.send_message(MSPCodes.MSP_SET_RC_DEADBAND, mspHelper.crunch(MSPCodes.MSP_SET_RC_DEADBAND), false, next_callback); } else { next_callback(); } } function save_to_eeprom() { - MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { + MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () { GUI.log(chrome.i18n.getMessage('receiverEepromSaved')); }); } - MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING), false, save_rc_map); + MSP.send_message(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING), false, save_rc_map); }); $("a.sticks").click(function() { @@ -367,7 +367,7 @@ TABS.receiver.initialize = function (callback) { // Give the window a callback it can use to send the channels (otherwise it can't see those objects) createdWindow.contentWindow.setRawRx = function(channels) { if (CONFIGURATOR.connectionValid && GUI.active_tab != 'cli') { - MSP.setRawRx(channels); + mspHelper.setRawRx(channels); return true; } else { return false; @@ -386,7 +386,7 @@ TABS.receiver.initialize = function (callback) { chrome.storage.local.set({'rx_refresh_rate': plot_update_rate}); function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui); + MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui); } // setup plot @@ -485,7 +485,7 @@ TABS.receiver.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); diff --git a/tabs/sensors.js b/tabs/sensors.js index 389dbc43..65c69bbb 100644 --- a/tabs/sensors.js +++ b/tabs/sensors.js @@ -361,25 +361,25 @@ TABS.sensors.initialize = function (callback) { // data pulling timers if (checkboxes[0] || checkboxes[1] || checkboxes[2]) { GUI.interval_add('IMU_pull', function imu_data_pull() { - MSP.send_message(MSP_codes.MSP_RAW_IMU, false, false, update_imu_graphs); + MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_imu_graphs); }, fastest, true); } if (checkboxes[3]) { GUI.interval_add('altitude_pull', function altitude_data_pull() { - MSP.send_message(MSP_codes.MSP_ALTITUDE, false, false, update_altitude_graph); + MSP.send_message(MSPCodes.MSP_ALTITUDE, false, false, update_altitude_graph); }, rates.baro, true); } if (checkboxes[4]) { GUI.interval_add('sonar_pull', function sonar_data_pull() { - MSP.send_message(MSP_codes.MSP_SONAR, false, false, update_sonar_graphs); + MSP.send_message(MSPCodes.MSP_SONAR, false, false, update_sonar_graphs); }, rates.sonar, true); } if (checkboxes[5]) { GUI.interval_add('debug_pull', function debug_data_pull() { - MSP.send_message(MSP_codes.MSP_DEBUG, false, false, update_debug_graphs); + MSP.send_message(MSPCodes.MSP_DEBUG, false, false, update_debug_graphs); }, rates.debug, true); } @@ -445,7 +445,7 @@ TABS.sensors.initialize = function (callback) { // status data pulled via separate timer with static speed GUI.interval_add('status_pull', function status_pull() { - MSP.send_message(MSP_codes.MSP_STATUS); + MSP.send_message(MSPCodes.MSP_STATUS); }, 250, true); GUI.content_ready(callback); diff --git a/tabs/servos.js b/tabs/servos.js index 1d2ad5e2..6a73c186 100755 --- a/tabs/servos.js +++ b/tabs/servos.js @@ -10,47 +10,47 @@ TABS.servos.initialize = function (callback) { } function get_servo_configurations() { - MSP.send_message(MSP_codes.MSP_SERVO_CONFIGURATIONS, false, false, get_servo_mix_rules); + MSP.send_message(MSPCodes.MSP_SERVO_CONFIGURATIONS, false, false, get_servo_mix_rules); } function get_servo_mix_rules() { - MSP.send_message(MSP_codes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding); + MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding); } function get_channel_forwarding() { var nextFunction = get_rc_data; - + if (semver.lt(CONFIG.apiVersion, "1.12.0")) { - MSP.send_message(MSP_codes.MSP_CHANNEL_FORWARDING, false, false, nextFunction); - } else { + MSP.send_message(MSPCodes.MSP_CHANNEL_FORWARDING, false, false, nextFunction); + } else { nextFunction(); } } function get_rc_data() { - MSP.send_message(MSP_codes.MSP_RC, false, false, get_boxnames_data); + MSP.send_message(MSPCodes.MSP_RC, false, false, get_boxnames_data); } function get_boxnames_data() { - MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, load_html); + MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, load_html); } function load_html() { $('#content').load("./tabs/servos.html", process_html); } - - MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_servo_configurations); - + + MSP.send_message(MSPCodes.MSP_IDENT, false, false, get_servo_configurations); + function update_ui() { - + if (semver.lt(CONFIG.apiVersion, "1.12.0") || SERVO_CONFIG.length == 0) { - + $(".tab-servos").removeClass("supported"); return; } - + $(".tab-servos").addClass("supported"); - + var servoCheckbox = ''; var servoHeader = ''; for (var i = 0; i < RC.active_channels-4; i++) { @@ -69,9 +69,9 @@ TABS.servos.initialize = function (callback) { $('div.tab-servos table.fields tr.main').append(servoHeader); function process_servos(name, alternate, obj) { - + $('div.supported_wrapper').show(); - + $('div.tab-servos table.fields').append('\