mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-17 05:15:21 +03:00
Some cleanup of MSP code
This commit is contained in:
parent
ce9ade16e5
commit
2ffefb065f
11 changed files with 29 additions and 81 deletions
|
@ -705,10 +705,6 @@ function configuration_restore(callback) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
function upload_servo_mix_rules() {
|
|
||||||
MSP.sendServoMixRules(upload_servo_configuration);
|
|
||||||
}
|
|
||||||
|
|
||||||
function upload_servo_configuration() {
|
function upload_servo_configuration() {
|
||||||
MSP.sendServoConfigurations(upload_mode_ranges);
|
MSP.sendServoConfigurations(upload_mode_ranges);
|
||||||
}
|
}
|
||||||
|
@ -825,9 +821,8 @@ 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(MSP_codes.MSP_STATUS, false, false, function() {
|
||||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||||
|
|
||||||
if (callback) callback();
|
if (callback) callback();
|
||||||
});
|
});
|
||||||
}, 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
|
||||||
|
|
|
@ -47,7 +47,7 @@ var Model = function (wrapper, canvas) {
|
||||||
this.renderer.setSize(this.wrapper.width() * 2, this.wrapper.height() * 2);
|
this.renderer.setSize(this.wrapper.width() * 2, this.wrapper.height() * 2);
|
||||||
|
|
||||||
// load the model including materials
|
// load the model including materials
|
||||||
var model_file = useWebGLRenderer ? mixerList[CONFIG.multiType - 1].model : 'fallback';
|
var model_file = useWebGLRenderer ? mixerList[BF_CONFIG.mixerConfiguration - 1].model : 'fallback';
|
||||||
|
|
||||||
// Temporary workaround for 'custom' model until akfreak's custom model is merged.
|
// Temporary workaround for 'custom' model until akfreak's custom model is merged.
|
||||||
if (model_file == 'custom') { model_file = 'fallback'; }
|
if (model_file == 'custom') { model_file = 'fallback'; }
|
||||||
|
|
72
js/msp.js
72
js/msp.js
|
@ -63,7 +63,7 @@ var MSP_codes = {
|
||||||
MSP_SET_SPECIAL_PARAMETERS: 99,
|
MSP_SET_SPECIAL_PARAMETERS: 99,
|
||||||
|
|
||||||
// Multiwii MSP commands
|
// Multiwii MSP commands
|
||||||
MSP_IDENT: 100,
|
MSP_IDENT: 100, // Not used
|
||||||
MSP_STATUS: 101,
|
MSP_STATUS: 101,
|
||||||
MSP_RAW_IMU: 102,
|
MSP_RAW_IMU: 102,
|
||||||
MSP_SERVO: 103,
|
MSP_SERVO: 103,
|
||||||
|
@ -76,12 +76,12 @@ var MSP_codes = {
|
||||||
MSP_ANALOG: 110,
|
MSP_ANALOG: 110,
|
||||||
MSP_RC_TUNING: 111,
|
MSP_RC_TUNING: 111,
|
||||||
MSP_PID: 112,
|
MSP_PID: 112,
|
||||||
MSP_BOX: 113,
|
MSP_BOX: 113, // Not used
|
||||||
MSP_MISC: 114,
|
MSP_MISC: 114,
|
||||||
MSP_MOTOR_PINS: 115,
|
MSP_MOTOR_PINS: 115, // Not used
|
||||||
MSP_BOXNAMES: 116,
|
MSP_BOXNAMES: 116,
|
||||||
MSP_PIDNAMES: 117,
|
MSP_PIDNAMES: 117,
|
||||||
MSP_WP: 118,
|
MSP_WP: 118, // Not used
|
||||||
MSP_BOXIDS: 119,
|
MSP_BOXIDS: 119,
|
||||||
MSP_SERVO_CONFIGURATIONS: 120,
|
MSP_SERVO_CONFIGURATIONS: 120,
|
||||||
MSP_3D: 124,
|
MSP_3D: 124,
|
||||||
|
@ -91,7 +91,7 @@ var MSP_codes = {
|
||||||
MSP_STATUS_EX: 150,
|
MSP_STATUS_EX: 150,
|
||||||
|
|
||||||
MSP_SET_RAW_RC: 200,
|
MSP_SET_RAW_RC: 200,
|
||||||
MSP_SET_RAW_GPS: 201,
|
MSP_SET_RAW_GPS: 201, // Not used
|
||||||
MSP_SET_PID: 202,
|
MSP_SET_PID: 202,
|
||||||
MSP_SET_BOX: 203,
|
MSP_SET_BOX: 203,
|
||||||
MSP_SET_RC_TUNING: 204,
|
MSP_SET_RC_TUNING: 204,
|
||||||
|
@ -99,9 +99,9 @@ var MSP_codes = {
|
||||||
MSP_MAG_CALIBRATION: 206,
|
MSP_MAG_CALIBRATION: 206,
|
||||||
MSP_SET_MISC: 207,
|
MSP_SET_MISC: 207,
|
||||||
MSP_RESET_CONF: 208,
|
MSP_RESET_CONF: 208,
|
||||||
MSP_SET_WP: 209,
|
MSP_SET_WP: 209, // Not used
|
||||||
MSP_SELECT_SETTING: 210,
|
MSP_SELECT_SETTING: 210,
|
||||||
MSP_SET_HEAD: 211,
|
MSP_SET_HEAD: 211, // Not used
|
||||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||||
MSP_SET_MOTOR: 214,
|
MSP_SET_MOTOR: 214,
|
||||||
MSP_SET_3D: 217,
|
MSP_SET_3D: 217,
|
||||||
|
@ -110,14 +110,13 @@ var MSP_codes = {
|
||||||
MSP_SET_SENSOR_ALIGNMENT: 220,
|
MSP_SET_SENSOR_ALIGNMENT: 220,
|
||||||
MSP_SET_LED_STRIP_MODECOLOR:221,
|
MSP_SET_LED_STRIP_MODECOLOR:221,
|
||||||
|
|
||||||
// MSP_BIND: 240,
|
|
||||||
|
|
||||||
MSP_SERVO_MIX_RULES: 241,
|
MSP_SERVO_MIX_RULES: 241,
|
||||||
MSP_SET_SERVO_MIX_RULE: 242,
|
MSP_SET_SERVO_MIX_RULE: 242, // Not used
|
||||||
|
|
||||||
MSP_EEPROM_WRITE: 250,
|
MSP_EEPROM_WRITE: 250,
|
||||||
|
|
||||||
MSP_DEBUGMSG: 253,
|
MSP_DEBUGMSG: 253, // Not used
|
||||||
MSP_DEBUG: 254,
|
MSP_DEBUG: 254,
|
||||||
|
|
||||||
// Additional baseflight commands that are not compatible with MultiWii
|
// Additional baseflight commands that are not compatible with MultiWii
|
||||||
|
@ -132,7 +131,7 @@ var MSP_codes = {
|
||||||
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
|
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
|
||||||
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
|
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
|
||||||
MSP_SET_REBOOT: 68, // reboot settings
|
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 // Not used
|
||||||
};
|
};
|
||||||
|
|
||||||
var MSP = {
|
var MSP = {
|
||||||
|
@ -269,14 +268,6 @@ var MSP = {
|
||||||
var data = new DataView(message_buffer, 0); // DataView (allowing us to view arrayBuffer as struct/union)
|
var data = new DataView(message_buffer, 0); // DataView (allowing us to view arrayBuffer as struct/union)
|
||||||
|
|
||||||
if (!this.unsupported) switch (code) {
|
if (!this.unsupported) switch (code) {
|
||||||
case MSP_codes.MSP_IDENT:
|
|
||||||
console.log('Using deprecated msp command: MSP_IDENT');
|
|
||||||
// Deprecated
|
|
||||||
CONFIG.version = parseFloat((data.getUint8(0) / 100).toFixed(2));
|
|
||||||
CONFIG.multiType = data.getUint8(1);
|
|
||||||
CONFIG.msp_version = data.getUint8(2);
|
|
||||||
CONFIG.capability = data.getUint32(3, 1);
|
|
||||||
break;
|
|
||||||
case MSP_codes.MSP_STATUS:
|
case MSP_codes.MSP_STATUS:
|
||||||
CONFIG.cycleTime = data.getUint16(0, 1);
|
CONFIG.cycleTime = data.getUint16(0, 1);
|
||||||
CONFIG.i2cError = data.getUint16(2, 1);
|
CONFIG.i2cError = data.getUint16(2, 1);
|
||||||
|
@ -448,17 +439,7 @@ var MSP = {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
// Disabled, cleanflight does not use MSP_BOX.
|
|
||||||
/*
|
|
||||||
case MSP_codes.MSP_BOX:
|
|
||||||
AUX_CONFIG_values = []; // empty the array as new data is coming in
|
|
||||||
|
|
||||||
// fill in current data
|
|
||||||
for (var i = 0; i < data.byteLength; i += 2) { // + 2 because uint16_t = 2 bytes
|
|
||||||
AUX_CONFIG_values.push(data.getUint16(i, 1));
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
*/
|
|
||||||
case MSP_codes.MSP_ARMING_CONFIG:
|
case MSP_codes.MSP_ARMING_CONFIG:
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
ARMING_CONFIG.auto_disarm_delay = data.getUint8(0, 1);
|
ARMING_CONFIG.auto_disarm_delay = data.getUint8(0, 1);
|
||||||
|
@ -511,9 +492,6 @@ var MSP = {
|
||||||
_3D.deadband3d_throttle = data.getUint16(offset, 1);
|
_3D.deadband3d_throttle = data.getUint16(offset, 1);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_MOTOR_PINS:
|
|
||||||
console.log(data);
|
|
||||||
break;
|
|
||||||
case MSP_codes.MSP_BOXNAMES:
|
case MSP_codes.MSP_BOXNAMES:
|
||||||
AUX_CONFIG = []; // empty the array as new data is coming in
|
AUX_CONFIG = []; // empty the array as new data is coming in
|
||||||
|
|
||||||
|
@ -544,9 +522,6 @@ var MSP = {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_WP:
|
|
||||||
console.log(data);
|
|
||||||
break;
|
|
||||||
case MSP_codes.MSP_BOXIDS:
|
case MSP_codes.MSP_BOXIDS:
|
||||||
AUX_CONFIG_IDS = []; // empty the array as new data is coming in
|
AUX_CONFIG_IDS = []; // empty the array as new data is coming in
|
||||||
|
|
||||||
|
@ -623,8 +598,6 @@ var MSP = {
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_RAW_RC:
|
case MSP_codes.MSP_SET_RAW_RC:
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_RAW_GPS:
|
|
||||||
break;
|
|
||||||
case MSP_codes.MSP_SET_PID:
|
case MSP_codes.MSP_SET_PID:
|
||||||
console.log('PID settings saved');
|
console.log('PID settings saved');
|
||||||
break;
|
break;
|
||||||
|
@ -657,8 +630,6 @@ var MSP = {
|
||||||
case MSP_codes.MSP_EEPROM_WRITE:
|
case MSP_codes.MSP_EEPROM_WRITE:
|
||||||
console.log('Settings Saved in EEPROM');
|
console.log('Settings Saved in EEPROM');
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_DEBUGMSG:
|
|
||||||
break;
|
|
||||||
case MSP_codes.MSP_DEBUG:
|
case MSP_codes.MSP_DEBUG:
|
||||||
for (var i = 0; i < 4; i++)
|
for (var i = 0; i < 4; i++)
|
||||||
SENSOR_DATA.debug[i] = data.getInt16((2 * i), 1);
|
SENSOR_DATA.debug[i] = data.getInt16((2 * i), 1);
|
||||||
|
@ -1725,6 +1696,11 @@ MSP.crunch = function (code) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSP_codes.MSP_SET_BLACKBOX_CONFIG:
|
||||||
|
buffer.push(BLACKBOX.blackboxDevice);
|
||||||
|
buffer.push(BLACKBOX.blackboxRateNum);
|
||||||
|
buffer.push(BLACKBOX.blackboxRateDenom);
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return false;
|
return false;
|
||||||
|
@ -1749,19 +1725,6 @@ MSP.setRawRx = function(channels) {
|
||||||
MSP.send_message(MSP_codes.MSP_SET_RAW_RC, buffer, false);
|
MSP.send_message(MSP_codes.MSP_SET_RAW_RC, buffer, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.sendBlackboxConfiguration = function(onDataCallback) {
|
|
||||||
var
|
|
||||||
message = [
|
|
||||||
BLACKBOX.blackboxDevice & 0xFF,
|
|
||||||
BLACKBOX.blackboxRateNum & 0xFF,
|
|
||||||
BLACKBOX.blackboxRateDenom & 0xFF
|
|
||||||
];
|
|
||||||
|
|
||||||
MSP.send_message(MSP_codes.MSP_SET_BLACKBOX_CONFIG, message, false, function(response) {
|
|
||||||
onDataCallback();
|
|
||||||
});
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Send a request to read a block of data from the dataflash at the given address and pass that address and a dataview
|
* Send a request to read a block of data from the dataflash at the given address and pass that address and a dataview
|
||||||
* of the returned data to the given callback (or null for the data if an error occured).
|
* of the returned data to the given callback (or null for the data if an error occured).
|
||||||
|
@ -1784,11 +1747,6 @@ MSP.dataflashRead = function(address, onDataCallback) {
|
||||||
});
|
});
|
||||||
};
|
};
|
||||||
|
|
||||||
MSP.sendServoMixRules = function(onCompleteCallback) {
|
|
||||||
// TODO implement
|
|
||||||
onCompleteCallback();
|
|
||||||
};
|
|
||||||
|
|
||||||
MSP.sendServoConfigurations = function(onCompleteCallback) {
|
MSP.sendServoConfigurations = function(onCompleteCallback) {
|
||||||
var nextFunction = send_next_servo_configuration;
|
var nextFunction = send_next_servo_configuration;
|
||||||
|
|
||||||
|
|
|
@ -174,7 +174,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(MSP_codes.MSP_STATUS, 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();
|
||||||
|
|
|
@ -110,7 +110,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);
|
load_config();
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
var mixer_list_e = $('select.mixerList');
|
var mixer_list_e = $('select.mixerList');
|
||||||
|
@ -612,7 +612,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(MSP_codes.MSP_STATUS, 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());
|
||||||
});
|
});
|
||||||
|
|
|
@ -57,9 +57,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);
|
load_rx_config();
|
||||||
} else {
|
} else {
|
||||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_config);
|
load_config();
|
||||||
}
|
}
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
|
@ -333,7 +333,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(MSP_codes.MSP_STATUS, 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());
|
||||||
});
|
});
|
||||||
|
|
|
@ -185,7 +185,7 @@ TABS.motors.initialize = function (callback) {
|
||||||
$('#motorsEnableTestMode').prop('checked', false);
|
$('#motorsEnableTestMode').prop('checked', false);
|
||||||
$('#motorsEnableTestMode').prop('disabled', true);
|
$('#motorsEnableTestMode').prop('disabled', true);
|
||||||
|
|
||||||
update_model(CONFIG.multiType);
|
update_model(BF_CONFIG.mixerConfiguration);
|
||||||
|
|
||||||
// Always start with default/empty sensor data array, clean slate all
|
// Always start with default/empty sensor data array, clean slate all
|
||||||
initSensorData();
|
initSensorData();
|
||||||
|
|
|
@ -73,7 +73,7 @@ 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(MSP_codes.MSP_STATUS, 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());
|
||||||
});
|
});
|
||||||
|
@ -135,7 +135,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
||||||
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);
|
MSP.send_message(MSP_codes.MSP_SET_BLACKBOX_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BLACKBOX_CONFIG), false, false, save_to_eeprom);
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -275,7 +275,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(MSP_codes.MSP_STATUS, 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());
|
||||||
});
|
});
|
||||||
|
|
|
@ -37,8 +37,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
function load_html() {
|
function load_html() {
|
||||||
$('#content').load("./tabs/servos.html", process_html);
|
$('#content').load("./tabs/servos.html", process_html);
|
||||||
}
|
}
|
||||||
|
get_servo_configurations();
|
||||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_servo_configurations);
|
|
||||||
|
|
||||||
function update_ui() {
|
function update_ui() {
|
||||||
|
|
||||||
|
|
|
@ -12,11 +12,7 @@ TABS.setup.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_status() {
|
function load_status() {
|
||||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_ident);
|
MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_config);
|
||||||
}
|
|
||||||
|
|
||||||
function load_ident() {
|
|
||||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, load_config);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_config() {
|
function load_config() {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue