Merge pull request #1462 from iNavFlight/dzikuvx-drop-bf-config

drop BF_CONFIG MSP frame
pull/1466/head
Paweł Spychalski 3 years ago committed by GitHub
commit f0b7b75ec0
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

@ -1,4 +1,4 @@
/*global mspHelper,$,GUI,MSP,BF_CONFIG,chrome*/
/*global mspHelper,$,GUI,MSP,chrome*/
'use strict';
var helper = helper || {};
@ -733,7 +733,7 @@ helper.defaultsDialog = (function () {
savingDefaultsModal.close();
}
mspHelper.loadBfConfig(function () {
mspHelper.loadFeatures(function () {
privateScope.setFeaturesBits(selectedDefaultPreset)
});
} else {

@ -2,7 +2,6 @@
// define all the global variables that are uses to hold FC state
var CONFIG,
BF_CONFIG,
LED_STRIP,
LED_COLORS,
LED_MODE_COLORS,
@ -65,7 +64,8 @@ var CONFIG,
BRAKING_CONFIG,
SAFEHOMES,
BOARD_ALIGNMENT,
CURRENT_METER_CONFIG;
CURRENT_METER_CONFIG,
FEATURES;
var FC = {
MAX_SERVO_RATE: 125,
@ -129,17 +129,6 @@ var FC = {
name: ''
};
BF_CONFIG = {
mixerConfiguration: 0,
features: 0,
serialrx_type: 0,
board_align_roll: 0,
board_align_pitch: 0,
board_align_yaw: 0,
currentscale: 0,
currentoffset: 0
};
BOARD_ALIGNMENT = {
roll: 0,
pitch: 0,
@ -157,6 +146,8 @@ var FC = {
LED_COLORS = [];
LED_MODE_COLORS = [];
FEATURES = 0;
PID = {
};
@ -621,7 +612,7 @@ var FC = {
features = this.getFeatures();
}
for (var i = 0; i < features.length; i++) {
if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) {
if (features[i].name == featureName && bit_check(FEATURES, features[i].bit)) {
return true;
}
}

@ -1,4 +1,4 @@
/*global mspHelper,BF_CONFIG*/
/*global mspHelper,FEATURES,bit_clear,bit_set*/
'use strict';
var helper = helper || {};
@ -67,20 +67,20 @@ helper.features = (function() {
publicScope.execute = function(callback) {
exitPoint = callback;
mspHelper.loadBfConfig(privateScope.setBits);
mspHelper.loadFeatures(privateScope.setBits);
};
privateScope.setBits = function () {
for (const bit of toSet) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, bit);
FEATURES = bit_set(FEATURES, bit);
}
for (const bit of toUnset) {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, bit);
FEATURES = bit_clear(FEATURES, bit);
}
mspHelper.saveBfConfig(exitPoint);
mspHelper.saveFeatures(exitPoint);
}
return publicScope;

@ -33,6 +33,8 @@ var MSPCodes = {
MSP_SET_CHANNEL_FORWARDING: 33,
MSP_MODE_RANGES: 34,
MSP_SET_MODE_RANGE: 35,
MSP_FEATURE: 36,
MSP_SET_FEATURE: 37,
MSP_BOARD_ALIGNMENT: 38,
MSP_SET_BOARD_ALIGNMENT: 39,
MSP_CURRENT_METER_CONFIG: 40,
@ -48,8 +50,6 @@ var MSPCodes = {
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,
@ -153,10 +153,10 @@ var MSPCodes = {
// 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_BF_CONFIG: 66, // Depreciated
MSP_SET_BF_CONFIG: 67, // Depreciated
MSP_SET_REBOOT: 68, // reboot settings
MSP_BF_BUILD_INFO: 69, // build date as well as some space for future expansion
MSP_BF_BUILD_INFO: 69, // Depreciated
// INAV specific codes
MSPV2_SETTING: 0x1003,

@ -68,15 +68,6 @@ var mspHelper = (function (gui) {
colorCount,
color;
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
case MSPCodes.MSP_IDENT:
//FIXME remove this frame when proven not needed
console.log('Using deprecated msp command: MSP_IDENT');
// Deprecated
CONFIG.version = parseFloat((data.getUint8(0) / 100).toFixed(2));
CONFIG.multiType = data.getUint8(1);
CONFIG.msp_version = data.getUint8(2);
CONFIG.capability = data.getUint32(3, true);
break;
case MSPCodes.MSP_STATUS:
console.log('Using deprecated msp command: MSP_STATUS');
CONFIG.cycleTime = data.getUint16(0, true);
@ -293,14 +284,6 @@ var mspHelper = (function (gui) {
RC_tuning.manual_pitch_rate = data.getUint8(offset++);
RC_tuning.manual_yaw_rate = data.getUint8(offset++);
break;
case MSPCodes.MSP_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 3); i++, needle += 3) {
PIDs[i][0] = data.getUint8(needle);
PIDs[i][1] = data.getUint8(needle + 1);
PIDs[i][2] = data.getUint8(needle + 2);
}
break;
case MSPCodes.MSP2_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
@ -640,9 +623,6 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_SET_RAW_GPS:
break;
case MSPCodes.MSP_SET_PID:
console.log('PID settings saved');
break;
case MSPCodes.MSP2_SET_PID:
console.log('PID settings saved');
break;
@ -735,21 +715,6 @@ var mspHelper = (function (gui) {
console.log('RCMAP saved');
break;
case MSPCodes.MSP_BF_CONFIG:
BF_CONFIG.mixerConfiguration = data.getUint8(0);
BF_CONFIG.features = data.getUint32(1, true);
BF_CONFIG.serialrx_type = data.getUint8(5);
BF_CONFIG.board_align_roll = data.getInt16(6, true); // -180 - 360
BF_CONFIG.board_align_pitch = data.getInt16(8, true); // -180 - 360
BF_CONFIG.board_align_yaw = data.getInt16(10, true); // -180 - 360
BF_CONFIG.currentscale = data.getInt16(12, true);
BF_CONFIG.currentoffset = data.getInt16(14, true);
break;
case MSPCodes.MSP_SET_BF_CONFIG:
console.log('BF_CONFIG saved');
break;
case MSPCodes.MSP_BOARD_ALIGNMENT:
BOARD_ALIGNMENT.roll = data.getInt16(0, true); // -180 - 360
BOARD_ALIGNMENT.pitch = data.getInt16(2, true); // -180 - 360
@ -771,6 +736,14 @@ var mspHelper = (function (gui) {
console.log('MSP_SET_CURRENT_METER_CONFIG saved');
break;
case MSPCodes.MSP_FEATURE:
FEATURES = data.getUint32(0, true);
break;
case MSPCodes.MSP_SET_FEATURE:
console.log('MSP_SET_FEATURE saved');
break;
case MSPCodes.MSP_SET_REBOOT:
console.log('Reboot request accepted');
break;
@ -1561,6 +1534,13 @@ var mspHelper = (function (gui) {
switch (code) {
case MSPCodes.MSP_SET_FEATURE:
buffer.push(specificByte(FEATURES, 0));
buffer.push(specificByte(FEATURES, 1));
buffer.push(specificByte(FEATURES, 2));
buffer.push(specificByte(FEATURES, 3));
break;
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 1));
@ -1580,24 +1560,6 @@ var mspHelper = (function (gui) {
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 1));
break;
case MSPCodes.MSP_SET_BF_CONFIG:
buffer.push(BF_CONFIG.mixerConfiguration);
buffer.push(specificByte(BF_CONFIG.features, 0));
buffer.push(specificByte(BF_CONFIG.features, 1));
buffer.push(specificByte(BF_CONFIG.features, 2));
buffer.push(specificByte(BF_CONFIG.features, 3));
buffer.push(BF_CONFIG.serialrx_type);
buffer.push(specificByte(BF_CONFIG.board_align_roll, 0));
buffer.push(specificByte(BF_CONFIG.board_align_roll, 1));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 0));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 1));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 0));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 1));
buffer.push(lowByte(BF_CONFIG.currentscale));
buffer.push(highByte(BF_CONFIG.currentscale));
buffer.push(lowByte(BF_CONFIG.currentoffset));
buffer.push(highByte(BF_CONFIG.currentoffset));
break;
case MSPCodes.MSP_SET_VTX_CONFIG:
if (VTX_CONFIG.band > 0) {
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
@ -1610,13 +1572,6 @@ var mspHelper = (function (gui) {
buffer.push(0);
buffer.push(VTX_CONFIG.low_power_disarm);
break;
case MSPCodes.MSP_SET_PID:
for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
buffer.push(parseInt(PIDs[i][1]));
buffer.push(parseInt(PIDs[i][2]));
}
break;
case MSPCodes.MSP2_SET_PID:
for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
@ -2755,14 +2710,6 @@ var mspHelper = (function (gui) {
* Basic sending methods used for chaining purposes
*/
/**
* @deprecated
* @param callback
*/
self.loadMspIdent = function (callback) {
MSP.send_message(MSPCodes.MSP_IDENT, false, false, callback);
};
self.loadINAVPidConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
};
@ -2803,8 +2750,8 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
};
self.loadBfConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, callback);
self.loadFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, callback);
};
self.loadBoardAlignment = function (callback) {
@ -2915,8 +2862,8 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback);
};
self.saveBfConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, callback);
self.saveFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_FEATURE, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE), false, callback);
};
self.saveCurrentMeterConfig = function (callback) {

@ -1,4 +1,4 @@
/*global chrome,GUI,FC_CONFIG,$,mspHelper,googleAnalytics,ADVANCED_CONFIG,VTX_CONFIG,CONFIG,MSPChainerClass,BOARD_ALIGNMENT,TABS*/
/*global chrome,GUI,FC_CONFIG,$,mspHelper,googleAnalytics,ADVANCED_CONFIG,VTX_CONFIG,CONFIG,MSPChainerClass,BOARD_ALIGNMENT,TABS,MISC*/
'use strict';
TABS.configuration = {};
@ -30,7 +30,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var loadChainer = new MSPChainerClass();
var loadChain = [
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.loadArmingConfig,
mspHelper.loadLoopTime,
mspHelper.load3dConfig,
@ -52,7 +52,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var saveChainer = new MSPChainerClass();
var saveChain = [
mspHelper.saveBfConfig,
mspHelper.save3dConfig,
mspHelper.saveSensorAlignment,
mspHelper.saveAccTrim,
@ -137,7 +136,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
});
}
helper.features.updateUI($('.tab-configuration'), BF_CONFIG.features);
helper.features.updateUI($('.tab-configuration'), FEATURES);
// translate to user-selected language
localize();
@ -329,13 +328,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
craftName = $('input[name="craft_name"]').val();
if (FC.isFeatureEnabled('GPS', features)) {
googleAnalytics.sendEvent('Setting', 'GpsProtocol', gpsProtocols[MISC.gps_type]);
googleAnalytics.sendEvent('Setting', 'GpsSbas', gpsSbas[MISC.gps_ubx_sbas]);
}
googleAnalytics.sendEvent('Setting', 'GPSEnabled', FC.isFeatureEnabled('GPS', features) ? "true" : "false");
googleAnalytics.sendEvent('Setting', 'Looptime', FC_CONFIG.loopTime);
googleAnalytics.sendEvent('Setting', 'I2CSpeed', $('#i2c_speed').children("option:selected").text());

@ -14,14 +14,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_html);
}
/* function load_config() {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
}
function load_misc() {
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
}*/
function load_html() {
GUI.load("./tabs/failsafe.html", Settings.processHtml(function() {
GUI.simpleBind();
@ -150,80 +142,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect($('.tab_failsafe a'));
}
/*function process_html() {
// generate labels for assigned aux modes
var element;
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
$('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay);
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
// Alternate, minimum distance failsafe procedure
GUI.fillSelect($failsafeMinDistanceProcedure, FC.getFailsafeProcedure(), FAILSAFE_CONFIG.failsafe_min_distance_procedure);
$failsafeMinDistanceProcedure.val(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
$failsafeMinDistanceProcedure.change(function () {
FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val();
});
$('a.save').click(function () {
FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val());
FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val());
FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val());
FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val());
if ($('input[id="land"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 0;
} else if ($('input[id="drop"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 1;
} else if ($('input[id="rth"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 2;
} else if ($('input[id="nothing"]').is(':checked')) {
FAILSAFE_CONFIG.failsafe_procedure = 3;
}
function save_failssafe_config() {
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_bf_config);
}
function save_bf_config() {
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
}
function save_to_eeprom() {
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
}
function reboot() {
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
});
}
function reinitialize() {
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect($('.tab_failsafe a'));
}
save_failssafe_config();
});
GUI.content_ready(callback);
}*/
};
TABS.failsafe.cleanup = function (callback) {

@ -12,7 +12,7 @@ TABS.gps.initialize = function (callback) {
var loadChainer = new MSPChainerClass();
var loadChain = [
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.loadMiscV2
];
@ -23,7 +23,6 @@ TABS.gps.initialize = function (callback) {
var saveChainer = new MSPChainerClass();
var saveChain = [
mspHelper.saveBfConfig,
mspHelper.saveMiscV2,
saveSettings,
mspHelper.saveToEeprom
@ -64,7 +63,7 @@ TABS.gps.initialize = function (callback) {
var features = FC.getFeatures();
helper.features.updateUI($('.tab-gps'), BF_CONFIG.features);
helper.features.updateUI($('.tab-gps'), FEATURES);
// generate GPS
var gpsProtocols = FC.getGpsProtocols();

@ -1,4 +1,4 @@
/*global $,MSP,MSPCodes,BF_CONFIG,TABS,GUI,CONFIGURATOR,helper,mspHelper,nwdialog,SDCARD,chrome*/
/*global $,MSP,MSPCodes,TABS,GUI,CONFIGURATOR,helper,mspHelper,nwdialog,SDCARD,chrome*/
'use strict';
var
@ -17,7 +17,7 @@ TABS.onboard_logging.initialize = function (callback) {
}
if (CONFIGURATOR.connectionValid) {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() {
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, function() {
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
MSP.send_message(MSPCodes.MSP2_BLACKBOX_CONFIG, false, false, load_html);
@ -59,7 +59,7 @@ TABS.onboard_logging.initialize = function (callback) {
dataflashPresent = DATAFLASH.totalSize > 0,
blackboxSupport = false;
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(BF_CONFIG.features, 19)) {
if ((BLACKBOX.supported || DATAFLASH.supported) && bit_check(FEATURES, 19)) {
blackboxSupport = true;
}

@ -1,4 +1,4 @@
/*global helper,MSP,MSPChainerClass,googleAnalytics,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM_MULTIROTOR,BF_CONFIG,PLATFORM_TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
/*global helper,MSP,MSPChainerClass,googleAnalytics,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM_MULTIROTOR,PLATFORM_TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
'use strict';
TABS.outputs = {
@ -24,7 +24,7 @@ TABS.outputs.initialize = function (callback) {
loadChainer.setChain([
mspHelper.loadMiscV2,
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.load3dConfig,
mspHelper.loadMotors,
mspHelper.loadMotorMixRules,
@ -46,7 +46,6 @@ TABS.outputs.initialize = function (callback) {
saveSettings,
mspHelper.sendServoConfigurations,
mspHelper.saveAdvancedConfig,
mspHelper.saveBfConfig,
mspHelper.saveMiscV2,
mspHelper.saveToEeprom
]);
@ -65,7 +64,7 @@ TABS.outputs.initialize = function (callback) {
function onLoad() {
self.feature3DEnabled = bit_check(BF_CONFIG.features, 12);
self.feature3DEnabled = bit_check(FEATURES, 12);
process_motors();
process_servos();
@ -193,7 +192,7 @@ TABS.outputs.initialize = function (callback) {
$('#servo-rate-container').show();
helper.features.updateUI($('.tab-motors'), BF_CONFIG.features);
helper.features.updateUI($('.tab-motors'), FEATURES);
GUI.simpleBind();
let $reversibleMotorCheckbox = $('#feature-12');

@ -15,7 +15,7 @@ TABS.pid_tuning.initialize = function (callback) {
mspHelper.loadINAVPidConfig,
mspHelper.loadPidAdvanced,
mspHelper.loadFilterConfig,
mspHelper.loadBfConfig
mspHelper.loadFeatures
];
loadChain.push(mspHelper.loadRateProfileData);
@ -101,7 +101,7 @@ TABS.pid_tuning.initialize = function (callback) {
if (have_sensor(sensors_detected, 'mag')) {
$('#pid_mag').show();
}
if (bit_check(BF_CONFIG.features, 7)) { //This will need to be reworked to remove BF_CONFIG reference eventually
if (bit_check(FEATURES, 7)) {
$('#pid_gps').show();
}
if (have_sensor(sensors_detected, 'sonar')) {
@ -132,7 +132,7 @@ TABS.pid_tuning.initialize = function (callback) {
}
helper.tabs.init($('.tab-pid_tuning'));
helper.features.updateUI($('.tab-pid_tuning'), BF_CONFIG.features);
helper.features.updateUI($('.tab-pid_tuning'), FEATURES);
hideUnusedPids(CONFIG.activeSensors);

@ -1,4 +1,4 @@
/*global $,chrome,FC,helper,mspHelper,MIXER_CONFIG,BF_CONFIG*/
/*global $,chrome,FC,helper,mspHelper,MIXER_CONFIG*/
'use strict';
TABS.setup = {
@ -22,12 +22,12 @@ TABS.setup.initialize = function (callback) {
var loadChainer = new MSPChainerClass();
var loadChain = [
mspHelper.loadBfConfig,
mspHelper.loadFeatures,
mspHelper.queryFcStatus,
mspHelper.loadMixerConfig
mspHelper.loadMixerConfig,
mspHelper.loadMiscV2
];
loadChain.push(mspHelper.loadMiscV2);
loadChainer.setChain(loadChain);
loadChainer.setExitPoint(load_html);
loadChainer.execute();

Loading…
Cancel
Save