1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-13 19:40:22 +03:00

MSP refactoring

This commit is contained in:
Pawel Spychalski (DzikuVx) 2016-11-23 17:10:33 +01:00 committed by Pawel Spychalski (DzikuVx)
parent 3311093cb1
commit 18a00dedf8
26 changed files with 2431 additions and 2426 deletions

View file

@ -13,35 +13,35 @@ function configuration_backup(callback) {
}; };
var profileSpecificData = [ var profileSpecificData = [
MSP_codes.MSP_PID, MSPCodes.MSP_PID,
MSP_codes.MSP_RC_TUNING, MSPCodes.MSP_RC_TUNING,
MSP_codes.MSP_ACC_TRIM, MSPCodes.MSP_ACC_TRIM,
MSP_codes.MSP_SERVO_CONFIGURATIONS, MSPCodes.MSP_SERVO_CONFIGURATIONS,
MSP_codes.MSP_MODE_RANGES, MSPCodes.MSP_MODE_RANGES,
MSP_codes.MSP_ADJUSTMENT_RANGES MSPCodes.MSP_ADJUSTMENT_RANGES
]; ];
function update_profile_specific_data_list() { function update_profile_specific_data_list() {
if (semver.lt(CONFIG.apiVersion, "1.12.0")) { if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
profileSpecificData.push(MSP_codes.MSP_CHANNEL_FORWARDING); profileSpecificData.push(MSPCodes.MSP_CHANNEL_FORWARDING);
} else { } else {
profileSpecificData.push(MSP_codes.MSP_SERVO_MIX_RULES); profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES);
} }
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { 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(); 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; activeProfile = CONFIG.profile;
select_profile(); select_profile();
}); });
function select_profile() { function select_profile() {
if (activeProfile > 0) { 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 { } else {
fetch_specific_data(); fetch_specific_data();
} }
@ -76,11 +76,11 @@ function configuration_backup(callback) {
codeKey = 0; codeKey = 0;
fetchingProfile++; 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 { } 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 = [ var uniqueData = [
MSP_codes.MSP_MISC, MSPCodes.MSP_MISC,
MSP_codes.MSP_RX_MAP, MSPCodes.MSP_RX_MAP,
MSP_codes.MSP_BF_CONFIG, MSPCodes.MSP_BF_CONFIG,
MSP_codes.MSP_CF_SERIAL_CONFIG, MSPCodes.MSP_CF_SERIAL_CONFIG,
MSP_codes.MSP_LED_STRIP_CONFIG, MSPCodes.MSP_LED_STRIP_CONFIG,
MSP_codes.MSP_LED_COLORS MSPCodes.MSP_LED_COLORS
]; ];
function update_unique_data_list() { function update_unique_data_list() {
if (semver.gte(CONFIG.apiVersion, "1.8.0")) { if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
uniqueData.push(MSP_codes.MSP_LOOP_TIME); uniqueData.push(MSPCodes.MSP_LOOP_TIME);
uniqueData.push(MSP_codes.MSP_ARMING_CONFIG); uniqueData.push(MSPCodes.MSP_ARMING_CONFIG);
} }
if (semver.gte(CONFIG.apiVersion, "1.14.0")) { 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")) { if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
uniqueData.push(MSP_codes.MSP_SENSOR_ALIGNMENT); uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT);
uniqueData.push(MSP_codes.MSP_RX_CONFIG); uniqueData.push(MSPCodes.MSP_RX_CONFIG);
uniqueData.push(MSP_codes.MSP_FAILSAFE_CONFIG); uniqueData.push(MSPCodes.MSP_FAILSAFE_CONFIG);
uniqueData.push(MSP_codes.MSP_RXFAIL_CONFIG); uniqueData.push(MSPCodes.MSP_RXFAIL_CONFIG);
} }
if (semver.gte(CONFIG.apiVersion, "1.19.0")) { 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')) { if (!compareVersions(migratedVersion, '1.2.0')) {
// LED_COLORS & LED_MODE_COLORS support was added. // LED_COLORS & LED_MODE_COLORS support was added.
if (!configuration.LED_COLORS) { if (!configuration.LED_COLORS) {
configuration.LED_COLORS = []; configuration.LED_COLORS = [];
@ -620,23 +620,23 @@ function configuration_restore(callback) {
profilesN = 3; profilesN = 3;
var profileSpecificData = [ var profileSpecificData = [
MSP_codes.MSP_SET_PID, MSPCodes.MSP_SET_PID,
MSP_codes.MSP_SET_RC_TUNING, MSPCodes.MSP_SET_RC_TUNING,
MSP_codes.MSP_SET_ACC_TRIM MSPCodes.MSP_SET_ACC_TRIM
]; ];
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { 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; activeProfile = CONFIG.profile;
select_profile(); select_profile();
}); });
function select_profile() { function select_profile() {
if (activeProfile > 0) { 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 { } else {
upload_specific_data(); upload_specific_data();
} }
@ -659,7 +659,7 @@ function configuration_restore(callback) {
} }
function upload_using_specific_commands() { 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++; codeKey++;
if (codeKey < profileSpecificData.length) { if (codeKey < profileSpecificData.length) {
@ -671,12 +671,12 @@ function configuration_restore(callback) {
if (savingProfile < profilesN) { if (savingProfile < profilesN) {
load_objects(savingProfile); load_objects(savingProfile);
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { MSP.send_message(MSPCodes.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_SELECT_SETTING, [savingProfile], false, upload_using_specific_commands);
}); });
} else { } else {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () { MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [activeProfile], false, upload_unique_data); 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() { function upload_servo_mix_rules() {
MSP.sendServoMixRules(upload_servo_configuration); mspHelper.sendServoMixRules(upload_servo_configuration);
} }
function upload_servo_configuration() { function upload_servo_configuration() {
MSP.sendServoConfigurations(upload_mode_ranges); mspHelper.sendServoConfigurations(upload_mode_ranges);
} }
function upload_mode_ranges() { function upload_mode_ranges() {
MSP.sendModeRanges(upload_adjustment_ranges); mspHelper.sendModeRanges(upload_adjustment_ranges);
} }
function upload_adjustment_ranges() { function upload_adjustment_ranges() {
MSP.sendAdjustmentRanges(upload_using_specific_commands); mspHelper.sendAdjustmentRanges(upload_using_specific_commands);
} }
// start uploading // start uploading
load_objects(0); load_objects(0);
@ -707,24 +707,24 @@ function configuration_restore(callback) {
var codeKey = 0; var codeKey = 0;
var uniqueData = [ var uniqueData = [
MSP_codes.MSP_SET_MISC, MSPCodes.MSP_SET_MISC,
MSP_codes.MSP_SET_RX_MAP, MSPCodes.MSP_SET_RX_MAP,
MSP_codes.MSP_SET_BF_CONFIG, MSPCodes.MSP_SET_BF_CONFIG,
MSP_codes.MSP_SET_CF_SERIAL_CONFIG MSPCodes.MSP_SET_CF_SERIAL_CONFIG
]; ];
function update_unique_data_list() { function update_unique_data_list() {
if (semver.gte(CONFIG.apiVersion, "1.8.0")) { if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
uniqueData.push(MSP_codes.MSP_SET_LOOP_TIME); uniqueData.push(MSPCodes.MSP_SET_LOOP_TIME);
uniqueData.push(MSP_codes.MSP_SET_ARMING_CONFIG); uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG);
} }
if (semver.gte(CONFIG.apiVersion, "1.14.0")) { 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")) { if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
uniqueData.push(MSP_codes.MSP_SET_SENSOR_ALIGNMENT); uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT);
uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG); uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG);
uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG); uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG);
} }
} }
@ -747,7 +747,7 @@ function configuration_restore(callback) {
function send_unique_data_item() { function send_unique_data_item() {
if (codeKey < uniqueData.length) { 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++; codeKey++;
send_unique_data_item(); send_unique_data_item();
}); });
@ -765,37 +765,37 @@ function configuration_restore(callback) {
} }
function send_led_strip_config() { function send_led_strip_config() {
MSP.sendLedStripConfig(send_led_strip_colors); mspHelper.sendLedStripConfig(send_led_strip_colors);
} }
function 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() { function send_led_strip_mode_colors() {
if (semver.gte(CONFIG.apiVersion, "1.19.0")) if (semver.gte(CONFIG.apiVersion, "1.19.0"))
MSP.sendLedStripModeColors(send_rxfail_config); mspHelper.sendLedStripModeColors(send_rxfail_config);
else else
send_rxfail_config(); send_rxfail_config();
} }
function send_rxfail_config() { function send_rxfail_config() {
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
MSP.sendRxFailConfig(save_to_eeprom); mspHelper.sendRxFailConfig(save_to_eeprom);
} else { } else {
save_to_eeprom(); save_to_eeprom();
} }
} }
function 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() { function reboot() {
GUI.log(chrome.i18n.getMessage('eeprom_saved_ok')); GUI.log(chrome.i18n.getMessage('eeprom_saved_ok'));
GUI.tab_switch_cleanup(function() { 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.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { 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')); GUI.log(chrome.i18n.getMessage('deviceReady'));
if (callback) callback(); if (callback) callback();

1863
js/msp.js

File diff suppressed because it is too large Load diff

128
js/msp/MSPCodes.js Normal file
View file

@ -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
};

1739
js/msp/MSPHelper.js Normal file

File diff suppressed because it is too large Load diff

View file

@ -187,31 +187,31 @@ function onOpen(openInfo) {
FC.resetState(); FC.resetState();
// request configuration data // 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])); GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.apiVersionAccepted)) { 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); googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion);
GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion])); GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
if (CONFIG.flightControllerIdentifier == 'INAV') { 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); googleAnalytics.sendEvent('Firmware', 'Using', CONFIG.buildInfo);
GUI.log(chrome.i18n.getMessage('buildInfoReceived', [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); googleAnalytics.sendEvent('Board', 'Using', CONFIG.boardIdentifier + ',' + CONFIG.boardVersion);
GUI.log(chrome.i18n.getMessage('boardInfoReceived', [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)])); GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
// continue as usually // continue as usually
@ -269,12 +269,12 @@ function onConnect() {
$('#tabs ul.mode-connected').show(); $('#tabs ul.mode-connected').show();
if (semver.gte(CONFIG.flightControllerVersion, "1.2.0")) { 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 { } 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(); $('#sensor-status').show();
$('#portsinput').hide(); $('#portsinput').hide();
@ -451,12 +451,12 @@ function update_live_status() {
}); });
if (GUI.active_tab != 'cli') { 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")) 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 else
MSP.send_message(MSP_codes.MSP_STATUS, false, false); MSP.send_message(MSPCodes.MSP_STATUS, false, false);
MSP.send_message(MSP_codes.MSP_ANALOG, false, false); MSP.send_message(MSPCodes.MSP_ANALOG, false, false);
} }
var active = ((Date.now() - MSP.analog_last_received_timestamp) < 300); var active = ((Date.now() - MSP.analog_last_received_timestamp) < 300);

View file

@ -48,6 +48,8 @@
<script type="text/javascript" src="./js/libraries/jquery.ba-throttle-debounce.min.js"></script> <script type="text/javascript" src="./js/libraries/jquery.ba-throttle-debounce.min.js"></script>
<script type="text/javascript" src="./js/libraries/inflection.min.js"></script> <script type="text/javascript" src="./js/libraries/inflection.min.js"></script>
<script type="text/javascript" src="./js/injected_methods.js"></script> <script type="text/javascript" src="./js/injected_methods.js"></script>
<script type="text/javascript" src="./js/msp/MSPCodes.js"></script>
<script type="text/javascript" src="./js/msp/MSPHelper.js"></script>
<script type="text/javascript" src="./js/port_handler.js"></script> <script type="text/javascript" src="./js/port_handler.js"></script>
<script type="text/javascript" src="./js/port_usage.js"></script> <script type="text/javascript" src="./js/port_usage.js"></script>
<script type="text/javascript" src="./js/serial.js"></script> <script type="text/javascript" src="./js/serial.js"></script>

View file

@ -354,7 +354,7 @@ $(document).ready(function () {
profile_e.change(function () { profile_e.change(function () {
var profile = parseInt($(this).val()); 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])); GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1]));
updateActivatedTab(); updateActivatedTab();
}); });

View file

@ -7,44 +7,44 @@ TABS.adjustments.initialize = function (callback) {
GUI.active_tab_ref = this; GUI.active_tab_ref = this;
GUI.active_tab = 'adjustments'; GUI.active_tab = 'adjustments';
googleAnalytics.sendAppView('Adjustments'); googleAnalytics.sendAppView('Adjustments');
function get_adjustment_ranges() { 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() { 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() { 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() { function load_html() {
$('#content').load("./tabs/adjustments.html", process_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) { function addAdjustment(adjustmentIndex, adjustmentRange, auxChannelCount) {
var template = $('#tab-adjustments-templates').find('.adjustments .adjustment'); var template = $('#tab-adjustments-templates').find('.adjustments .adjustment');
var newAdjustment = template.clone(); var newAdjustment = template.clone();
$(newAdjustment).attr('id', 'adjustment-' + adjustmentIndex); $(newAdjustment).attr('id', 'adjustment-' + adjustmentIndex);
$(newAdjustment).data('index', adjustmentIndex); $(newAdjustment).data('index', adjustmentIndex);
// //
// update selected slot // update selected slot
// //
var channelList = $(newAdjustment).find('.adjustmentSlot .slot'); var channelList = $(newAdjustment).find('.adjustmentSlot .slot');
channelList.val(adjustmentRange.slotIndex); channelList.val(adjustmentRange.slotIndex);
// //
// populate source channel select box // populate source channel select box
// //
var channelList = $(newAdjustment).find('.channelInfo .channel'); var channelList = $(newAdjustment).find('.channelInfo .channel');
var channelOptionTemplate = $(channelList).find('option'); var channelOptionTemplate = $(channelList).find('option');
channelOptionTemplate.remove(); channelOptionTemplate.remove();
@ -59,13 +59,13 @@ TABS.adjustments.initialize = function (callback) {
// //
// update selected function // update selected function
// //
var functionList = $(newAdjustment).find('.functionSelection .function'); var functionList = $(newAdjustment).find('.functionSelection .function');
// update list of selected functions // update list of selected functions
var functionListOptions = $(functionList).find('option'); var functionListOptions = $(functionList).find('option');
var availableFunctionCount = 13; var availableFunctionCount = 13;
if (semver.gte(CONFIG.flightControllerVersion, '1.8.0')) { if (semver.gte(CONFIG.flightControllerVersion, '1.8.0')) {
availableFunctionCount += 2; // pitch and roll rate availableFunctionCount += 2; // pitch and roll rate
if (semver.gte(CONFIG.flightControllerVersion, '1.9.0')) { if (semver.gte(CONFIG.flightControllerVersion, '1.9.0')) {
@ -75,18 +75,18 @@ TABS.adjustments.initialize = function (callback) {
} }
} }
} }
var functionListOptions = $(functionListOptions).slice(0,availableFunctionCount); var functionListOptions = $(functionListOptions).slice(0,availableFunctionCount);
functionList.empty().append(functionListOptions); functionList.empty().append(functionListOptions);
functionList.val(adjustmentRange.adjustmentFunction); functionList.val(adjustmentRange.adjustmentFunction);
// //
// populate function channel select box // populate function channel select box
// //
var channelList = $(newAdjustment).find('.functionSwitchChannel .channel'); var channelList = $(newAdjustment).find('.functionSwitchChannel .channel');
var channelOptionTemplate = $(channelList).find('option'); var channelOptionTemplate = $(channelList).find('option');
channelOptionTemplate.remove(); channelOptionTemplate.remove();
@ -101,12 +101,12 @@ TABS.adjustments.initialize = function (callback) {
// //
// configure range // configure range
// //
var channel_range = { var channel_range = {
'min': [ 900 ], 'min': [ 900 ],
'max': [ 2100 ] 'max': [ 2100 ]
}; };
var defaultRangeValues = [1300, 1700]; var defaultRangeValues = [1300, 1700];
var rangeValues = defaultRangeValues; var rangeValues = defaultRangeValues;
if (adjustmentRange.range != undefined) { if (adjustmentRange.range != undefined) {
@ -137,16 +137,16 @@ TABS.adjustments.initialize = function (callback) {
density: 4, density: 4,
stepped: true stepped: true
}); });
// //
// add the enable/disable behavior // add the enable/disable behavior
// //
var enableElement = $(newAdjustment).find('.enable'); var enableElement = $(newAdjustment).find('.enable');
$(enableElement).data('adjustmentElement', newAdjustment); $(enableElement).data('adjustmentElement', newAdjustment);
$(enableElement).change(function() { $(enableElement).change(function() {
var adjustmentElement = $(this).data('adjustmentElement'); var adjustmentElement = $(this).data('adjustmentElement');
if ($(this).prop("checked")) { if ($(this).prop("checked")) {
$(adjustmentElement).find(':input').prop("disabled", false); $(adjustmentElement).find(':input').prop("disabled", false);
$(adjustmentElement).find('.channel-slider').removeAttr("disabled"); $(adjustmentElement).find('.channel-slider').removeAttr("disabled");
var rangeElement = $(adjustmentElement).find('.range .channel-slider'); var rangeElement = $(adjustmentElement).find('.range .channel-slider');
@ -163,10 +163,10 @@ TABS.adjustments.initialize = function (callback) {
// keep this element enabled // keep this element enabled
$(this).prop("disabled", false); $(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(); $(enableElement).prop("checked", isEnabled).change();
return newAdjustment; return newAdjustment;
} }
@ -174,12 +174,12 @@ TABS.adjustments.initialize = function (callback) {
var auxChannelCount = RC.active_channels - 4; 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++) { for (var adjustmentIndex = 0; adjustmentIndex < ADJUSTMENT_RANGES.length; adjustmentIndex++) {
var newAdjustment = addAdjustment(adjustmentIndex, ADJUSTMENT_RANGES[adjustmentIndex], auxChannelCount); var newAdjustment = addAdjustment(adjustmentIndex, ADJUSTMENT_RANGES[adjustmentIndex], auxChannelCount);
modeTableBodyElement.append(newAdjustment); modeTableBodyElement.append(newAdjustment);
} }
// translate to user-selected language // translate to user-selected language
localize(); localize();
@ -188,9 +188,9 @@ TABS.adjustments.initialize = function (callback) {
// update internal data structures based on current UI elements // update internal data structures based on current UI elements
var requiredAdjustmentRangeCount = ADJUSTMENT_RANGES.length; var requiredAdjustmentRangeCount = ADJUSTMENT_RANGES.length;
ADJUSTMENT_RANGES = []; ADJUSTMENT_RANGES = [];
var defaultAdjustmentRange = { var defaultAdjustmentRange = {
slotIndex: 0, slotIndex: 0,
auxChannelIndex: 0, auxChannelIndex: 0,
@ -204,7 +204,7 @@ TABS.adjustments.initialize = function (callback) {
$('.tab-adjustments .adjustments .adjustment').each(function () { $('.tab-adjustments .adjustments .adjustment').each(function () {
var adjustmentElement = $(this); var adjustmentElement = $(this);
if ($(adjustmentElement).find('.enable').prop("checked")) { if ($(adjustmentElement).find('.enable').prop("checked")) {
var rangeValues = $(this).find('.range .channel-slider').val(); var rangeValues = $(this).find('.range .channel-slider').val();
var adjustmentRange = { var adjustmentRange = {
@ -222,18 +222,18 @@ TABS.adjustments.initialize = function (callback) {
ADJUSTMENT_RANGES.push(defaultAdjustmentRange); ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
} }
}); });
for (var adjustmentRangeIndex = ADJUSTMENT_RANGES.length; adjustmentRangeIndex < requiredAdjustmentRangeCount; adjustmentRangeIndex++) { for (var adjustmentRangeIndex = ADJUSTMENT_RANGES.length; adjustmentRangeIndex < requiredAdjustmentRangeCount; adjustmentRangeIndex++) {
ADJUSTMENT_RANGES.push(defaultAdjustmentRange); ADJUSTMENT_RANGES.push(defaultAdjustmentRange);
} }
// //
// send data to FC // send data to FC
// //
MSP.sendAdjustmentRanges(save_to_eeprom); mspHelper.sendAdjustmentRanges(save_to_eeprom);
function 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')); GUI.log(chrome.i18n.getMessage('adjustmentsEepromSaved'));
}); });
} }
@ -247,20 +247,20 @@ TABS.adjustments.initialize = function (callback) {
channelPosition = 2100; channelPosition = 2100;
} }
var percentage = (channelPosition - 900) / (2100-900) * 100; var percentage = (channelPosition - 900) / (2100-900) * 100;
$('.adjustments .adjustment').each( function () { $('.adjustments .adjustment').each( function () {
var auxChannelCandidateIndex = $(this).find('.channel').val(); var auxChannelCandidateIndex = $(this).find('.channel').val();
if (auxChannelCandidateIndex != auxChannelIndex) { if (auxChannelCandidateIndex != auxChannelIndex) {
return; return;
} }
$(this).find('.range .marker').css('left', percentage + '%'); $(this).find('.range .marker').css('left', percentage + '%');
}); });
} }
// data pulling functions used inside interval timer // data pulling functions used inside interval timer
function get_rc_data() { 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() { function update_ui() {
@ -268,7 +268,7 @@ TABS.adjustments.initialize = function (callback) {
for (var auxChannelIndex = 0; auxChannelIndex < auxChannelCount; auxChannelIndex++) { for (var auxChannelIndex = 0; auxChannelIndex < auxChannelCount; auxChannelIndex++) {
update_marker(auxChannelIndex, RC.channels[auxChannelIndex + 4]); update_marker(auxChannelIndex, RC.channels[auxChannelIndex + 4]);
} }
} }
// update ui instantly on first load // update ui instantly on first load
@ -279,7 +279,7 @@ TABS.adjustments.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function () { GUI.interval_add('status_pull', function () {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);
@ -288,4 +288,4 @@ TABS.adjustments.initialize = function (callback) {
TABS.adjustments.cleanup = function (callback) { TABS.adjustments.cleanup = function (callback) {
if (callback) callback(); if (callback) callback();
}; };

View file

@ -8,22 +8,22 @@ TABS.auxiliary.initialize = function (callback) {
googleAnalytics.sendAppView('Auxiliary'); googleAnalytics.sendAppView('Auxiliary');
function 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() { 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() { 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() { function load_html() {
$('#content').load("./tabs/auxiliary.html", process_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) { function createMode(modeIndex, modeId) {
var modeTemplate = $('#tab-auxiliary-templates .mode'); var modeTemplate = $('#tab-auxiliary-templates .mode');
@ -216,7 +216,7 @@ TABS.auxiliary.initialize = function (callback) {
// //
// send data to FC // send data to FC
// //
MSP.sendModeRanges(save_to_eeprom); mspHelper.sendModeRanges(save_to_eeprom);
/* /*
* Send some data to analytics * Send some data to analytics
@ -227,7 +227,7 @@ TABS.auxiliary.initialize = function (callback) {
} }
function 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('auxiliaryEepromSaved')); GUI.log(chrome.i18n.getMessage('auxiliaryEepromSaved'));
}); });
} }
@ -257,7 +257,7 @@ TABS.auxiliary.initialize = function (callback) {
// data pulling functions used inside interval timer // data pulling functions used inside interval timer
function get_rc_data() { 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() { function update_ui() {
@ -292,7 +292,7 @@ TABS.auxiliary.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function () { GUI.interval_add('status_pull', function () {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -172,7 +172,7 @@ TABS.cli.read = function (readInfo) {
} else { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { 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')); GUI.log(chrome.i18n.getMessage('deviceReady'));
if (!GUI.tab_switch_in_progress) { if (!GUI.tab_switch_in_progress) {
$('#tabs ul.mode-connected .tab_setup a').click(); $('#tabs ul.mode-connected .tab_setup a').click();

View file

@ -11,30 +11,30 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
function load_config() { 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() { function load_serial_config() {
var next_callback = load_rc_map; var next_callback = load_rc_map;
if (semver.lt(CONFIG.apiVersion, "1.6.0")) { 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 { } else {
next_callback(); next_callback();
} }
} }
function load_rc_map() { 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() { 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() { function load_arming_config() {
var next_callback = load_loop_time; var next_callback = load_loop_time;
if (semver.gte(CONFIG.apiVersion, "1.8.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -43,7 +43,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function load_loop_time() { function load_loop_time() {
var next_callback = load_rx_config; var next_callback = load_rx_config;
if (semver.gte(CONFIG.apiVersion, "1.8.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -52,7 +52,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function load_rx_config() { function load_rx_config() {
var next_callback = load_3d; var next_callback = load_3d;
if (semver.gte(CONFIG.apiVersion, "1.21.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -61,7 +61,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function load_3d() { function load_3d() {
var next_callback = load_sensor_alignment; var next_callback = load_sensor_alignment;
if (semver.gte(CONFIG.apiVersion, "1.14.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -70,7 +70,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function load_sensor_alignment() { function load_sensor_alignment() {
var next_callback = loadAdvancedConfig; var next_callback = loadAdvancedConfig;
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -79,7 +79,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function loadAdvancedConfig() { function loadAdvancedConfig() {
var next_callback = loadINAVPidConfig; var next_callback = loadINAVPidConfig;
if (semver.gte(CONFIG.flightControllerVersion, "1.3.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -88,7 +88,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function loadINAVPidConfig() { function loadINAVPidConfig() {
var next_callback = load_html; var next_callback = load_html;
if (semver.gt(CONFIG.flightControllerVersion, "1.3.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -96,7 +96,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
//Update Analog/Battery Data //Update Analog/Battery Data
function load_analog() { 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="batteryvoltage"]').val([ANALOG.voltage.toFixed(1)]);
$('input[name="batterycurrent"]').val([ANALOG.amperage.toFixed(2)]); $('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); $('#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() { function process_html() {
@ -708,20 +708,20 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function save_serial_config() { function save_serial_config() {
if (semver.lt(CONFIG.apiVersion, "1.6.0")) { 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 { } else {
save_misc(); save_misc();
} }
} }
function 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() { function save_3d() {
var next_callback = save_sensor_alignment; var next_callback = save_sensor_alignment;
if(semver.gte(CONFIG.apiVersion, "1.14.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -730,29 +730,29 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function save_sensor_alignment() { function save_sensor_alignment() {
var next_callback = save_acc_trim; var next_callback = save_acc_trim;
if(semver.gte(CONFIG.apiVersion, "1.15.0")) { 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 { } else {
next_callback(); next_callback();
} }
} }
function save_acc_trim() { 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); , semver.gte(CONFIG.apiVersion, "1.8.0") ? save_arming_config : save_to_eeprom);
} }
function save_arming_config() { 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() { 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() { function save_rx_config() {
var next_callback = saveAdvancedConfig; var next_callback = saveAdvancedConfig;
if(semver.gte(CONFIG.apiVersion, "1.21.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -761,7 +761,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function saveAdvancedConfig() { function saveAdvancedConfig() {
var next_callback = saveINAVPidConfig; var next_callback = saveINAVPidConfig;
if(semver.gte(CONFIG.flightControllerVersion, "1.3.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -770,21 +770,21 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function saveINAVPidConfig() { function saveINAVPidConfig() {
var next_callback = save_to_eeprom; var next_callback = save_to_eeprom;
if(semver.gt(CONFIG.flightControllerVersion, "1.3.0")) { 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 { } else {
next_callback(); next_callback();
} }
} }
function 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() { function reboot() {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function() { 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 { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { 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')); GUI.log(chrome.i18n.getMessage('deviceReady'));
TABS.configuration.initialize(false, $('#content').scrollTop()); 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 // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.interval_add('config_load_analog', load_analog, 250, true); // 4 fps GUI.interval_add('config_load_analog', load_analog, 250, true); // 4 fps
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -11,40 +11,40 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
function load_rx_config() { 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() { 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() { 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() { 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() { 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() { 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() { 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 // BEGIN Support for pre API version 1.15.0
function load_config() { 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() { 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 // END (Support for pre API version 1.15.0
@ -58,9 +58,9 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
//apiVersionGte1_15_0 = false; //apiVersionGte1_15_0 = false;
if(apiVersionGte1_15_0) { 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 { } 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() { function process_html() {
@ -317,32 +317,32 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
function save_failssafe_config() { 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() { function save_rxfail_config() {
MSP.sendRxFailConfig(save_bf_config); mspHelper.sendRxFailConfig(save_bf_config);
} }
function 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 // BEGIN pre API 1.15.0 save functions
function save_misc() { 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 // END pre API 1.15.0 save functions
function 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() { function reboot() {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function() { 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 { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { 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')); GUI.log(chrome.i18n.getMessage('deviceReady'));
TABS.failsafe.initialize(false, $('#content').scrollTop()); TABS.failsafe.initialize(false, $('#content').scrollTop());
}); });
@ -366,15 +366,15 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
if(apiVersionGte1_15_0) { 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 { } 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 // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -13,7 +13,7 @@ TABS.gps.initialize = function (callback) {
$('#content').load("./tabs/gps.html", process_html); $('#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(){ function set_online(){
$('#connect').hide(); $('#connect').hide();
@ -32,15 +32,15 @@ TABS.gps.initialize = function (callback) {
localize(); localize();
function get_raw_gps_data() { 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() { 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() { 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() { function update_ui() {
@ -113,7 +113,7 @@ TABS.gps.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);

View file

@ -29,30 +29,30 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
function load_led_config() { 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() { 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() { function load_led_mode_colors() {
if (semver.gte(CONFIG.apiVersion, "1.19.0")) 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 else
load_html(); load_html();
} }
function load_html() { function load_html() {
$('#content').load("./tabs/led_strip.html", process_html); $('#content').load("./tabs/led_strip.html", process_html);
} }
load_led_config(); load_led_config();
function buildUsedWireNumbers() { function buildUsedWireNumbers() {
var usedWireNumbers = []; var usedWireNumbers = [];
@ -65,9 +65,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
usedWireNumbers.sort(function(a,b){return a - b}); usedWireNumbers.sort(function(a,b){return a - b});
return usedWireNumbers; return usedWireNumbers;
} }
function process_html() { function process_html() {
localize(); localize();
// Build Grid // Build Grid
@ -145,7 +145,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
updateBulkCmd(); updateBulkCmd();
} }
}); });
// Mode Color Buttons // Mode Color Buttons
$('.mode_colors').on('click', 'button', function() { $('.mode_colors').on('click', 'button', function() {
var that = this; var that = this;
@ -166,7 +166,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$(className).addClass('btnOn'); $(className).addClass('btnOn');
selectedColorIndex = colorIndex; selectedColorIndex = colorIndex;
setColorSliders(colorIndex); setColorSliders(colorIndex);
} else { } else {
$(className).removeClass('btnOn'); $(className).removeClass('btnOn');
} }
@ -180,15 +180,15 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
if (! $(this).is($(that))) { if (! $(this).is($(that))) {
if ($(this).is('.btnOn')) { if ($(this).is('.btnOn')) {
$(this).removeClass('btnOn'); $(this).removeClass('btnOn');
} }
} }
}); });
}); });
updateBulkCmd(); updateBulkCmd();
}); });
// Color sliders // Color sliders
var ip = $('div.colorDefineSliders input'); var ip = $('div.colorDefineSliders input');
ip.eq(0).on("input change", function() { updateColors($(this).val(), 0); }); 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) { $('.colors').on('click', 'button', function(e) {
var that = this; var that = this;
var colorButtons = $(this).parent().find('button'); var colorButtons = $(this).parent().find('button');
for (var colorIndex = 0; colorIndex < 16; colorIndex++) { for (var colorIndex = 0; colorIndex < 16; colorIndex++) {
colorButtons.removeClass('btnOn'); colorButtons.removeClass('btnOn');
if (selectedModeColor == undefined) if (selectedModeColor == undefined)
$('.ui-selected').removeClass('color-' + colorIndex); $('.ui-selected').removeClass('color-' + colorIndex);
if ($(that).is('.color-' + colorIndex)) { if ($(that).is('.color-' + colorIndex)) {
selectedColorIndex = colorIndex; selectedColorIndex = colorIndex;
if (selectedModeColor == undefined) if (selectedModeColor == undefined)
@ -217,7 +217,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
setColorSliders(selectedColorIndex); setColorSliders(selectedColorIndex);
$(this).addClass('btnOn'); $(this).addClass('btnOn');
if (selectedModeColor) { if (selectedModeColor) {
@ -226,28 +226,28 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
drawColorBoxesInColorLedPoints(); drawColorBoxesInColorLedPoints();
// refresh color buttons // refresh color buttons
$('.colors').children().each(function() { setBackgroundColor($(this)); }); $('.colors').children().each(function() { setBackgroundColor($(this)); });
$('.overlay-color').each(function() { setBackgroundColor($(this)); }); $('.overlay-color').each(function() { setBackgroundColor($(this)); });
$('.mode_colors').each(function() { setModeBackgroundColor($(this)); }); $('.mode_colors').each(function() { setModeBackgroundColor($(this)); });
$('.special_colors').each(function() { setModeBackgroundColor($(this)); }); $('.special_colors').each(function() { setModeBackgroundColor($(this)); });
updateBulkCmd(); updateBulkCmd();
}); });
$('.colors').on('dblclick', 'button', function(e) { $('.colors').on('dblclick', 'button', function(e) {
var pp = $('.tab-led-strip').position(); var pp = $('.tab-led-strip').position();
var moveLeft = $('.tab-led-strip').position().left + ($('.colorDefineSliders').width() / 2); var moveLeft = $('.tab-led-strip').position().left + ($('.colorDefineSliders').width() / 2);
var moveUp = $('.tab-led-strip').position().top + $('.colorDefineSliders').height() + 20; var moveUp = $('.tab-led-strip').position().top + $('.colorDefineSliders').height() + 20;
$('.colorDefineSliders').css('left', e.pageX - e.offsetX - moveLeft); $('.colorDefineSliders').css('left', e.pageX - e.offsetX - moveLeft);
$('.colorDefineSliders').css('top', e.pageY - e.offsetY - moveUp); $('.colorDefineSliders').css('top', e.pageY - e.offsetY - moveUp);
$('.colorDefineSliders').show(); $('.colorDefineSliders').show();
}); });
$('.colorDefineSliders').on({ $('.colorDefineSliders').on({
mouseleave: function () { mouseleave: function () {
$('.colorDefineSliders').hide(); $('.colorDefineSliders').hide();
@ -260,10 +260,10 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.colorDefineSliders').hide(); $('.colorDefineSliders').hide();
} }
}); });
$('.funcWire').click(function() { $('.funcWire').click(function() {
$(this).toggleClass('btnOn'); $(this).toggleClass('btnOn');
TABS.led_strip.wireMode = $(this).hasClass('btnOn'); TABS.led_strip.wireMode = $(this).hasClass('btnOn');
$('.mainGrid').toggleClass('gridWire'); $('.mainGrid').toggleClass('gridWire');
}); });
@ -292,16 +292,16 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
var that; var that;
$('.ui-selected').each(function() { $('.ui-selected').each(function() {
var usedWireNumbers = buildUsedWireNumbers(); var usedWireNumbers = buildUsedWireNumbers();
var nextWireNumber = 0; var nextWireNumber = 0;
for (var nextWireNumber = 0; nextWireNumber < usedWireNumbers.length; nextWireNumber++) { for (var nextWireNumber = 0; nextWireNumber < usedWireNumbers.length; nextWireNumber++) {
if (usedWireNumbers[nextWireNumber] != nextWireNumber) { if (usedWireNumbers[nextWireNumber] != nextWireNumber) {
break; break;
} }
} }
if (TABS.led_strip.wireMode) { if (TABS.led_strip.wireMode) {
if ($(this).find('.wire').html() == '' && nextWireNumber < LED_STRIP.length) { if ($(this).find('.wire').html() == '' && nextWireNumber < LED_STRIP.length) {
$(this).find('.wire').html(nextWireNumber); $(this).find('.wire').html(nextWireNumber);
@ -319,14 +319,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
directionsInSelection.push(className); directionsInSelection.push(className);
} }
}); });
TABS.led_strip.baseFuncs.forEach(function(letter) { TABS.led_strip.baseFuncs.forEach(function(letter) {
var className = '.function-' + letter; var className = '.function-' + letter;
if ($(that).is(className)) { if ($(that).is(className)) {
functionsInSelection.push(className); functionsInSelection.push(className);
} }
}); });
TABS.led_strip.overlays.forEach(function(letter) { TABS.led_strip.overlays.forEach(function(letter) {
var className = '.function-' + letter; var className = '.function-' + letter;
if ($(that).is(className)) { if ($(that).is(className)) {
@ -345,47 +345,47 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('select.functionSelect').removeClass(className); $('select.functionSelect').removeClass(className);
} }
}); });
selectedColorIndex = 0; selectedColorIndex = 0;
if (uiSelectedLast) { if (uiSelectedLast) {
// set active color // set active color
for (var colorIndex = 0; colorIndex < 16; colorIndex++) { for (var colorIndex = 0; colorIndex < 16; colorIndex++) {
var className = '.color-' + colorIndex; var className = '.color-' + colorIndex;
if ($(uiSelectedLast).is(className)) { if ($(uiSelectedLast).is(className)) {
$(className).addClass('btnOn'); $(className).addClass('btnOn');
selectedColorIndex = colorIndex; selectedColorIndex = colorIndex;
} else { } else {
$(className).removeClass('btnOn'); $(className).removeClass('btnOn');
} }
} }
// set checkbox values // set checkbox values
TABS.led_strip.overlays.forEach(function(letter) { TABS.led_strip.overlays.forEach(function(letter) {
var feature_o = $('.checkbox').find('input.function-' + letter); var feature_o = $('.checkbox').find('input.function-' + letter);
var newVal = ($(uiSelectedLast).is('.function-' + letter)); var newVal = ($(uiSelectedLast).is('.function-' + letter));
if (feature_o.is(':checked') != newVal) { if (feature_o.is(':checked') != newVal) {
feature_o.prop('checked', newVal); feature_o.prop('checked', newVal);
feature_o.change(); feature_o.change();
} }
}); });
// Update active function in combobox // Update active function in combobox
TABS.led_strip.baseFuncs.forEach(function(letter) { TABS.led_strip.baseFuncs.forEach(function(letter) {
if ($(uiSelectedLast).is('.function-' + letter)) { if ($(uiSelectedLast).is('.function-' + letter)) {
$('select.functionSelect').val("function-" + letter); $('select.functionSelect').val("function-" + letter);
$('select.functionSelect').addClass("function-" + letter); $('select.functionSelect').addClass("function-" + letter);
} }
}); });
} }
updateBulkCmd(); updateBulkCmd();
setColorSliders(selectedColorIndex); setColorSliders(selectedColorIndex);
setOptionalGroupsVisibility(); setOptionalGroupsVisibility();
$('.directions button').removeClass('btnOn'); $('.directions button').removeClass('btnOn');
@ -408,7 +408,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.modeSelect').on('change', function() { $('.modeSelect').on('change', function() {
var that = this; var that = this;
var mode = Number($(that).val()); var mode = Number($(that).val());
$('.mode_colors').find('button').each(function() { $('.mode_colors').find('button').each(function() {
for (var i = 0; i < 6; i++) for (var i = 0; i < 6; i++)
@ -421,13 +421,13 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.mode_colors').each(function() { setModeBackgroundColor($(this)); }); $('.mode_colors').each(function() { setModeBackgroundColor($(this)); });
}); });
function toggleSwitch(that, letter) function toggleSwitch(that, letter)
{ {
if ($(that).is(':checked')) { if ($(that).is(':checked')) {
$('.ui-selected').find('.wire').each(function() { $('.ui-selected').find('.wire').each(function() {
if ($(this).text() != "") { if ($(this).text() != "") {
var p = $(this).parent(); var p = $(this).parent();
TABS.led_strip.functions.forEach(function(f) { TABS.led_strip.functions.forEach(function(f) {
@ -464,21 +464,21 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
return $(that).is(':checked'); return $(that).is(':checked');
} }
// UI: check-box toggle // UI: check-box toggle
$('.checkbox').change(function(e) { $('.checkbox').change(function(e) {
if (e.originalEvent) { if (e.originalEvent) {
// user-triggered event // user-triggered event
var that = $(this).find('input'); var that = $(this).find('input');
if ($('.ui-selected').length > 0) { if ($('.ui-selected').length > 0) {
TABS.led_strip.overlays.forEach(function(letter) { TABS.led_strip.overlays.forEach(function(letter) {
if ($(that).is('.function-' + letter)) { if ($(that).is('.function-' + letter)) {
var ret = toggleSwitch(that, letter); var ret = toggleSwitch(that, letter);
var cbn = $('.checkbox .function-n'); // blink on landing var cbn = $('.checkbox .function-n'); // blink on landing
var cbb = $('.checkbox .function-b'); // blink var cbb = $('.checkbox .function-b'); // blink
if (ret) { if (ret) {
if (letter == 'b' && cbn.is(':checked')) { if (letter == 'b' && cbn.is(':checked')) {
cbn.prop('checked', false); cbn.prop('checked', false);
@ -488,11 +488,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
cbb.prop('checked', false); cbb.prop('checked', false);
cbb.change(); cbb.change();
toggleSwitch(cbb, 'b'); toggleSwitch(cbb, 'b');
} }
} }
} }
}); });
clearModeColorSelection(); clearModeColorSelection();
updateBulkCmd(); updateBulkCmd();
setOptionalGroupsVisibility(); setOptionalGroupsVisibility();
@ -501,9 +501,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
// code-triggered event // code-triggered event
} }
}); });
$('.mainGrid').disableSelection(); $('.mainGrid').disableSelection();
$('.gPoint').each(function(){ $('.gPoint').each(function(){
@ -513,50 +513,50 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
if (col < 0) { if (col < 0) {
col = 15; col = 15;
} }
var ledResult = findLed(col, row); var ledResult = findLed(col, row);
if (!ledResult) { if (!ledResult) {
return; return;
} }
var ledIndex = ledResult.index; var ledIndex = ledResult.index;
var led = ledResult.led; 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) { if (led.functions[0] == 'c' && led.functions.length == 1 && led.directions.length == 0 && led.color == 0 && led.x == 0 && led.y == 0) {
return; return;
} }
$(this).find('.wire').html(ledIndex); $(this).find('.wire').html(ledIndex);
for (var modeIndex = 0; modeIndex < led.functions.length; modeIndex++) { for (var modeIndex = 0; modeIndex < led.functions.length; modeIndex++) {
$(this).addClass('function-' + led.functions[modeIndex]); $(this).addClass('function-' + led.functions[modeIndex]);
} }
for (var directionIndex = 0; directionIndex < led.directions.length; directionIndex++) { for (var directionIndex = 0; directionIndex < led.directions.length; directionIndex++) {
$(this).addClass('dir-' + led.directions[directionIndex]); $(this).addClass('dir-' + led.directions[directionIndex]);
} }
$(this).addClass('color-' + led.color); $(this).addClass('color-' + led.color);
}); });
$('a.save').click(function () { $('a.save').click(function () {
MSP.sendLedStripConfig(send_led_strip_colors); mspHelper.sendLedStripConfig(send_led_strip_colors);
function 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() { function send_led_strip_mode_colors() {
if (semver.gte(CONFIG.apiVersion, "1.19.0")) if (semver.gte(CONFIG.apiVersion, "1.19.0"))
MSP.sendLedStripModeColors(save_to_eeprom); mspHelper.sendLedStripModeColors(save_to_eeprom);
else else
save_to_eeprom(); save_to_eeprom();
} }
function 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')); GUI.log(chrome.i18n.getMessage('ledStripEepromSaved'));
}); });
} }
@ -564,19 +564,19 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
}); });
$('.colorDefineSliders').hide(); $('.colorDefineSliders').hide();
applyFunctionToSelectedLeds(); applyFunctionToSelectedLeds();
drawColorBoxesInColorLedPoints(); drawColorBoxesInColorLedPoints();
setOptionalGroupsVisibility(); setOptionalGroupsVisibility();
updateBulkCmd(); updateBulkCmd();
GUI.content_ready(callback); GUI.content_ready(callback);
} }
@ -589,8 +589,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
return undefined; return undefined;
} }
function updateBulkCmd() { function updateBulkCmd() {
var counter = 0; var counter = 0;
@ -598,9 +598,9 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
var ledStripLength = LED_STRIP.length; var ledStripLength = LED_STRIP.length;
var ledColorsLength = LED_COLORS.length; var ledColorsLength = LED_COLORS.length;
var ledModeColorsLenggth = LED_MODE_COLORS.length; var ledModeColorsLenggth = LED_MODE_COLORS.length;
LED_STRIP = []; LED_STRIP = [];
$('.gPoint').each(function(){ $('.gPoint').each(function(){
if ($(this).is('[class*="function"]')) { if ($(this).is('[class*="function"]')) {
var gridNumber = ($(this).index() + 1); var gridNumber = ($(this).index() + 1);
@ -613,7 +613,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
var directions = ''; var directions = '';
var colorIndex = 0; var colorIndex = 0;
var that = this; var that = this;
var match = $(this).attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/); var match = $(this).attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/);
if (match) { if (match) {
colorIndex = match[2]; colorIndex = match[2];
@ -644,7 +644,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
functions: functions, functions: functions,
color: colorIndex color: colorIndex
} }
LED_STRIP[wireNumber] = led; LED_STRIP[wireNumber] = led;
} }
counter++; counter++;
@ -657,28 +657,28 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
directions: '', directions: '',
functions: '' functions: ''
}; };
for (var i = 0; i < ledStripLength; i++) { for (var i = 0; i < ledStripLength; i++) {
if (LED_STRIP[i]) { if (LED_STRIP[i]) {
continue; continue;
} }
LED_STRIP[i] = defaultLed; LED_STRIP[i] = defaultLed;
} }
var usedWireNumbers = buildUsedWireNumbers(); var usedWireNumbers = buildUsedWireNumbers();
var remaining = LED_STRIP.length - usedWireNumbers.length; var remaining = LED_STRIP.length - usedWireNumbers.length;
$('.wires-remaining div').html(remaining); $('.wires-remaining div').html(remaining);
} }
// refresh mode color buttons // refresh mode color buttons
function setModeBackgroundColor(element) { function setModeBackgroundColor(element) {
if (semver.gte(CONFIG.apiVersion, "1.19.0")) { 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 m = 0;
var d = 0; var d = 0;
var match = $(this).attr("class").match(/(^|\s)mode_color-([0-9]+)-([0-9]+)(\s|$)/); var match = $(this).attr("class").match(/(^|\s)mode_color-([0-9]+)-([0-9]+)(\s|$)/);
if (match) { if (match) {
m = Number(match[2]); m = Number(match[2]);
@ -688,11 +688,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
}); });
} }
} }
function setBackgroundColor(element) { function setBackgroundColor(element) {
if (element.is('[class*="color"]')) { if (element.is('[class*="color"]')) {
var colorIndex = 0; var colorIndex = 0;
var match = element.attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/); var match = element.attr("class").match(/(^|\s)color-([0-9]+)(\s|$)/);
if (match) { if (match) {
colorIndex = match[2]; colorIndex = match[2];
@ -700,11 +700,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
} }
} }
function areModifiersActive(activeFunction) { function areModifiersActive(activeFunction) {
switch (activeFunction) { switch (activeFunction) {
case "function-c": case "function-c":
case "function-a": case "function-a":
case "function-f": case "function-f":
return true; return true;
break; break;
@ -715,8 +715,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
function areOverlaysActive(activeFunction) { function areOverlaysActive(activeFunction) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) { if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
switch (activeFunction) { switch (activeFunction) {
case "function-c": case "function-c":
case "function-a": case "function-a":
case "function-f": case "function-f":
case "function-g": case "function-g":
return true; return true;
@ -724,13 +724,13 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
} else { } else {
switch (activeFunction) { switch (activeFunction) {
case "": case "":
case "function-c": case "function-c":
case "function-a": case "function-a":
case "function-f": case "function-f":
case "function-s": case "function-s":
case "function-l": case "function-l":
case "function-r": case "function-r":
case "function-o": case "function-o":
case "function-g": case "function-g":
return true; return true;
@ -743,8 +743,8 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
function areBlinkersActive(activeFunction) { function areBlinkersActive(activeFunction) {
if (semver.gte(CONFIG.apiVersion, "1.20.0")) { if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
switch (activeFunction) { switch (activeFunction) {
case "function-c": case "function-c":
case "function-a": case "function-a":
case "function-f": case "function-f":
return true; return true;
break; break;
@ -755,7 +755,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
function isWarningActive(activeFunction) { function isWarningActive(activeFunction) {
switch (activeFunction) { switch (activeFunction) {
case "function-l": case "function-l":
case "function-s": case "function-s":
case "function-g": case "function-g":
return false; return false;
@ -765,26 +765,26 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) if (semver.lt(CONFIG.apiVersion, "1.20.0"))
return false; return false;
break; break;
default: default:
return true; return true;
break; break;
} }
} }
function setOptionalGroupsVisibility() { function setOptionalGroupsVisibility() {
var activeFunction = $('select.functionSelect').val(); var activeFunction = $('select.functionSelect').val();
$('select.functionSelect').addClass(activeFunction); $('select.functionSelect').addClass(activeFunction);
if (semver.lte(CONFIG.apiVersion, "1.18.0")) { if (semver.lte(CONFIG.apiVersion, "1.18.0")) {
// <= 18 // <= 18
// Hide GPS (Func) // Hide GPS (Func)
// Hide RSSI (O/L), Blink (Func) // Hide RSSI (O/L), Blink (Func)
// Hide Battery, RSSI (Func), Larson (O/L), Blink (O/L), Landing (O/L) // Hide Battery, RSSI (Func), Larson (O/L), Blink (O/L), Landing (O/L)
$(".extra_functions20").hide(); $(".extra_functions20").hide();
$(".mode_colors").hide(); $(".mode_colors").hide();
} else { } else {
// >= 20 // >= 20
// Show GPS (Func) // Show GPS (Func)
// Hide RSSI (O/L), Blink (Func) // Hide RSSI (O/L), Blink (Func)
@ -792,14 +792,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$(".extra_functions20").show(); $(".extra_functions20").show();
$(".mode_colors").show(); $(".mode_colors").show();
} }
// set color modifiers (check-boxes) visibility // set color modifiers (check-boxes) visibility
$('.overlays').hide(); $('.overlays').hide();
$('.modifiers').hide(); $('.modifiers').hide();
$('.blinkers').hide(); $('.blinkers').hide();
$('.warningOverlay').hide(); $('.warningOverlay').hide();
if (areOverlaysActive(activeFunction)) if (areOverlaysActive(activeFunction))
$('.overlays').show(); $('.overlays').show();
@ -812,7 +812,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
if (isWarningActive(activeFunction)) if (isWarningActive(activeFunction))
$('.warningOverlay').show(); $('.warningOverlay').show();
// set directions visibility // set directions visibility
if (semver.lt(CONFIG.apiVersion, "1.20.0")) { if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
@ -821,21 +821,21 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.indicatorOverlay').hide(); $('.indicatorOverlay').hide();
$('.directions').hide(); $('.directions').hide();
break; break;
default: default:
$('.indicatorOverlay').show(); $('.indicatorOverlay').show();
$('.directions').show(); $('.directions').show();
break; break;
} }
} }
$('.mode_colors').hide(); $('.mode_colors').hide();
if (semver.gte(CONFIG.apiVersion, "1.19.0")) { if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
// set mode colors visibility // set mode colors visibility
if (semver.gte(CONFIG.apiVersion, "1.20.0")) if (semver.gte(CONFIG.apiVersion, "1.20.0"))
if (activeFunction == "function-f") if (activeFunction == "function-f")
$('.mode_colors').show(); $('.mode_colors').show();
// set special colors visibility // set special colors visibility
$('.special_colors').show(); $('.special_colors').show();
$('.mode_color-6-0').hide(); $('.mode_color-6-0').hide();
@ -846,11 +846,11 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
$('.mode_color-6-5').hide(); $('.mode_color-6-5').hide();
$('.mode_color-6-6').hide(); $('.mode_color-6-6').hide();
$('.mode_color-6-7').hide(); $('.mode_color-6-7').hide();
switch (activeFunction) { switch (activeFunction) {
case "": // none case "": // none
case "function-f": // Modes & Orientation case "function-f": // Modes & Orientation
case "function-l": // Battery case "function-l": // Battery
// $('.mode_color-6-3').show(); // background // $('.mode_color-6-3').show(); // background
$('.special_colors').hide(); $('.special_colors').hide();
break; break;
@ -861,47 +861,47 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
// $('.mode_color-6-3').show(); // background // $('.mode_color-6-3').show(); // background
break; break;
case "function-b": // Blink case "function-b": // Blink
$('.mode_color-6-4').show(); // blink background $('.mode_color-6-4').show(); // blink background
break; break;
case "function-a": // Arm state case "function-a": // Arm state
$('.mode_color-6-0').show(); // disarmed $('.mode_color-6-0').show(); // disarmed
$('.mode_color-6-1').show(); // armed $('.mode_color-6-1').show(); // armed
break; break;
case "function-r": // Ring case "function-r": // Ring
default: default:
$('.special_colors').hide(); $('.special_colors').hide();
break; break;
} }
} }
} }
function applyFunctionToSelectedLeds() { function applyFunctionToSelectedLeds() {
var activeFunction = $('select.functionSelect').val(); var activeFunction = $('select.functionSelect').val();
TABS.led_strip.baseFuncs.forEach(function(letter) { TABS.led_strip.baseFuncs.forEach(function(letter) {
if (activeFunction == 'function-' + letter) { if (activeFunction == 'function-' + letter) {
$('select.functionSelect').addClass('function-' + letter); $('select.functionSelect').addClass('function-' + letter);
$('.ui-selected').find('.wire').each(function() { $('.ui-selected').find('.wire').each(function() {
if ($(this).text() != "") if ($(this).text() != "")
$(this).parent().addClass('function-' + letter); $(this).parent().addClass('function-' + letter);
}); });
unselectOverlays(letter); unselectOverlays(letter);
} else { } else {
$('select.functionSelect').removeClass('function-' + letter); $('select.functionSelect').removeClass('function-' + letter);
$('.ui-selected').removeClass('function-' + letter); $('.ui-selected').removeClass('function-' + letter);
} }
if (activeFunction == '') { if (activeFunction == '') {
unselectOverlays(activeFunction); unselectOverlays(activeFunction);
} }
}); });
} }
function unselectOverlays(letter) { function unselectOverlays(letter) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) { if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
if (letter == 'b' || letter == 'r') { if (letter == 'b' || letter == 'r') {
@ -929,7 +929,7 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
} }
} }
function unselectOverlay(func, overlay) { function unselectOverlay(func, overlay) {
$('input.function-' + overlay).prop('checked', false); $('input.function-' + overlay).prop('checked', false);
$('input.function-' + overlay).change(); $('input.function-' + overlay).change();
@ -939,12 +939,12 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
}); });
} }
function updateColors(value, hsvIndex) { function updateColors(value, hsvIndex) {
var change = false; var change = false;
value = Number(value); value = Number(value);
var className = '.color-' + selectedColorIndex; var className = '.color-' + selectedColorIndex;
if ($(className).hasClass('btnOn')) { if ($(className).hasClass('btnOn')) {
switch (hsvIndex) { switch (hsvIndex) {
@ -955,40 +955,40 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
change = true change = true
} }
break; break;
case 1: case 1:
if (LED_COLORS[selectedColorIndex].s != value) { if (LED_COLORS[selectedColorIndex].s != value) {
LED_COLORS[selectedColorIndex].s = value; LED_COLORS[selectedColorIndex].s = value;
$('.colorDefineSliderValue.Svalue').text(LED_COLORS[selectedColorIndex].s); $('.colorDefineSliderValue.Svalue').text(LED_COLORS[selectedColorIndex].s);
change = true change = true
} }
break; break;
case 2: case 2:
if (LED_COLORS[selectedColorIndex].v != value) { if (LED_COLORS[selectedColorIndex].v != value) {
LED_COLORS[selectedColorIndex].v = value; LED_COLORS[selectedColorIndex].v = value;
$('.colorDefineSliderValue.Vvalue').text(LED_COLORS[selectedColorIndex].v); $('.colorDefineSliderValue.Vvalue').text(LED_COLORS[selectedColorIndex].v);
change = true change = true
} }
break; break;
} }
} }
// refresh color buttons
// refresh color buttons
$('.colors').children().each(function() { setBackgroundColor($(this)); }); $('.colors').children().each(function() { setBackgroundColor($(this)); });
$('.overlay-color').each(function() { setBackgroundColor($(this)); }); $('.overlay-color').each(function() { setBackgroundColor($(this)); });
$('.mode_colors').each(function() { setModeBackgroundColor($(this)); }); $('.mode_colors').each(function() { setModeBackgroundColor($(this)); });
$('.special_colors').each(function() { setModeBackgroundColor($(this)); }); $('.special_colors').each(function() { setModeBackgroundColor($(this)); });
if (change) if (change)
updateBulkCmd(); updateBulkCmd();
} }
function drawColorBoxesInColorLedPoints() { function drawColorBoxesInColorLedPoints() {
$('.gPoint').each(function() { $('.gPoint').each(function() {
if ($(this).is('.function-c') || $(this).is('.function-r') || $(this).is('.function-b')) { if ($(this).is('.function-c') || $(this).is('.function-r') || $(this).is('.function-b')) {
$(this).find('.overlay-color').show(); $(this).find('.overlay-color').show();
for (var colorIndex = 0; colorIndex < 16; colorIndex++) { for (var colorIndex = 0; colorIndex < 16; colorIndex++) {
var className = 'color-' + colorIndex; var className = 'color-' + colorIndex;
if ($(this).is('.' + className)) { if ($(this).is('.' + className)) {
@ -1004,27 +1004,27 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
}); });
} }
function setColorSliders(colorIndex) { function setColorSliders(colorIndex) {
var sliders = $('div.colorDefineSliders input'); var sliders = $('div.colorDefineSliders input');
var change = false; var change = false;
if (!LED_COLORS[colorIndex]) if (!LED_COLORS[colorIndex])
return; return;
if (LED_COLORS[colorIndex].h != Number(sliders.eq(0).val())) { if (LED_COLORS[colorIndex].h != Number(sliders.eq(0).val())) {
sliders.eq(0).val(LED_COLORS[colorIndex].h); sliders.eq(0).val(LED_COLORS[colorIndex].h);
$('.colorDefineSliderValue.Hvalue').text(LED_COLORS[colorIndex].h); $('.colorDefineSliderValue.Hvalue').text(LED_COLORS[colorIndex].h);
change = true; change = true;
} }
if (LED_COLORS[colorIndex].s != Number(sliders.eq(1).val())) { if (LED_COLORS[colorIndex].s != Number(sliders.eq(1).val())) {
sliders.eq(1).val(LED_COLORS[colorIndex].s); sliders.eq(1).val(LED_COLORS[colorIndex].s);
$('.colorDefineSliderValue.Svalue').text(LED_COLORS[colorIndex].s); $('.colorDefineSliderValue.Svalue').text(LED_COLORS[colorIndex].s);
change = true; change = true;
} }
if (LED_COLORS[colorIndex].v != Number(sliders.eq(2).val())) { if (LED_COLORS[colorIndex].v != Number(sliders.eq(2).val())) {
sliders.eq(2).val(LED_COLORS[colorIndex].v); sliders.eq(2).val(LED_COLORS[colorIndex].v);
$('.colorDefineSliderValue.Vvalue').text(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 // only fire events when all values are set
if (change) if (change)
sliders.trigger('input'); sliders.trigger('input');
} }
function HsvToColor(input) { function HsvToColor(input) {
if (input == undefined) if (input == undefined)
return ""; return "";
var HSV = { h:Number(input.h), s:Number(input.s), v:Number(input.v) }; var HSV = { h:Number(input.h), s:Number(input.s), v:Number(input.v) };
if (HSV.s == 0 && HSV.v == 0) if (HSV.s == 0 && HSV.v == 0)
return ""; return "";
HSV = { h:HSV.h, s:1 - HSV.s / 255, v:HSV.v / 255 }; HSV = { h:HSV.h, s:1 - HSV.s / 255, v:HSV.v / 255 };
var HSL = { h:0, s:0, v:0}; var HSL = { h:0, s:0, v:0};
HSL.h = HSV.h; HSL.h = HSV.h;
HSL.l = (2 - HSV.s) * HSV.v / 2; 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; 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 + '%)'; var ret = 'hsl(' + HSL.h + ', ' + HSL.s * 100 + '%, ' + HSL.l * 100 + '%)';
return ret; return ret;
} }
@ -1076,14 +1076,14 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
} }
return 0; return 0;
} }
function clearModeColorSelection() { function clearModeColorSelection() {
selectedModeColor = null; selectedModeColor = null;
$('.mode_colors').each(function() { $('.mode_colors').each(function() {
$(this).children().each(function() { $(this).children().each(function() {
if ($(this).is('.btnOn')) { if ($(this).is('.btnOn')) {
$(this).removeClass('btnOn'); $(this).removeClass('btnOn');
} }
}); });
}); });
} }
@ -1091,4 +1091,4 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
TABS.led_strip.cleanup = function (callback) { TABS.led_strip.cleanup = function (callback) {
if (callback) callback(); if (callback) callback();
}; };

View file

@ -16,14 +16,14 @@ TABS.logging.initialize = function (callback) {
if (CONFIGURATOR.connectionValid) { if (CONFIGURATOR.connectionValid) {
var get_motor_data = function () { 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 () { var load_html = function () {
$('#content').load("./tabs/logging.html", process_html); $('#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() { function process_html() {
@ -61,7 +61,7 @@ TABS.logging.initialize = function (callback) {
// request new // request new
for (var i = 0; i < requested_properties.length; i++, requests++) { 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]]);
} }
} }

View file

@ -12,22 +12,22 @@ TABS.modes.initialize = function (callback) {
} }
function get_box_data() { 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() { 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() { 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() { function load_html() {
$('#content').load("./tabs/modes.html", process_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() { function process_html() {
// generate heads according to RC count // generate heads according to RC count
@ -87,12 +87,12 @@ TABS.modes.initialize = function (callback) {
}); });
function 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('auxiliaryEepromSaved')); 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 // val = channel value
@ -116,7 +116,7 @@ TABS.modes.initialize = function (callback) {
// data pulling functions used inside interval timer // data pulling functions used inside interval timer
function get_rc_data() { 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() { function update_ui() {
@ -146,7 +146,7 @@ TABS.modes.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -18,18 +18,18 @@ TABS.motors.initialize = function (callback) {
} }
function get_arm_status() { 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() { 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() { function load_3d() {
var next_callback = get_motor_data; var next_callback = get_motor_data;
if (semver.gte(CONFIG.apiVersion, "1.14.0")) { if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
self.feature3DSupported = true; 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 { } else {
next_callback(); next_callback();
} }
@ -38,14 +38,14 @@ TABS.motors.initialize = function (callback) {
function get_motor_data() { function get_motor_data() {
update_arm_status(); 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() { function load_html() {
$('#content').load("./tabs/motors.html", process_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() { function update_arm_status() {
self.armed = bit_check(CONFIG.mode, 0); 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_kill_all(['motor_and_status_pull']);
GUI.interval_add('IMU_pull', function imu_data_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); }, rate, true);
function update_accel_graph() { function update_accel_graph() {
@ -366,7 +366,7 @@ TABS.motors.initialize = function (callback) {
buffer_delay = setTimeout(function () { buffer_delay = setTimeout(function () {
buffer = buffering_set_motor.pop(); 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 = []; buffering_set_motor = [];
buffer_delay = false; buffer_delay = false;
@ -456,15 +456,15 @@ TABS.motors.initialize = function (callback) {
function get_status() { function get_status() {
// status needed for arming flag // 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() { 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() { 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; var full_block_scale = MISC.maxthrottle - MISC.mincommand;

View file

@ -7,7 +7,7 @@ TABS.onboard_logging = {
}; };
TABS.onboard_logging.initialize = function (callback) { TABS.onboard_logging.initialize = function (callback) {
var var
self = this, self = this,
saveCancelled, eraseCancelled; saveCancelled, eraseCancelled;
@ -17,11 +17,11 @@ TABS.onboard_logging.initialize = function (callback) {
} }
if (CONFIGURATOR.connectionValid) { if (CONFIGURATOR.connectionValid) {
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, function() { MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() {
MSP.send_message(MSP_codes.MSP_DATAFLASH_SUMMARY, false, false, function() { MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
if (semver.gte(CONFIG.flightControllerVersion, "1.2.0")) { if (semver.gte(CONFIG.flightControllerVersion, "1.2.0")) {
MSP.send_message(MSP_codes.MSP_SDCARD_SUMMARY, false, false, function() { MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
MSP.send_message(MSP_codes.MSP_BLACKBOX_CONFIG, false, false, load_html); MSP.send_message(MSPCodes.MSP_BLACKBOX_CONFIG, false, false, load_html);
}); });
} else { } else {
load_html(); load_html();
@ -29,23 +29,23 @@ TABS.onboard_logging.initialize = function (callback) {
}); });
}); });
} }
function gcd(a, b) { function gcd(a, b) {
if (b == 0) if (b == 0)
return a; return a;
return gcd(b, a % b); return gcd(b, a % b);
} }
function 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() { function reboot() {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function() { 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 { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { 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')); GUI.log(chrome.i18n.getMessage('deviceReady'));
TABS.onboard_logging.initialize(false, $('#content').scrollTop()); TABS.onboard_logging.initialize(false, $('#content').scrollTop());
}); });
},1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts },1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
} }
} }
function load_html() { function load_html() {
$('#content').load("./tabs/onboard_logging.html", function() { $('#content').load("./tabs/onboard_logging.html", function() {
// translate to user-selected language // translate to user-selected language
localize(); localize();
var var
dataflashPresent = DATAFLASH.totalSize > 0, dataflashPresent = DATAFLASH.totalSize > 0,
blackboxSupport; blackboxSupport;
/* /*
* Pre-1.11.0 firmware supported DATAFLASH API (on targets with SPI flash) but not the BLACKBOX config API. * 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. * 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)) { || semver.gte(CONFIG.flightControllerVersion, "1.5.0") && semver.lte(CONFIG.flightControllerVersion, "1.10.0") && bit_check(BF_CONFIG.features, 19)) {
blackboxSupport = 'yes'; blackboxSupport = 'yes';
} else if (semver.gte(CONFIG.flightControllerVersion, "1.5.0") && semver.lte(CONFIG.flightControllerVersion, "1.10.0")) { } 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 { } else {
blackboxSupport = 'no'; blackboxSupport = 'no';
} }
$(".tab-onboard_logging") $(".tab-onboard_logging")
.addClass("serial-supported") .addClass("serial-supported")
.toggleClass("dataflash-supported", DATAFLASH.supported) .toggleClass("dataflash-supported", DATAFLASH.supported)
.toggleClass("dataflash-present", dataflashPresent) .toggleClass("dataflash-present", dataflashPresent)
.toggleClass("sdcard-supported", SDCARD.supported) .toggleClass("sdcard-supported", SDCARD.supported)
.toggleClass("blackbox-config-supported", BLACKBOX.supported) .toggleClass("blackbox-config-supported", BLACKBOX.supported)
.toggleClass("blackbox-supported", blackboxSupport == 'yes') .toggleClass("blackbox-supported", blackboxSupport == 'yes')
.toggleClass("blackbox-maybe-supported", blackboxSupport == 'maybe') .toggleClass("blackbox-maybe-supported", blackboxSupport == 'maybe')
.toggleClass("blackbox-unsupported", blackboxSupport == 'no'); .toggleClass("blackbox-unsupported", blackboxSupport == 'no');
@ -105,40 +105,40 @@ TABS.onboard_logging.initialize = function (callback) {
if (dataflashPresent) { if (dataflashPresent) {
// UI hooks // UI hooks
$('.tab-onboard_logging a.erase-flash').click(ask_to_erase_flash); $('.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-confirm').click(flash_erase);
$('.tab-onboard_logging a.erase-flash-cancel').click(flash_erase_cancel); $('.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').click(flash_save_begin);
$('.tab-onboard_logging a.save-flash-cancel').click(flash_save_cancel); $('.tab-onboard_logging a.save-flash-cancel').click(flash_save_cancel);
$('.tab-onboard_logging a.save-flash-dismiss').click(dismiss_saving_dialog); $('.tab-onboard_logging a.save-flash-dismiss').click(dismiss_saving_dialog);
} }
if (BLACKBOX.supported) { if (BLACKBOX.supported) {
$(".tab-onboard_logging a.save-settings").click(function() { $(".tab-onboard_logging a.save-settings").click(function() {
var rate = $(".blackboxRate select").val().split('/'); var rate = $(".blackboxRate select").val().split('/');
BLACKBOX.blackboxRateNum = parseInt(rate[0], 10); BLACKBOX.blackboxRateNum = parseInt(rate[0], 10);
BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10); BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10);
BLACKBOX.blackboxDevice = parseInt($(".blackboxDevice select").val(), 10); BLACKBOX.blackboxDevice = parseInt($(".blackboxDevice select").val(), 10);
MSP.sendBlackboxConfiguration(save_to_eeprom); mspHelper.sendBlackboxConfiguration(save_to_eeprom);
}); });
} }
populateLoggingRates(); populateLoggingRates();
populateDevices(); populateDevices();
update_html(); update_html();
GUI.content_ready(callback); GUI.content_ready(callback);
}); });
} }
function populateDevices() { function populateDevices() {
var var
deviceSelect = $(".blackboxDevice select").empty(); deviceSelect = $(".blackboxDevice select").empty();
deviceSelect.append('<option value="0">Serial port</option>'); deviceSelect.append('<option value="0">Serial port</option>');
if (DATAFLASH.ready) { if (DATAFLASH.ready) {
deviceSelect.append('<option value="1">On-board dataflash chip</option>'); deviceSelect.append('<option value="1">On-board dataflash chip</option>');
@ -146,17 +146,17 @@ TABS.onboard_logging.initialize = function (callback) {
if (SDCARD.supported) { if (SDCARD.supported) {
deviceSelect.append('<option value="2">On-board SD card slot</option>'); deviceSelect.append('<option value="2">On-board SD card slot</option>');
} }
deviceSelect.val(BLACKBOX.blackboxDevice); deviceSelect.val(BLACKBOX.blackboxDevice);
} }
function populateLoggingRates() { function populateLoggingRates() {
var var
userRateGCD = gcd(BLACKBOX.blackboxRateNum, BLACKBOX.blackboxRateDenom), userRateGCD = gcd(BLACKBOX.blackboxRateNum, BLACKBOX.blackboxRateDenom),
userRate = {num: BLACKBOX.blackboxRateNum / userRateGCD, denom: BLACKBOX.blackboxRateDenom / userRateGCD}; 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) // Offer a reasonable choice of logging rates (if people want weird steps they can use CLI)
var var
loggingRates = [ loggingRates = [
{num: 1, denom: 32}, {num: 1, denom: 32},
{num: 1, denom: 16}, {num: 1, denom: 16},
@ -172,58 +172,58 @@ TABS.onboard_logging.initialize = function (callback) {
{num: 1, denom: 1}, {num: 1, denom: 1},
], ],
loggingRatesSelect = $(".blackboxRate select"); loggingRatesSelect = $(".blackboxRate select");
var var
addedCurrentValue = false; addedCurrentValue = false;
for (var i = 0; i < loggingRates.length; i++) { for (var i = 0; i < loggingRates.length; i++) {
if (!addedCurrentValue && userRate.num / userRate.denom <= loggingRates[i].num / loggingRates[i].denom) { if (!addedCurrentValue && userRate.num / userRate.denom <= loggingRates[i].num / loggingRates[i].denom) {
if (userRate.num / userRate.denom < loggingRates[i].num / loggingRates[i].denom) { if (userRate.num / userRate.denom < loggingRates[i].num / loggingRates[i].denom) {
loggingRatesSelect.append('<option value="' + userRate.num + '/' + userRate.denom + '">' loggingRatesSelect.append('<option value="' + userRate.num + '/' + userRate.denom + '">'
+ userRate.num + '/' + userRate.denom + ' (' + Math.round(userRate.num / userRate.denom * 100) + '%)</option>'); + userRate.num + '/' + userRate.denom + ' (' + Math.round(userRate.num / userRate.denom * 100) + '%)</option>');
} }
addedCurrentValue = true; addedCurrentValue = true;
} }
loggingRatesSelect.append('<option value="' + loggingRates[i].num + '/' + loggingRates[i].denom + '">' loggingRatesSelect.append('<option value="' + loggingRates[i].num + '/' + loggingRates[i].denom + '">'
+ loggingRates[i].num + '/' + loggingRates[i].denom + ' (' + Math.round(loggingRates[i].num / loggingRates[i].denom * 100) + '%)</option>'); + loggingRates[i].num + '/' + loggingRates[i].denom + ' (' + Math.round(loggingRates[i].num / loggingRates[i].denom * 100) + '%)</option>');
} }
loggingRatesSelect.val(userRate.num + '/' + userRate.denom); loggingRatesSelect.val(userRate.num + '/' + userRate.denom);
} }
function formatFilesizeKilobytes(kilobytes) { function formatFilesizeKilobytes(kilobytes) {
if (kilobytes < 1024) { if (kilobytes < 1024) {
return Math.round(kilobytes) + "kB"; return Math.round(kilobytes) + "kB";
} }
var var
megabytes = kilobytes / 1024, megabytes = kilobytes / 1024,
gigabytes; gigabytes;
if (megabytes < 900) { if (megabytes < 900) {
return megabytes.toFixed(1) + "MB"; return megabytes.toFixed(1) + "MB";
} else { } else {
gigabytes = megabytes / 1024; gigabytes = megabytes / 1024;
return gigabytes.toFixed(1) + "GB"; return gigabytes.toFixed(1) + "GB";
} }
} }
function formatFilesizeBytes(bytes) { function formatFilesizeBytes(bytes) {
if (bytes < 1024) { if (bytes < 1024) {
return bytes + "B"; return bytes + "B";
} }
return formatFilesizeKilobytes(bytes / 1024); return formatFilesizeKilobytes(bytes / 1024);
} }
function update_bar_width(bar, value, total, label, valuesAreKilobytes) { function update_bar_width(bar, value, total, label, valuesAreKilobytes) {
if (value > 0) { if (value > 0) {
bar.css({ bar.css({
width: (value / total * 100) + "%", width: (value / total * 100) + "%",
display: 'block' display: 'block'
}); });
$("div", bar).text((label ? label + " " : "") + (valuesAreKilobytes ? formatFilesizeKilobytes(value) : formatFilesizeBytes(value))); $("div", bar).text((label ? label + " " : "") + (valuesAreKilobytes ? formatFilesizeKilobytes(value) : formatFilesizeBytes(value)));
} else { } else {
bar.css({ bar.css({
@ -231,7 +231,7 @@ TABS.onboard_logging.initialize = function (callback) {
}); });
} }
} }
function update_html() { 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-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); 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); 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); $(".btn a.erase-flash, .btn a.save-flash").toggleClass("disabled", DATAFLASH.usedSize == 0);
$(".tab-onboard_logging") $(".tab-onboard_logging")
.toggleClass("sdcard-error", SDCARD.state == MSP.SDCARD_STATE_FATAL) .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-initializing", SDCARD.state == MSP.SDCARD_STATE_CARD_INIT || SDCARD.state == MSP.SDCARD_STATE_FS_INIT)
.toggleClass("sdcard-ready", SDCARD.state == MSP.SDCARD_STATE_READY); .toggleClass("sdcard-ready", SDCARD.state == MSP.SDCARD_STATE_READY);
switch (SDCARD.state) { switch (SDCARD.state) {
case MSP.SDCARD_STATE_NOT_PRESENT: case MSP.SDCARD_STATE_NOT_PRESENT:
$(".sdcard-status").text("No card inserted"); $(".sdcard-status").text("No card inserted");
@ -265,85 +265,85 @@ TABS.onboard_logging.initialize = function (callback) {
default: default:
$(".sdcard-status").text("Unknown state " + SDCARD.state); $(".sdcard-status").text("Unknown state " + SDCARD.state);
} }
if (SDCARD.supported && !sdcardTimer) { if (SDCARD.supported && !sdcardTimer) {
// Poll for changes in SD card status // Poll for changes in SD card status
sdcardTimer = setTimeout(function() { sdcardTimer = setTimeout(function() {
sdcardTimer = false; sdcardTimer = false;
if (CONFIGURATOR.connectionValid) { 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(); update_html();
}); });
} }
}, 2000); }, 2000);
} }
} }
// IO related methods // IO related methods
function zeroPad(value, width) { function zeroPad(value, width) {
value = "" + value; value = "" + value;
while (value.length < width) { while (value.length < width) {
value = "0" + value; value = "0" + value;
} }
return value; return value;
} }
function flash_save_cancel() { function flash_save_cancel() {
saveCancelled = true; saveCancelled = true;
} }
function show_saving_dialog() { function show_saving_dialog() {
$(".dataflash-saving progress").attr("value", 0); $(".dataflash-saving progress").attr("value", 0);
saveCancelled = false; saveCancelled = false;
$(".dataflash-saving").removeClass("done"); $(".dataflash-saving").removeClass("done");
$(".dataflash-saving")[0].showModal(); $(".dataflash-saving")[0].showModal();
} }
function dismiss_saving_dialog() { function dismiss_saving_dialog() {
$(".dataflash-saving")[0].close(); $(".dataflash-saving")[0].close();
} }
function mark_saving_dialog_done() { function mark_saving_dialog_done() {
$(".dataflash-saving").addClass("done"); $(".dataflash-saving").addClass("done");
} }
function flash_update_summary(onDone) { 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(); update_html();
if (onDone) { if (onDone) {
onDone(); onDone();
} }
}); });
} }
function flash_save_begin() { function flash_save_begin() {
if (GUI.connected_to) { if (GUI.connected_to) {
// Begin by refreshing the occupied size in case it changed while the tab was open // Begin by refreshing the occupied size in case it changed while the tab was open
flash_update_summary(function() { flash_update_summary(function() {
var var
maxBytes = DATAFLASH.usedSize; maxBytes = DATAFLASH.usedSize;
prepare_file(function(fileWriter) { prepare_file(function(fileWriter) {
var var
nextAddress = 0; nextAddress = 0;
show_saving_dialog(); show_saving_dialog();
function onChunkRead(chunkAddress, chunkDataView) { function onChunkRead(chunkAddress, chunkDataView) {
if (chunkDataView != null) { if (chunkDataView != null) {
// Did we receive any data? // Did we receive any data?
if (chunkDataView.byteLength > 0) { if (chunkDataView.byteLength > 0) {
nextAddress += chunkDataView.byteLength; nextAddress += chunkDataView.byteLength;
$(".dataflash-saving progress").attr("value", nextAddress / maxBytes * 100); $(".dataflash-saving progress").attr("value", nextAddress / maxBytes * 100);
var var
blob = new Blob([chunkDataView]); blob = new Blob([chunkDataView]);
fileWriter.onwriteend = function(e) { fileWriter.onwriteend = function(e) {
if (saveCancelled || nextAddress >= maxBytes) { if (saveCancelled || nextAddress >= maxBytes) {
if (saveCancelled) { if (saveCancelled) {
@ -352,10 +352,10 @@ TABS.onboard_logging.initialize = function (callback) {
mark_saving_dialog_done(); mark_saving_dialog_done();
} }
} else { } else {
MSP.dataflashRead(nextAddress, onChunkRead); mspHelper.dataflashRead(nextAddress, onChunkRead);
} }
}; };
fileWriter.write(blob); fileWriter.write(blob);
} else { } else {
// A zero-byte block indicates end-of-file, so we're done // A zero-byte block indicates end-of-file, so we're done
@ -363,37 +363,37 @@ TABS.onboard_logging.initialize = function (callback) {
} }
} else { } else {
// There was an error with the received block (address didn't match the one we asked for), retry // 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 // Fetch the initial block
MSP.dataflashRead(nextAddress, onChunkRead); mspHelper.dataflashRead(nextAddress, onChunkRead);
}); });
}); });
} }
} }
function prepare_file(onComplete) { function prepare_file(onComplete) {
var var
date = new Date(), date = new Date(),
filename = 'blackbox_log_' + date.getFullYear() + '-' + zeroPad(date.getMonth() + 1, 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.getDate(), 2) + '_' + zeroPad(date.getHours(), 2) + zeroPad(date.getMinutes(), 2)
+ zeroPad(date.getSeconds(), 2); + zeroPad(date.getSeconds(), 2);
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename, chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename,
accepts: [{extensions: ['TXT']}]}, function(fileEntry) { accepts: [{extensions: ['TXT']}]}, function(fileEntry) {
var error = chrome.runtime.lastError; var error = chrome.runtime.lastError;
if (error) { if (error) {
console.error(error.message); console.error(error.message);
if (error.message != "User cancelled") { if (error.message != "User cancelled") {
GUI.log(chrome.i18n.getMessage('dataflashFileWriteFailed')); GUI.log(chrome.i18n.getMessage('dataflashFileWriteFailed'));
} }
return; return;
} }
// echo/console log path specified // echo/console log path specified
chrome.fileSystem.getDisplayPath(fileEntry, function(path) { chrome.fileSystem.getDisplayPath(fileEntry, function(path) {
console.log('Dataflash dump file path: ' + path); console.log('Dataflash dump file path: ' + path);
@ -414,12 +414,12 @@ TABS.onboard_logging.initialize = function (callback) {
}); });
}); });
} }
function ask_to_erase_flash() { function ask_to_erase_flash() {
eraseCancelled = false; eraseCancelled = false;
$(".dataflash-confirm-erase").removeClass('erasing'); $(".dataflash-confirm-erase").removeClass('erasing');
$(".dataflash-confirm-erase")[0].showModal(); $(".dataflash-confirm-erase")[0].showModal();
} }
function poll_for_erase_completion() { function poll_for_erase_completion() {
@ -433,13 +433,13 @@ TABS.onboard_logging.initialize = function (callback) {
} }
}); });
} }
function flash_erase() { function flash_erase() {
$(".dataflash-confirm-erase").addClass('erasing'); $(".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() { function flash_erase_cancel() {
eraseCancelled = true; eraseCancelled = true;
$(".dataflash-confirm-erase")[0].close(); $(".dataflash-confirm-erase")[0].close();
@ -451,8 +451,8 @@ TABS.onboard_logging.cleanup = function (callback) {
clearTimeout(sdcardTimer); clearTimeout(sdcardTimer);
sdcardTimer = false; sdcardTimer = false;
} }
if (callback) { if (callback) {
callback(); callback();
} }
}; };

View file

@ -22,12 +22,8 @@ SYM.METRE = 0xC;
SYM.FEET = 0xF; SYM.FEET = 0xF;
SYM.GPS_SAT = 0x1F; SYM.GPS_SAT = 0x1F;
var FONT = FONT || {}; var FONT = FONT || {};
//FIXME This is hack!
var MSPCodes = MSP_codes;
FONT.initData = function () { FONT.initData = function () {
if (FONT.data) { if (FONT.data) {
return; return;

View file

@ -13,21 +13,21 @@ TABS.pid_tuning.initialize = function (callback) {
} }
function get_pid_names() { 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() { 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() { 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() { function loadINAVPidConfig() {
var next_callback = loadPidAdvanced; var next_callback = loadPidAdvanced;
if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -36,7 +36,7 @@ TABS.pid_tuning.initialize = function (callback) {
function loadPidAdvanced() { function loadPidAdvanced() {
var next_callback = loadFilterConfig; var next_callback = loadFilterConfig;
if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -45,7 +45,7 @@ TABS.pid_tuning.initialize = function (callback) {
function loadFilterConfig() { function loadFilterConfig() {
var next_callback = load_html; var next_callback = load_html;
if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -57,7 +57,7 @@ TABS.pid_tuning.initialize = function (callback) {
} }
// requesting MSP_STATUS manually because it contains CONFIG.profile // 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 = [ var sectionClasses = [
'ROLL', // 0 'ROLL', // 0
@ -165,7 +165,7 @@ TABS.pid_tuning.initialize = function (callback) {
}); });
$('#resetPIDs').on('click', function(){ $('#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(); updateActivatedTab();
}); });
@ -277,17 +277,17 @@ TABS.pid_tuning.initialize = function (callback) {
form_to_pid_and_rc(); form_to_pid_and_rc();
function send_pids() { 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() { 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() { function saveINAVPidConfig() {
var next_callback = savePidAdvanced; var next_callback = savePidAdvanced;
if(semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -296,7 +296,7 @@ TABS.pid_tuning.initialize = function (callback) {
function savePidAdvanced() { function savePidAdvanced() {
var next_callback = saveFilterConfig; var next_callback = saveFilterConfig;
if(semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -305,14 +305,14 @@ TABS.pid_tuning.initialize = function (callback) {
function saveFilterConfig() { function saveFilterConfig() {
var next_callback = save_to_eeprom; var next_callback = save_to_eeprom;
if(semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { 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 { } else {
next_callback(); next_callback();
} }
} }
function 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('pidTuningEepromSaved')); 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 // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -84,7 +84,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
load_configuration_from_fc(); load_configuration_from_fc();
function 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() { function on_configuration_loaded_handler() {
$('#content').load("./tabs/ports.html", on_tab_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 // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);
@ -258,17 +258,17 @@ TABS.ports.initialize = function (callback, scrollPosition) {
SERIAL_CONFIG.ports.push(serialPort); 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() { 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() { function on_saved_handler() {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function() { 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); },2500);
} else { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { 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')); GUI.log(chrome.i18n.getMessage('deviceReady'));
TABS.ports.initialize(false, $('#content').scrollTop()); TABS.ports.initialize(false, $('#content').scrollTop());
}); });

View file

@ -13,26 +13,26 @@ TABS.receiver.initialize = function (callback) {
} }
function get_misc_data() { 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() { 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() { 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: // Fetch features so we can check if RX_MSP is enabled:
function load_config() { 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() { function load_rc_configs() {
var next_callback = load_html; var next_callback = load_html;
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { 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 { } else {
next_callback(); next_callback();
} }
@ -42,7 +42,7 @@ TABS.receiver.initialize = function (callback) {
$('#content').load("./tabs/receiver.html", process_html); $('#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() { function process_html() {
// translate to user-selected language // translate to user-selected language
@ -283,7 +283,7 @@ TABS.receiver.initialize = function (callback) {
}).trigger('input'); }).trigger('input');
$('a.refresh').click(function () { $('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')); GUI.log(chrome.i18n.getMessage('receiverDataRefreshed'));
// fill in data from RC_tuning // 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.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
RC_deadband.deadband = parseInt($('.deadband input[name="deadband"]').val()); RC_deadband.deadband = parseInt($('.deadband input[name="deadband"]').val());
} }
// catch rc map // catch rc map
var RC_MAP_Letters = ['A', 'E', 'R', 'T', '1', '2', '3', '4']; var RC_MAP_Letters = ['A', 'E', 'R', 'T', '1', '2', '3', '4'];
var strBuffer = $('input[name="rcmap"]').val().split(''); 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()); MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val());
function save_rc_map() { 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() { 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() { function save_rc_configs() {
var next_callback = save_to_eeprom; var next_callback = save_to_eeprom;
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { 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 { } else {
next_callback(); next_callback();
} }
} }
function 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('receiverEepromSaved')); 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() { $("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) // Give the window a callback it can use to send the channels (otherwise it can't see those objects)
createdWindow.contentWindow.setRawRx = function(channels) { createdWindow.contentWindow.setRawRx = function(channels) {
if (CONFIGURATOR.connectionValid && GUI.active_tab != 'cli') { if (CONFIGURATOR.connectionValid && GUI.active_tab != 'cli') {
MSP.setRawRx(channels); mspHelper.setRawRx(channels);
return true; return true;
} else { } else {
return false; return false;
@ -386,7 +386,7 @@ TABS.receiver.initialize = function (callback) {
chrome.storage.local.set({'rx_refresh_rate': plot_update_rate}); chrome.storage.local.set({'rx_refresh_rate': plot_update_rate});
function get_rc_data() { 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 // setup plot
@ -485,7 +485,7 @@ TABS.receiver.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -361,25 +361,25 @@ TABS.sensors.initialize = function (callback) {
// data pulling timers // data pulling timers
if (checkboxes[0] || checkboxes[1] || checkboxes[2]) { if (checkboxes[0] || checkboxes[1] || checkboxes[2]) {
GUI.interval_add('IMU_pull', function imu_data_pull() { 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); }, fastest, true);
} }
if (checkboxes[3]) { if (checkboxes[3]) {
GUI.interval_add('altitude_pull', function altitude_data_pull() { 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); }, rates.baro, true);
} }
if (checkboxes[4]) { if (checkboxes[4]) {
GUI.interval_add('sonar_pull', function sonar_data_pull() { 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); }, rates.sonar, true);
} }
if (checkboxes[5]) { if (checkboxes[5]) {
GUI.interval_add('debug_pull', function debug_data_pull() { 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); }, rates.debug, true);
} }
@ -445,7 +445,7 @@ TABS.sensors.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -10,47 +10,47 @@ TABS.servos.initialize = function (callback) {
} }
function get_servo_configurations() { 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() { 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() { function get_channel_forwarding() {
var nextFunction = get_rc_data; var nextFunction = get_rc_data;
if (semver.lt(CONFIG.apiVersion, "1.12.0")) { if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
MSP.send_message(MSP_codes.MSP_CHANNEL_FORWARDING, false, false, nextFunction); MSP.send_message(MSPCodes.MSP_CHANNEL_FORWARDING, false, false, nextFunction);
} else { } else {
nextFunction(); nextFunction();
} }
} }
function get_rc_data() { 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() { 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() { function load_html() {
$('#content').load("./tabs/servos.html", process_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() { function update_ui() {
if (semver.lt(CONFIG.apiVersion, "1.12.0") || SERVO_CONFIG.length == 0) { if (semver.lt(CONFIG.apiVersion, "1.12.0") || SERVO_CONFIG.length == 0) {
$(".tab-servos").removeClass("supported"); $(".tab-servos").removeClass("supported");
return; return;
} }
$(".tab-servos").addClass("supported"); $(".tab-servos").addClass("supported");
var servoCheckbox = ''; var servoCheckbox = '';
var servoHeader = ''; var servoHeader = '';
for (var i = 0; i < RC.active_channels-4; i++) { 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); $('div.tab-servos table.fields tr.main').append(servoHeader);
function process_servos(name, alternate, obj) { function process_servos(name, alternate, obj) {
$('div.supported_wrapper').show(); $('div.supported_wrapper').show();
$('div.tab-servos table.fields').append('\ $('div.tab-servos table.fields').append('\
<tr> \ <tr> \
<td style="text-align: center">' + name + '</td>\ <td style="text-align: center">' + name + '</td>\
@ -105,9 +105,9 @@ TABS.servos.initialize = function (callback) {
select.val(SERVO_CONFIG[obj].rate); select.val(SERVO_CONFIG[obj].rate);
$('div.tab-servos table.fields tr:last').data('info', {'obj': obj}); $('div.tab-servos table.fields tr:last').data('info', {'obj': obj});
// UI hooks // UI hooks
// only one checkbox for indicating a channel to forward can be selected at a time, perhaps a radio group would be best here. // only one checkbox for indicating a channel to forward can be selected at a time, perhaps a radio group would be best here.
$('div.tab-servos table.fields tr:last td.channel input').click(function () { $('div.tab-servos table.fields tr:last td.channel input').click(function () {
if($(this).is(':checked')) { if($(this).is(':checked')) {
@ -126,10 +126,10 @@ TABS.servos.initialize = function (callback) {
if (channelIndex == -1) { if (channelIndex == -1) {
channelIndex = undefined; channelIndex = undefined;
} }
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex; SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val()); SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val()); SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val()); SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
@ -139,19 +139,20 @@ TABS.servos.initialize = function (callback) {
var val = parseInt($('.direction select', this).val()); var val = parseInt($('.direction select', this).val());
SERVO_CONFIG[info.obj].rate = val; SERVO_CONFIG[info.obj].rate = val;
}); });
// //
// send data to FC // send data to FC
// //
MSP.sendServoConfigurations(send_servo_mixer_rules); //FIXME investigate why the same frame is sent twice
mspHelper.sendServoConfigurations(send_servo_mixer_rules);
function send_servo_mixer_rules() { function send_servo_mixer_rules() {
MSP.sendServoConfigurations(save_to_eeprom); mspHelper.sendServoConfigurations(save_to_eeprom);
} }
function save_to_eeprom() { function save_to_eeprom() {
if (save_configuration_to_eeprom) { if (save_configuration_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('servosEepromSave')); GUI.log(chrome.i18n.getMessage('servosEepromSave'));
}); });
} }
@ -173,23 +174,23 @@ TABS.servos.initialize = function (callback) {
GUI.timeout_add('servos_update', servos_update, 10); GUI.timeout_add('servos_update', servos_update, 10);
} }
}); });
$('a.update').click(function () { $('a.update').click(function () {
servos_update(true); servos_update(true);
}); });
} }
function process_html() { function process_html() {
update_ui(); update_ui();
// translate to user-selected language // translate to user-selected language
localize(); localize();
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function () { GUI.interval_add('status_pull', function () {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -13,22 +13,22 @@ TABS.setup.initialize = function (callback) {
} }
function load_ident() { function load_ident() {
MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_config); MSP.send_message(MSPCodes.MSP_IDENT, false, false, load_config);
} }
function load_config() { function load_config() {
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_misc_data); MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc_data);
} }
function load_misc_data() { function load_misc_data() {
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_html); MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
} }
function load_html() { function load_html() {
$('#content').load("./tabs/setup.html", process_html); $('#content').load("./tabs/setup.html", process_html);
} }
MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_ident); MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_ident);
function process_html() { function process_html() {
// translate to user-selected language // translate to user-selected language
@ -73,7 +73,7 @@ TABS.setup.initialize = function (callback) {
// During this period MCU won't be able to process any serial commands because its locked in a for/while loop // During this period MCU won't be able to process any serial commands because its locked in a for/while loop
// until this operation finishes, sending more commands through data_poll() will result in serial buffer overflow // until this operation finishes, sending more commands through data_poll() will result in serial buffer overflow
GUI.interval_pause('setup_data_pull'); GUI.interval_pause('setup_data_pull');
MSP.send_message(MSP_codes.MSP_ACC_CALIBRATION, false, false, function () { MSP.send_message(MSPCodes.MSP_ACC_CALIBRATION, false, false, function () {
GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibStarted')); GUI.log(chrome.i18n.getMessage('initialSetupAccelCalibStarted'));
$('#accel_calib_running').show(); $('#accel_calib_running').show();
$('#accel_calib_rest').hide(); $('#accel_calib_rest').hide();
@ -97,7 +97,7 @@ TABS.setup.initialize = function (callback) {
if (!self.hasClass('calibrating') && !self.hasClass('disabled')) { if (!self.hasClass('calibrating') && !self.hasClass('disabled')) {
self.addClass('calibrating'); self.addClass('calibrating');
MSP.send_message(MSP_codes.MSP_MAG_CALIBRATION, false, false, function () { MSP.send_message(MSPCodes.MSP_MAG_CALIBRATION, false, false, function () {
GUI.log(chrome.i18n.getMessage('initialSetupMagCalibStarted')); GUI.log(chrome.i18n.getMessage('initialSetupMagCalibStarted'));
$('#mag_calib_running').show(); $('#mag_calib_running').show();
$('#mag_calib_rest').hide(); $('#mag_calib_rest').hide();
@ -113,7 +113,7 @@ TABS.setup.initialize = function (callback) {
}); });
$('a.resetSettings').click(function () { $('a.resetSettings').click(function () {
MSP.send_message(MSP_codes.MSP_RESET_CONF, false, false, function () { MSP.send_message(MSPCodes.MSP_RESET_CONF, false, false, function () {
GUI.log(chrome.i18n.getMessage('initialSetupSettingsRestored')); GUI.log(chrome.i18n.getMessage('initialSetupSettingsRestored'));
GUI.tab_switch_cleanup(function () { GUI.tab_switch_cleanup(function () {
@ -170,9 +170,9 @@ TABS.setup.initialize = function (callback) {
heading_e = $('dd.heading'); heading_e = $('dd.heading');
function get_slow_data() { function get_slow_data() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
MSP.send_message(MSP_codes.MSP_ANALOG, false, false, function () { MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
bat_voltage_e.text(chrome.i18n.getMessage('initialSetupBatteryValue', [ANALOG.voltage])); bat_voltage_e.text(chrome.i18n.getMessage('initialSetupBatteryValue', [ANALOG.voltage]));
bat_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn])); bat_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn]));
bat_mah_drawing_e.text(chrome.i18n.getMessage('initialSetupBatteryAValue', [ANALOG.amperage.toFixed(2)])); bat_mah_drawing_e.text(chrome.i18n.getMessage('initialSetupBatteryAValue', [ANALOG.amperage.toFixed(2)]));
@ -180,7 +180,7 @@ TABS.setup.initialize = function (callback) {
}); });
if (have_sensor(CONFIG.activeSensors, 'gps')) { if (have_sensor(CONFIG.activeSensors, 'gps')) {
MSP.send_message(MSP_codes.MSP_RAW_GPS, false, false, function () { MSP.send_message(MSPCodes.MSP_RAW_GPS, false, false, function () {
var gpsFixType = chrome.i18n.getMessage('gpsFixNone'); var gpsFixType = chrome.i18n.getMessage('gpsFixNone');
if (GPS_DATA.fix >= 2) if (GPS_DATA.fix >= 2)
gpsFixType = chrome.i18n.getMessage('gpsFix3D'); gpsFixType = chrome.i18n.getMessage('gpsFix3D');
@ -195,7 +195,7 @@ TABS.setup.initialize = function (callback) {
} }
function get_fast_data() { function get_fast_data() {
MSP.send_message(MSP_codes.MSP_ATTITUDE, false, false, function () { MSP.send_message(MSPCodes.MSP_ATTITUDE, false, false, function () {
roll_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[0]])); roll_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[0]]));
pitch_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[1]])); pitch_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[1]]));
heading_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[2]])); heading_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[2]]));

View file

@ -14,7 +14,7 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
// transponder supported added in MSP API Version 1.16.0 // transponder supported added in MSP API Version 1.16.0
TABS.transponder.available = semver.gte(CONFIG.apiVersion, "1.16.0"); TABS.transponder.available = semver.gte(CONFIG.apiVersion, "1.16.0");
if (!TABS.transponder.available) { if (!TABS.transponder.available) {
load_html(); load_html();
return; return;
@ -25,7 +25,7 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
} }
// get the transponder data and a flag to see if transponder support is enabled on the FC // get the transponder data and a flag to see if transponder support is enabled on the FC
MSP.send_message(MSP_codes.MSP_TRANSPONDER_CONFIG, false, false, load_html); MSP.send_message(MSPCodes.MSP_TRANSPONDER_CONFIG, false, false, load_html);
// Convert a hex string to a byte array // Convert a hex string to a byte array
function hexToBytes(hex) { function hexToBytes(hex) {
@ -38,7 +38,7 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
n = n + ''; n = n + '';
return n.length >= width ? n : new Array(width - n.length + 1).join('0') + n; return n.length >= width ? n : new Array(width - n.length + 1).join('0') + n;
} }
// Convert a byte array to a hex string // Convert a byte array to a hex string
function bytesToHex(bytes) { function bytesToHex(bytes) {
for (var hex = [], i = 0; i < bytes.length; i++) { for (var hex = [], i = 0; i < bytes.length; i++) {
@ -49,51 +49,51 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
function process_html() { function process_html() {
// translate to user-selected language // translate to user-selected language
localize(); localize();
$(".tab-transponder") $(".tab-transponder")
.toggleClass("transponder-supported", TABS.transponder.available && TRANSPONDER.supported); .toggleClass("transponder-supported", TABS.transponder.available && TRANSPONDER.supported);
if (TABS.transponder.available) { if (TABS.transponder.available) {
var data = bytesToHex(TRANSPONDER.data); var data = bytesToHex(TRANSPONDER.data);
$('input[name="data"]').val(data); $('input[name="data"]').val(data);
$('input[name="data"]').prop('maxLength', data.length); $('input[name="data"]').prop('maxLength', data.length);
$('a.save').click(function () { $('a.save').click(function () {
// gather data that doesn't have automatic change event bound // gather data that doesn't have automatic change event bound
var dataString = $('input[name="data"]').val(); var dataString = $('input[name="data"]').val();
var expectedLength = TRANSPONDER.data.length; var expectedLength = TRANSPONDER.data.length;
var hexRegExp = new RegExp('[0-9a-fA-F]{' + (expectedLength * 2) + '}', 'gi'); var hexRegExp = new RegExp('[0-9a-fA-F]{' + (expectedLength * 2) + '}', 'gi');
if (!dataString.match(hexRegExp)) { if (!dataString.match(hexRegExp)) {
GUI.log(chrome.i18n.getMessage('transponderDataInvalid')); GUI.log(chrome.i18n.getMessage('transponderDataInvalid'));
return; return;
} }
TRANSPONDER.data = hexToBytes(dataString); TRANSPONDER.data = hexToBytes(dataString);
// //
// send data to FC // send data to FC
// //
function save_transponder_config() { function save_transponder_config() {
MSP.send_message(MSP_codes.MSP_SET_TRANSPONDER_CONFIG, MSP.crunch(MSP_codes.MSP_SET_TRANSPONDER_CONFIG), false, save_to_eeprom); MSP.send_message(MSPCodes.MSP_SET_TRANSPONDER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_TRANSPONDER_CONFIG), false, save_to_eeprom);
} }
function 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('transponderEepromSaved')); GUI.log(chrome.i18n.getMessage('transponderEepromSaved'));
}); });
} }
save_transponder_config(); save_transponder_config();
}); });
} }
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSP_codes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);