Separation of MSP code into protocol and config parts, will ease further development and readability
parent
3679111878
commit
96115be10e
|
@ -12,36 +12,36 @@ function configuration_backup(callback) {
|
|||
};
|
||||
|
||||
var profileSpecificData = [
|
||||
MSP_codes.MSP_PID_CONTROLLER,
|
||||
MSP_codes.MSP_PID,
|
||||
MSP_codes.MSP_RC_TUNING,
|
||||
MSP_codes.MSP_ACC_TRIM,
|
||||
MSP_codes.MSP_SERVO_CONFIGURATIONS,
|
||||
MSP_codes.MSP_MODE_RANGES,
|
||||
MSP_codes.MSP_ADJUSTMENT_RANGES
|
||||
MSPCodes.MSP_PID_CONTROLLER,
|
||||
MSPCodes.MSP_PID,
|
||||
MSPCodes.MSP_RC_TUNING,
|
||||
MSPCodes.MSP_ACC_TRIM,
|
||||
MSPCodes.MSP_SERVO_CONFIGURATIONS,
|
||||
MSPCodes.MSP_MODE_RANGES,
|
||||
MSPCodes.MSP_ADJUSTMENT_RANGES
|
||||
];
|
||||
|
||||
function update_profile_specific_data_list() {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
profileSpecificData.push(MSP_codes.MSP_CHANNEL_FORWARDING);
|
||||
profileSpecificData.push(MSPCodes.MSP_CHANNEL_FORWARDING);
|
||||
} else {
|
||||
profileSpecificData.push(MSP_codes.MSP_SERVO_MIX_RULES);
|
||||
profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
profileSpecificData.push(MSP_codes.MSP_RC_DEADBAND);
|
||||
profileSpecificData.push(MSPCodes.MSP_RC_DEADBAND);
|
||||
}
|
||||
}
|
||||
|
||||
update_profile_specific_data_list();
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
|
||||
activeProfile = CONFIG.profile;
|
||||
select_profile();
|
||||
});
|
||||
|
||||
function select_profile() {
|
||||
if (activeProfile > 0) {
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [0], false, fetch_specific_data);
|
||||
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [0], false, fetch_specific_data);
|
||||
} else {
|
||||
fetch_specific_data();
|
||||
}
|
||||
|
@ -76,11 +76,11 @@ function configuration_backup(callback) {
|
|||
codeKey = 0;
|
||||
fetchingProfile++;
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [fetchingProfile], false, fetch_specific_data_item);
|
||||
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [fetchingProfile], false, fetch_specific_data_item);
|
||||
}
|
||||
});
|
||||
} else {
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [activeProfile], false, fetch_unique_data);
|
||||
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [activeProfile], false, fetch_unique_data);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -89,30 +89,30 @@ function configuration_backup(callback) {
|
|||
}
|
||||
|
||||
var uniqueData = [
|
||||
MSP_codes.MSP_MISC,
|
||||
MSP_codes.MSP_RX_MAP,
|
||||
MSP_codes.MSP_BF_CONFIG,
|
||||
MSP_codes.MSP_CF_SERIAL_CONFIG,
|
||||
MSP_codes.MSP_LED_STRIP_CONFIG,
|
||||
MSP_codes.MSP_LED_COLORS
|
||||
MSPCodes.MSP_MISC,
|
||||
MSPCodes.MSP_RX_MAP,
|
||||
MSPCodes.MSP_BF_CONFIG,
|
||||
MSPCodes.MSP_CF_SERIAL_CONFIG,
|
||||
MSPCodes.MSP_LED_STRIP_CONFIG,
|
||||
MSPCodes.MSP_LED_COLORS
|
||||
];
|
||||
|
||||
function update_unique_data_list() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_LOOP_TIME);
|
||||
uniqueData.push(MSP_codes.MSP_ARMING_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_LOOP_TIME);
|
||||
uniqueData.push(MSPCodes.MSP_ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_3D);
|
||||
uniqueData.push(MSPCodes.MSP_3D);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSP_codes.MSP_RX_CONFIG);
|
||||
uniqueData.push(MSP_codes.MSP_FAILSAFE_CONFIG);
|
||||
uniqueData.push(MSP_codes.MSP_RXFAIL_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSPCodes.MSP_RX_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_FAILSAFE_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_RXFAIL_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_LED_STRIP_MODECOLOR);
|
||||
uniqueData.push(MSPCodes.MSP_LED_STRIP_MODECOLOR);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -641,24 +641,24 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
var profileSpecificData = [
|
||||
MSP_codes.MSP_SET_PID_CONTROLLER,
|
||||
MSP_codes.MSP_SET_PID,
|
||||
MSP_codes.MSP_SET_RC_TUNING,
|
||||
MSP_codes.MSP_SET_ACC_TRIM
|
||||
MSPCodes.MSP_SET_PID_CONTROLLER,
|
||||
MSPCodes.MSP_SET_PID,
|
||||
MSPCodes.MSP_SET_RC_TUNING,
|
||||
MSPCodes.MSP_SET_ACC_TRIM
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
profileSpecificData.push(MSP_codes.MSP_SET_RC_DEADBAND);
|
||||
profileSpecificData.push(MSPCodes.MSP_SET_RC_DEADBAND);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
|
||||
activeProfile = CONFIG.profile;
|
||||
select_profile();
|
||||
});
|
||||
|
||||
function select_profile() {
|
||||
if (activeProfile > 0) {
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [0], false, upload_specific_data);
|
||||
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [0], false, upload_specific_data);
|
||||
} else {
|
||||
upload_specific_data();
|
||||
}
|
||||
|
@ -681,7 +681,7 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function upload_using_specific_commands() {
|
||||
MSP.send_message(profileSpecificData[codeKey], MSP.crunch(profileSpecificData[codeKey]), false, function () {
|
||||
MSP.send_message(profileSpecificData[codeKey], mspHelper.crunch(profileSpecificData[codeKey]), false, function () {
|
||||
codeKey++;
|
||||
|
||||
if (codeKey < profileSpecificData.length) {
|
||||
|
@ -693,12 +693,12 @@ function configuration_restore(callback) {
|
|||
if (savingProfile < numProfiles) {
|
||||
load_objects(savingProfile);
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [savingProfile], false, upload_using_specific_commands);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [savingProfile], false, upload_using_specific_commands);
|
||||
});
|
||||
} else {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [activeProfile], false, upload_unique_data);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [activeProfile], false, upload_unique_data);
|
||||
});
|
||||
}
|
||||
}
|
||||
|
@ -706,15 +706,15 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function upload_servo_configuration() {
|
||||
MSP.sendServoConfigurations(upload_mode_ranges);
|
||||
MspHelper.sendServoConfigurations(upload_mode_ranges);
|
||||
}
|
||||
|
||||
function upload_mode_ranges() {
|
||||
MSP.sendModeRanges(upload_adjustment_ranges);
|
||||
MspHelper.sendModeRanges(upload_adjustment_ranges);
|
||||
}
|
||||
|
||||
function upload_adjustment_ranges() {
|
||||
MSP.sendAdjustmentRanges(upload_using_specific_commands);
|
||||
MspHelper.sendAdjustmentRanges(upload_using_specific_commands);
|
||||
}
|
||||
// start uploading
|
||||
load_objects(0);
|
||||
|
@ -725,24 +725,24 @@ function configuration_restore(callback) {
|
|||
var codeKey = 0;
|
||||
|
||||
var uniqueData = [
|
||||
MSP_codes.MSP_SET_MISC,
|
||||
MSP_codes.MSP_SET_RX_MAP,
|
||||
MSP_codes.MSP_SET_BF_CONFIG,
|
||||
MSP_codes.MSP_SET_CF_SERIAL_CONFIG
|
||||
MSPCodes.MSP_SET_MISC,
|
||||
MSPCodes.MSP_SET_RX_MAP,
|
||||
MSPCodes.MSP_SET_BF_CONFIG,
|
||||
MSPCodes.MSP_SET_CF_SERIAL_CONFIG
|
||||
];
|
||||
|
||||
function update_unique_data_list() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_SET_LOOP_TIME);
|
||||
uniqueData.push(MSP_codes.MSP_SET_ARMING_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_LOOP_TIME);
|
||||
uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_SET_3D);
|
||||
uniqueData.push(MSPCodes.MSP_SET_3D);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
uniqueData.push(MSP_codes.MSP_SET_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG);
|
||||
uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -765,7 +765,7 @@ function configuration_restore(callback) {
|
|||
|
||||
function send_unique_data_item() {
|
||||
if (codeKey < uniqueData.length) {
|
||||
MSP.send_message(uniqueData[codeKey], MSP.crunch(uniqueData[codeKey]), false, function () {
|
||||
MSP.send_message(uniqueData[codeKey], mspHelper.crunch(uniqueData[codeKey]), false, function () {
|
||||
codeKey++;
|
||||
send_unique_data_item();
|
||||
});
|
||||
|
@ -783,37 +783,37 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function send_led_strip_config() {
|
||||
MSP.sendLedStripConfig(send_led_strip_colors);
|
||||
MspHelper.sendLedStripConfig(send_led_strip_colors);
|
||||
}
|
||||
|
||||
function send_led_strip_colors() {
|
||||
MSP.sendLedStripColors(send_led_strip_mode_colors);
|
||||
MspHelper.sendLedStripColors(send_led_strip_mode_colors);
|
||||
}
|
||||
|
||||
function send_led_strip_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
MSP.sendLedStripModeColors(send_rxfail_config);
|
||||
MspHelper.sendLedStripModeColors(send_rxfail_config);
|
||||
else
|
||||
send_rxfail_config();
|
||||
}
|
||||
|
||||
function send_rxfail_config() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.sendRxFailConfig(save_to_eeprom);
|
||||
MspHelper.sendRxFailConfig(save_to_eeprom);
|
||||
} else {
|
||||
save_to_eeprom();
|
||||
}
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
GUI.log(chrome.i18n.getMessage('eeprom_saved_ok'));
|
||||
|
||||
GUI.tab_switch_cleanup(function() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
});
|
||||
}
|
||||
|
||||
|
@ -821,7 +821,7 @@ function configuration_restore(callback) {
|
|||
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
|
||||
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
if (callback) callback();
|
||||
});
|
||||
|
|
|
@ -0,0 +1,130 @@
|
|||
'use strict';
|
||||
|
||||
//MSPCodes needs to be re-integrated inside MSP object
|
||||
var MSPCodes = {
|
||||
MSP_API_VERSION: 1,
|
||||
MSP_FC_VARIANT: 2,
|
||||
MSP_FC_VERSION: 3,
|
||||
MSP_BOARD_INFO: 4,
|
||||
MSP_BUILD_INFO: 5,
|
||||
|
||||
MSP_NAME: 10,
|
||||
MSP_SET_NAME: 11,
|
||||
|
||||
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_RX_MAP: 64,
|
||||
MSP_SET_RX_MAP: 65,
|
||||
MSP_BF_CONFIG: 66,
|
||||
MSP_SET_BF_CONFIG: 67,
|
||||
MSP_SET_REBOOT: 68,
|
||||
MSP_BF_BUILD_INFO: 69, // Not used
|
||||
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_SET_OSD_CONFIG: 85,
|
||||
MSP_OSD_CHAR_READ: 86,
|
||||
MSP_OSD_CHAR_WRITE: 87,
|
||||
MSP_VTX_CONFIG: 88,
|
||||
MSP_SET_VTX_CONFIG: 89,
|
||||
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,
|
||||
MSP_SENSOR_CONFIG: 96,
|
||||
MSP_SET_SENSOR_CONFIG: 97,
|
||||
MSP_SPECIAL_PARAMETERS: 98,
|
||||
MSP_SET_SPECIAL_PARAMETERS: 99,
|
||||
MSP_IDENT: 100, // Not used
|
||||
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, // Not used
|
||||
MSP_MISC: 114,
|
||||
MSP_MOTOR_PINS: 115, // Not used
|
||||
MSP_BOXNAMES: 116,
|
||||
MSP_PIDNAMES: 117,
|
||||
MSP_WP: 118, // Not used
|
||||
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_UID: 160,
|
||||
MSP_GPS_SV_INFO: 164,
|
||||
|
||||
MSP_SET_RAW_RC: 200,
|
||||
MSP_SET_RAW_GPS: 201, // Not used
|
||||
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, // Not used
|
||||
MSP_SELECT_SETTING: 210,
|
||||
MSP_SET_HEAD: 211, // Not used
|
||||
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_SET_ACC_TRIM: 239,
|
||||
MSP_ACC_TRIM: 240,
|
||||
MSP_SERVO_MIX_RULES: 241,
|
||||
MSP_SET_SERVO_MIX_RULE: 242, // Not used
|
||||
|
||||
MSP_EEPROM_WRITE: 250,
|
||||
MSP_DEBUGMSG: 253, // Not used
|
||||
MSP_DEBUG: 254
|
||||
};
|
File diff suppressed because it is too large
Load Diff
|
@ -1,4 +1,5 @@
|
|||
'use strict';
|
||||
var mspHelper;
|
||||
|
||||
$(document).ready(function () {
|
||||
|
||||
|
@ -181,28 +182,31 @@ function onOpen(openInfo) {
|
|||
}, 10000);
|
||||
|
||||
FC.resetState();
|
||||
|
||||
MSP.listen(update_packet_error);
|
||||
mspHelper = new MspHelper();
|
||||
MSP.listen(mspHelper.process_data.bind(mspHelper));
|
||||
|
||||
// request configuration data
|
||||
MSP.send_message(MSP_codes.MSP_API_VERSION, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.apiVersionAccepted)) {
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_FC_VARIANT, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_FC_VARIANT, false, false, function () {
|
||||
if (CONFIG.flightControllerIdentifier === 'BTFL') {
|
||||
MSP.send_message(MSP_codes.MSP_FC_VERSION, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () {
|
||||
|
||||
GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_BUILD_INFO, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_BUILD_INFO, false, false, function () {
|
||||
|
||||
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 () {
|
||||
|
||||
GUI.log(chrome.i18n.getMessage('boardInfoReceived', [CONFIG.boardIdentifier, CONFIG.boardVersion]));
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_UID, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_UID, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
|
||||
|
||||
// continue as usually
|
||||
|
@ -268,9 +272,9 @@ function onConnect() {
|
|||
$('#tabs ul.mode-connected').show();
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
} else {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
||||
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
|
||||
CONFIG.numProfiles = 2;
|
||||
|
@ -281,7 +285,7 @@ function onConnect() {
|
|||
}
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_DATAFLASH_SUMMARY, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false);
|
||||
|
||||
startLiveDataRefreshTimer();
|
||||
}
|
||||
|
@ -461,12 +465,12 @@ function update_live_status() {
|
|||
});
|
||||
|
||||
if (GUI.active_tab != 'cli') {
|
||||
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false);
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1"))
|
||||
MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||
else
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false);
|
||||
MSP.send_message(MSP_codes.MSP_ANALOG, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false);
|
||||
}
|
||||
|
||||
var active = ((Date.now() - MSP.analog_last_received_timestamp) < 300);
|
||||
|
|
|
@ -57,7 +57,9 @@
|
|||
<script type="text/javascript" src="./js/serial_backend.js"></script>
|
||||
<script type="text/javascript" src="./js/data_storage.js"></script>
|
||||
<script type="text/javascript" src="./js/fc.js"></script>
|
||||
<script type="text/javascript" src="./js/msp/MSPCodes.js"></script>
|
||||
<script type="text/javascript" src="./js/msp.js"></script>
|
||||
<script type="text/javascript" src="./js/msp/MSPHelper.js"></script>
|
||||
<script type="text/javascript" src="./js/backup_restore.js"></script>
|
||||
<script type="text/javascript" src="./js/protocols/stm32.js"></script>
|
||||
<script type="text/javascript" src="./js/protocols/stm32usbdfu.js"></script>
|
||||
|
|
4
main.js
4
main.js
|
@ -327,6 +327,10 @@ $(document).ready(function () {
|
|||
});
|
||||
});
|
||||
|
||||
function update_packet_error(caller) {
|
||||
$('span.packet-error').html(caller.packet_error);
|
||||
}
|
||||
|
||||
function microtime() {
|
||||
var now = new Date().getTime() / 1000;
|
||||
|
||||
|
|
|
@ -7,22 +7,22 @@ TABS.adjustments.initialize = function (callback) {
|
|||
GUI.active_tab = 'adjustments';
|
||||
|
||||
function get_adjustment_ranges() {
|
||||
MSP.send_message(MSP_codes.MSP_ADJUSTMENT_RANGES, false, false, get_box_ids);
|
||||
MSP.send_message(MSPCodes.MSP_ADJUSTMENT_RANGES, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
function get_box_ids() {
|
||||
MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||
}
|
||||
|
||||
function load_html() {
|
||||
$('#content').load("./tabs/adjustments.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_adjustment_ranges);
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_adjustment_ranges);
|
||||
|
||||
function addAdjustment(adjustmentIndex, adjustmentRange, auxChannelCount) {
|
||||
|
||||
|
@ -219,10 +219,10 @@ TABS.adjustments.initialize = function (callback) {
|
|||
//
|
||||
// send data to FC
|
||||
//
|
||||
MSP.sendAdjustmentRanges(save_to_eeprom);
|
||||
MspHelper.sendAdjustmentRanges(save_to_eeprom);
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('adjustmentsEepromSaved'));
|
||||
});
|
||||
}
|
||||
|
@ -249,7 +249,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
// data pulling functions used inside interval timer
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui);
|
||||
}
|
||||
|
||||
function update_ui() {
|
||||
|
@ -268,7 +268,7 @@ TABS.adjustments.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function () {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
|
|
@ -7,22 +7,22 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
GUI.active_tab = 'auxiliary';
|
||||
|
||||
function get_mode_ranges() {
|
||||
MSP.send_message(MSP_codes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
function get_box_ids() {
|
||||
MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_html);
|
||||
}
|
||||
|
||||
function load_html() {
|
||||
$('#content').load("./tabs/auxiliary.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||
|
||||
function createMode(modeIndex, modeId) {
|
||||
var modeTemplate = $('#tab-auxiliary-templates .mode');
|
||||
|
@ -212,10 +212,10 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
//
|
||||
// send data to FC
|
||||
//
|
||||
MSP.sendModeRanges(save_to_eeprom);
|
||||
MspHelper.sendModeRanges(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'));
|
||||
});
|
||||
}
|
||||
|
@ -245,7 +245,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
|
||||
// data pulling functions used inside interval timer
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui);
|
||||
}
|
||||
|
||||
function update_ui() {
|
||||
|
@ -280,7 +280,7 @@ TABS.auxiliary.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function () {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
|
|
@ -174,7 +174,7 @@ TABS.cli.read = function (readInfo) {
|
|||
} else {
|
||||
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
if (!GUI.tab_switch_in_progress) {
|
||||
$('#tabs ul.mode-connected .tab_setup a').click();
|
||||
|
|
|
@ -10,34 +10,34 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_serial_config);
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_serial_config);
|
||||
}
|
||||
|
||||
function load_serial_config() {
|
||||
var next_callback = load_rc_map;
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function load_rc_map() {
|
||||
MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_misc);
|
||||
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_misc);
|
||||
}
|
||||
|
||||
function load_misc() {
|
||||
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_acc_trim);
|
||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_acc_trim);
|
||||
}
|
||||
|
||||
function load_acc_trim() {
|
||||
MSP.send_message(MSP_codes.MSP_ACC_TRIM, false, false, load_arming_config);
|
||||
MSP.send_message(MSPCodes.MSP_ACC_TRIM, false, false, load_arming_config);
|
||||
}
|
||||
|
||||
function load_arming_config() {
|
||||
var next_callback = load_loop_time;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_ARMING_CONFIG, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_ARMING_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -46,7 +46,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function load_loop_time() {
|
||||
var next_callback = load_3d;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_LOOP_TIME, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -55,7 +55,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function load_3d() {
|
||||
var next_callback = esc_protocol;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_3D, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -64,7 +64,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function esc_protocol() {
|
||||
var next_callback = sensor_config;
|
||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
MSP.send_message(MSP_codes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -73,7 +73,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function sensor_config() {
|
||||
var next_callback = load_sensor_alignment;
|
||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
MSP.send_message(MSP_codes.MSP_SENSOR_CONFIG, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SENSOR_CONFIG, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -82,7 +82,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function load_sensor_alignment() {
|
||||
var next_callback = load_name;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SENSOR_ALIGNMENT, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SENSOR_ALIGNMENT, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -91,7 +91,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function load_name() {
|
||||
var next_callback = load_html;
|
||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_NAME, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_NAME, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -100,7 +100,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
//Update Analog/Battery Data
|
||||
function load_analog() {
|
||||
MSP.send_message(MSP_codes.MSP_ANALOG, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
|
||||
$('input[name="batteryvoltage"]').val([ANALOG.voltage.toFixed(1)]);
|
||||
$('input[name="batterycurrent"]').val([ANALOG.amperage.toFixed(2)]);
|
||||
});
|
||||
|
@ -511,20 +511,20 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function save_serial_config() {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc);
|
||||
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc);
|
||||
} else {
|
||||
save_misc();
|
||||
}
|
||||
}
|
||||
|
||||
function save_misc() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_3d);
|
||||
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_3d);
|
||||
}
|
||||
|
||||
function save_3d() {
|
||||
var next_callback = save_sensor_alignment;
|
||||
if(semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_3D, MSP.crunch(MSP_codes.MSP_SET_3D), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_3D, mspHelper.crunch(MSPCodes.MSP_SET_3D), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -533,7 +533,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function save_sensor_alignment() {
|
||||
var next_callback = save_esc_protocol;
|
||||
if(semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_SENSOR_ALIGNMENT, MSP.crunch(MSP_codes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -541,26 +541,26 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
function save_esc_protocol() {
|
||||
var next_callback = save_acc_trim;
|
||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADVANCED_CONFIG, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function save_acc_trim() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_ACC_TRIM, MSP.crunch(MSP_codes.MSP_SET_ACC_TRIM), false
|
||||
MSP.send_message(MSPCodes.MSP_SET_ACC_TRIM, mspHelper.crunch(MSPCodes.MSP_SET_ACC_TRIM), false
|
||||
, semver.gte(CONFIG.apiVersion, "1.8.0") ? save_arming_config : save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_arming_config() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_ARMING_CONFIG, MSP.crunch(MSP_codes.MSP_SET_ARMING_CONFIG), false, save_looptime_config);
|
||||
MSP.send_message(MSPCodes.MSP_SET_ARMING_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ARMING_CONFIG), false, save_looptime_config);
|
||||
}
|
||||
|
||||
function save_looptime_config() {
|
||||
var next_callback = save_sensor_config;
|
||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.lt(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
FC_CONFIG.loopTime = PID_ADVANCED_CONFIG.gyro_sync_denom * 125;
|
||||
MSP.send_message(MSP_codes.MSP_SET_LOOP_TIME, MSP.crunch(MSP_codes.MSP_SET_LOOP_TIME), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -572,7 +572,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
SENSOR_CONFIG.acc_hardware = $('input[name="accHardwareSwitch"]').is(':checked')?0:1;
|
||||
SENSOR_CONFIG.baro_hardware = $('input[name="baroHardwareSwitch"]').is(':checked')?0:1;
|
||||
SENSOR_CONFIG.mag_hardware = $('input[name="magHardwareSwitch"]').is(':checked')?0:1
|
||||
MSP.send_message(MSP_codes.MSP_SET_SENSOR_CONFIG, MSP.crunch(MSP_codes.MSP_SET_SENSOR_CONFIG), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_SENSOR_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_CONFIG), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -583,21 +583,21 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
|
||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
CONFIG.name = $.trim($('input[name="vesselName"]').val());
|
||||
MSP.send_message(MSP_codes.MSP_SET_NAME, MSP.crunch(MSP_codes.MSP_SET_NAME), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_NAME, mspHelper.crunch(MSPCodes.MSP_SET_NAME), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||
|
||||
GUI.tab_switch_cleanup(function() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
});
|
||||
}
|
||||
|
||||
|
@ -612,7 +612,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
} else {
|
||||
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
TABS.configuration.initialize(false, $('#content').scrollTop());
|
||||
});
|
||||
|
@ -620,13 +620,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_serial_config);
|
||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_serial_config);
|
||||
|
||||
});
|
||||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
GUI.interval_add('config_load_analog', load_analog, 250, true); // 4 fps
|
||||
GUI.content_ready(callback);
|
||||
|
|
|
@ -10,40 +10,40 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_rx_config() {
|
||||
MSP.send_message(MSP_codes.MSP_RX_CONFIG, false, false, load_failssafe_config);
|
||||
MSP.send_message(MSPCodes.MSP_RX_CONFIG, false, false, load_failssafe_config);
|
||||
}
|
||||
|
||||
function load_failssafe_config() {
|
||||
MSP.send_message(MSP_codes.MSP_FAILSAFE_CONFIG, false, false, load_rxfail_config);
|
||||
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_rxfail_config);
|
||||
}
|
||||
|
||||
function load_rxfail_config() {
|
||||
MSP.send_message(MSP_codes.MSP_RXFAIL_CONFIG, false, false, get_box_names);
|
||||
MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false, get_box_names);
|
||||
}
|
||||
|
||||
function get_box_names() {
|
||||
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
|
||||
}
|
||||
|
||||
function get_mode_ranges() {
|
||||
MSP.send_message(MSP_codes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids);
|
||||
}
|
||||
|
||||
function get_box_ids() {
|
||||
MSP.send_message(MSP_codes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
MSP.send_message(MSPCodes.MSP_BOXIDS, false, false, get_rc_data);
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, load_config);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_config);
|
||||
}
|
||||
|
||||
// BEGIN Support for pre API version 1.15.0
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_misc);
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
|
||||
}
|
||||
|
||||
function load_misc() {
|
||||
MSP.send_message(MSP_codes.MSP_MISC, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
|
||||
}
|
||||
// END (Support for pre API version 1.15.0
|
||||
|
||||
|
@ -293,32 +293,32 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function save_failssafe_config() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_FAILSAFE_CONFIG, MSP.crunch(MSP_codes.MSP_SET_FAILSAFE_CONFIG), false, save_rxfail_config);
|
||||
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_rxfail_config);
|
||||
}
|
||||
|
||||
function save_rxfail_config() {
|
||||
MSP.sendRxFailConfig(save_bf_config);
|
||||
MspHelper.sendRxFailConfig(save_bf_config);
|
||||
}
|
||||
|
||||
function save_bf_config() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
|
||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
|
||||
}
|
||||
|
||||
// BEGIN pre API 1.15.0 save functions
|
||||
function save_misc() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_to_eeprom);
|
||||
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_to_eeprom);
|
||||
}
|
||||
// END pre API 1.15.0 save functions
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||
|
||||
GUI.tab_switch_cleanup(function() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
});
|
||||
}
|
||||
|
||||
|
@ -333,7 +333,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
} else {
|
||||
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
TABS.failsafe.initialize(false, $('#content').scrollTop());
|
||||
});
|
||||
|
@ -342,9 +342,9 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
if(apiVersionGte1_15_0) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_RX_CONFIG, MSP.crunch(MSP_codes.MSP_SET_RX_CONFIG), false, save_failssafe_config);
|
||||
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, save_failssafe_config);
|
||||
} else {
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_misc);
|
||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_misc);
|
||||
}
|
||||
});
|
||||
|
||||
|
@ -353,7 +353,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
|
10
tabs/gps.js
10
tabs/gps.js
|
@ -12,7 +12,7 @@ TABS.gps.initialize = function (callback) {
|
|||
$('#content').load("./tabs/gps.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_html);
|
||||
|
||||
function set_online(){
|
||||
$('#connect').hide();
|
||||
|
@ -31,15 +31,15 @@ TABS.gps.initialize = function (callback) {
|
|||
localize();
|
||||
|
||||
function get_raw_gps_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RAW_GPS, false, false, get_comp_gps_data);
|
||||
MSP.send_message(MSPCodes.MSP_RAW_GPS, false, false, get_comp_gps_data);
|
||||
}
|
||||
|
||||
function get_comp_gps_data() {
|
||||
MSP.send_message(MSP_codes.MSP_COMP_GPS, false, false, get_gpsvinfo_data);
|
||||
MSP.send_message(MSPCodes.MSP_COMP_GPS, false, false, get_gpsvinfo_data);
|
||||
}
|
||||
|
||||
function get_gpsvinfo_data() {
|
||||
MSP.send_message(MSP_codes.MSP_GPS_SV_INFO, false, false, update_ui);
|
||||
MSP.send_message(MSPCodes.MSP_GPS_SV_INFO, false, false, update_ui);
|
||||
}
|
||||
|
||||
function update_ui() {
|
||||
|
@ -105,7 +105,7 @@ TABS.gps.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
|
||||
|
|
|
@ -28,16 +28,16 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_led_config() {
|
||||
MSP.send_message(MSP_codes.MSP_LED_STRIP_CONFIG, false, false, load_led_colors);
|
||||
MSP.send_message(MSPCodes.MSP_LED_STRIP_CONFIG, false, false, load_led_colors);
|
||||
}
|
||||
|
||||
function load_led_colors() {
|
||||
MSP.send_message(MSP_codes.MSP_LED_COLORS, false, false, load_led_mode_colors);
|
||||
MSP.send_message(MSPCodes.MSP_LED_COLORS, false, false, load_led_mode_colors);
|
||||
}
|
||||
|
||||
function load_led_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
MSP.send_message(MSP_codes.MSP_LED_STRIP_MODECOLOR, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_LED_STRIP_MODECOLOR, false, false, load_html);
|
||||
else
|
||||
load_html();
|
||||
}
|
||||
|
@ -541,21 +541,21 @@ TABS.led_strip.initialize = function (callback, scrollPosition) {
|
|||
|
||||
$('a.save').click(function () {
|
||||
|
||||
MSP.sendLedStripConfig(send_led_strip_colors);
|
||||
MspHelper.sendLedStripConfig(send_led_strip_colors);
|
||||
|
||||
function send_led_strip_colors() {
|
||||
MSP.sendLedStripColors(send_led_strip_mode_colors);
|
||||
MspHelper.sendLedStripColors(send_led_strip_mode_colors);
|
||||
}
|
||||
|
||||
function send_led_strip_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
MSP.sendLedStripModeColors(save_to_eeprom);
|
||||
MspHelper.sendLedStripModeColors(save_to_eeprom);
|
||||
else
|
||||
save_to_eeprom();
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('ledStripEepromSaved'));
|
||||
});
|
||||
}
|
||||
|
|
|
@ -15,14 +15,14 @@ TABS.logging.initialize = function (callback) {
|
|||
|
||||
if (CONFIGURATOR.connectionValid) {
|
||||
var get_motor_data = function () {
|
||||
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_html);
|
||||
}
|
||||
|
||||
var load_html = function () {
|
||||
$('#content').load("./tabs/logging.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, get_motor_data);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, get_motor_data);
|
||||
}
|
||||
|
||||
function process_html() {
|
||||
|
@ -60,7 +60,7 @@ TABS.logging.initialize = function (callback) {
|
|||
|
||||
// request new
|
||||
for (var i = 0; i < requested_properties.length; i++, requests++) {
|
||||
MSP.send_message(MSP_codes[requested_properties[i]]);
|
||||
MSP.send_message(MSPCodes[requested_properties[i]]);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -17,18 +17,18 @@ TABS.motors.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function get_arm_status() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_config);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_config);
|
||||
}
|
||||
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_3d);
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_3d);
|
||||
}
|
||||
|
||||
function load_3d() {
|
||||
var next_callback = get_motor_data;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
self.feature3DSupported = true;
|
||||
MSP.send_message(MSP_codes.MSP_3D, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -37,14 +37,14 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
function get_motor_data() {
|
||||
update_arm_status();
|
||||
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_html);
|
||||
}
|
||||
|
||||
function load_html() {
|
||||
$('#content').load("./tabs/motors.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_MISC, false, false, get_arm_status);
|
||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, get_arm_status);
|
||||
|
||||
function update_arm_status() {
|
||||
self.armed = bit_check(CONFIG.mode, 0);
|
||||
|
@ -245,7 +245,7 @@ TABS.motors.initialize = function (callback) {
|
|||
GUI.interval_kill_all(['motor_and_status_pull']);
|
||||
|
||||
GUI.interval_add('IMU_pull', function imu_data_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_RAW_IMU, false, false, update_accel_graph);
|
||||
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_accel_graph);
|
||||
}, rate, true);
|
||||
|
||||
function update_accel_graph() {
|
||||
|
@ -365,7 +365,7 @@ TABS.motors.initialize = function (callback) {
|
|||
buffer_delay = setTimeout(function () {
|
||||
buffer = buffering_set_motor.pop();
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_MOTOR, buffer);
|
||||
MSP.send_message(MSPCodes.MSP_SET_MOTOR, buffer);
|
||||
|
||||
buffering_set_motor = [];
|
||||
buffer_delay = false;
|
||||
|
@ -455,15 +455,15 @@ TABS.motors.initialize = function (callback) {
|
|||
|
||||
function get_status() {
|
||||
// status needed for arming flag
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_motor_data);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_motor_data);
|
||||
}
|
||||
|
||||
function get_motor_data() {
|
||||
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, get_servo_data);
|
||||
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, get_servo_data);
|
||||
}
|
||||
|
||||
function get_servo_data() {
|
||||
MSP.send_message(MSP_codes.MSP_SERVO, false, false, update_ui);
|
||||
MSP.send_message(MSPCodes.MSP_SERVO, false, false, update_ui);
|
||||
}
|
||||
|
||||
var full_block_scale = MISC.maxthrottle - MISC.mincommand;
|
||||
|
|
|
@ -24,13 +24,13 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
return;
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "1.8.0")) {
|
||||
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.11.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SDCARD_SUMMARY, false, false, function() {
|
||||
MSP.send_message(MSP_codes.MSP_BLACKBOX_CONFIG, false, false, function() {
|
||||
MSP.send_message(MSP_codes.MSP_ADVANCED_CONFIG, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_BLACKBOX_CONFIG, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, load_html);
|
||||
});
|
||||
});
|
||||
} else {
|
||||
|
@ -51,14 +51,14 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||
}
|
||||
|
||||
function reboot() {
|
||||
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||
|
||||
GUI.tab_switch_cleanup(function() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, reinitialize);
|
||||
});
|
||||
}
|
||||
|
||||
|
@ -73,7 +73,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
} else {
|
||||
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
TABS.onboard_logging.initialize(false, $('#content').scrollTop());
|
||||
});
|
||||
|
@ -135,7 +135,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
BLACKBOX.blackboxRateDenom = parseInt(rate[1], 10);
|
||||
BLACKBOX.blackboxDevice = parseInt($(".blackboxDevice select").val(), 10);
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_BLACKBOX_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BLACKBOX_CONFIG), false, save_to_eeprom);
|
||||
MSP.send_message(MSPCodes.MSP_SET_BLACKBOX_CONFIG, mspHelper.crunch(MSP_codes.MSP_SET_BLACKBOX_CONFIG), false, save_to_eeprom);
|
||||
});
|
||||
}
|
||||
|
||||
|
@ -278,7 +278,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
sdcardTimer = setTimeout(function() {
|
||||
sdcardTimer = false;
|
||||
if (CONFIGURATOR.connectionValid) {
|
||||
MSP.send_message(MSP_codes.MSP_SDCARD_SUMMARY, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
|
||||
update_html();
|
||||
});
|
||||
}
|
||||
|
@ -318,7 +318,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function flash_update_summary(onDone) {
|
||||
MSP.send_message(MSP_codes.MSP_DATAFLASH_SUMMARY, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
|
||||
update_html();
|
||||
|
||||
if (onDone) {
|
||||
|
@ -347,7 +347,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
nextAddress += chunkDataView.byteLength;
|
||||
|
||||
$(".dataflash-saving progress").attr("value", nextAddress / maxBytes * 100);
|
||||
|
||||
|
||||
var
|
||||
blob = new Blob([chunkDataView]);
|
||||
|
||||
|
@ -359,7 +359,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
mark_saving_dialog_done();
|
||||
}
|
||||
} else {
|
||||
MSP.dataflashRead(nextAddress, onChunkRead);
|
||||
MspHelper.dataflashRead(nextAddress, onChunkRead);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -370,12 +370,12 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
}
|
||||
} else {
|
||||
// There was an error with the received block (address didn't match the one we asked for), retry
|
||||
MSP.dataflashRead(nextAddress, onChunkRead);
|
||||
MspHelper.dataflashRead(nextAddress, onChunkRead);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Fetch the initial block
|
||||
MSP.dataflashRead(nextAddress, onChunkRead);
|
||||
MspHelper.dataflashRead(nextAddress, onChunkRead);
|
||||
});
|
||||
});
|
||||
}
|
||||
|
@ -444,7 +444,7 @@ TABS.onboard_logging.initialize = function (callback) {
|
|||
function flash_erase() {
|
||||
$(".dataflash-confirm-erase").addClass('erasing');
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_DATAFLASH_ERASE, false, false, poll_for_erase_completion);
|
||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_ERASE, false, false, poll_for_erase_completion);
|
||||
}
|
||||
|
||||
function flash_erase_cancel() {
|
||||
|
|
14
tabs/osd.js
14
tabs/osd.js
|
@ -174,10 +174,10 @@ FONT.msp = {
|
|||
FONT.upload = function($progress) {
|
||||
return Promise.mapSeries(FONT.data.characters, function(data, i) {
|
||||
$progress.val((i / FONT.data.characters.length) * 100);
|
||||
return MSP.promise(MSP_codes.MSP_OSD_CHAR_WRITE, FONT.msp.encode(i));
|
||||
return MSP.promise(MSPCodes.MSP_OSD_CHAR_WRITE, FONT.msp.encode(i));
|
||||
})
|
||||
.then(function() {
|
||||
return MSP.promise(MSP_codes.MSP_SET_REBOOT);
|
||||
return MSP.promise(MSPCodes.MSP_SET_REBOOT);
|
||||
});
|
||||
};
|
||||
|
||||
|
@ -414,7 +414,7 @@ TABS.osd.initialize = function (callback) {
|
|||
// 2 way binding... sorta
|
||||
function updateOsdView() {
|
||||
// ask for the OSD config data
|
||||
MSP.promise(MSP_codes.MSP_OSD_CONFIG)
|
||||
MSP.promise(MSPCodes.MSP_OSD_CONFIG)
|
||||
.then(function(info) {
|
||||
if (!info.length) {
|
||||
$('.unsupported').fadeIn();
|
||||
|
@ -435,7 +435,7 @@ TABS.osd.initialize = function (callback) {
|
|||
}
|
||||
$videoTypes.find(':radio').click(function(e) {
|
||||
OSD.data.video_system = $(this).data('type');
|
||||
MSP.promise(MSP_codes.MSP_SET_OSD_CONFIG, OSD.msp.encodeOther())
|
||||
MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, OSD.msp.encodeOther())
|
||||
.then(function() {
|
||||
updateOsdView();
|
||||
});
|
||||
|
@ -462,7 +462,7 @@ TABS.osd.initialize = function (callback) {
|
|||
OSD.data.last_positions[field.name] = field.position
|
||||
field.position = -1
|
||||
}
|
||||
MSP.promise(MSP_codes.MSP_SET_OSD_CONFIG, OSD.msp.encode(field))
|
||||
MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, OSD.msp.encode(field))
|
||||
.then(function() {
|
||||
updateOsdView();
|
||||
});
|
||||
|
@ -478,7 +478,7 @@ TABS.osd.initialize = function (callback) {
|
|||
var field = $(this).data('field');
|
||||
var position = parseInt($(this).val());
|
||||
field.position = position;
|
||||
MSP.promise(MSP_codes.MSP_SET_OSD_CONFIG, OSD.msp.encode(field))
|
||||
MSP.promise(MSPCodes.MSP_SET_OSD_CONFIG, OSD.msp.encode(field))
|
||||
.then(function() {
|
||||
updateOsdView();
|
||||
});
|
||||
|
@ -576,7 +576,7 @@ TABS.osd.initialize = function (callback) {
|
|||
|
||||
$('a.save').click(function() {
|
||||
var self = this;
|
||||
MSP.promise(MSP_codes.MSP_EEPROM_WRITE);
|
||||
MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||
GUI.log('OSD settings saved');
|
||||
var oldText = $(this).text();
|
||||
$(this).html("Saved");
|
||||
|
|
|
@ -17,34 +17,34 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// requesting MSP_STATUS manually because it contains CONFIG.profile
|
||||
MSP.promise(MSP_codes.MSP_STATUS).then(function() {
|
||||
MSP.promise(MSPCodes.MSP_STATUS).then(function() {
|
||||
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion)) {
|
||||
return MSP.promise(MSP_codes.MSP_PID_CONTROLLER);
|
||||
return MSP.promise(MSPCodes.MSP_PID_CONTROLLER);
|
||||
}
|
||||
}).then(function() {
|
||||
return MSP.promise(MSP_codes.MSP_PIDNAMES)
|
||||
return MSP.promise(MSPCodes.MSP_PIDNAMES)
|
||||
}).then(function() {
|
||||
return MSP.promise(MSP_codes.MSP_PID);
|
||||
return MSP.promise(MSPCodes.MSP_PID);
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.0") && semver.lt(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
return MSP.promise(MSP_codes.MSP_SPECIAL_PARAMETERS);
|
||||
return MSP.promise(MSPCodes.MSP_SPECIAL_PARAMETERS);
|
||||
}
|
||||
}).then(function() {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
return MSP.promise(MSP_codes.MSP_PID_ADVANCED);
|
||||
return MSP.promise(MSPCodes.MSP_PID_ADVANCED);
|
||||
}
|
||||
}).then(function() {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
return MSP.promise(MSP_codes.MSP_RX_CONFIG);
|
||||
return MSP.promise(MSPCodes.MSP_RX_CONFIG);
|
||||
}
|
||||
}).then(function() {
|
||||
return MSP.promise(MSP_codes.MSP_RC_TUNING);
|
||||
return MSP.promise(MSPCodes.MSP_RC_TUNING);
|
||||
}).then(function() {
|
||||
return MSP.promise(MSP_codes.MSP_FILTER_CONFIG);
|
||||
return MSP.promise(MSPCodes.MSP_FILTER_CONFIG);
|
||||
}).then(function() {
|
||||
var promise = true;
|
||||
if (CONFIG.flightControllerIdentifier === "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||
promise = MSP.promise(MSP_codes.MSP_BF_CONFIG);
|
||||
promise = MSP.promise(MSPCodes.MSP_BF_CONFIG);
|
||||
}
|
||||
|
||||
return promise;
|
||||
|
@ -506,7 +506,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
|
||||
$('#resetProfile').on('click', function(){
|
||||
self.updating = true;
|
||||
MSP.promise(MSP_codes.MSP_SET_RESET_CURR_PID).then(function () {
|
||||
MSP.promise(MSPCodes.MSP_SET_RESET_CURR_PID).then(function () {
|
||||
self.refresh(function () {
|
||||
self.updating = false;
|
||||
|
||||
|
@ -518,7 +518,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('.tab-pid_tuning select[name="profile"]').change(function () {
|
||||
self.currentProfile = parseInt($(this).val());
|
||||
self.updating = true;
|
||||
MSP.promise(MSP_codes.MSP_SELECT_SETTING, [self.currentProfile]).then(function () {
|
||||
MSP.promise(MSPCodes.MSP_SELECT_SETTING, [self.currentProfile]).then(function () {
|
||||
self.refresh(function () {
|
||||
self.updating = false;
|
||||
|
||||
|
@ -531,7 +531,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('.tab-pid_tuning select[name="rate_profile"]').change(function () {
|
||||
self.currentRateProfile = parseInt($(this).val());
|
||||
self.updating = true;
|
||||
MSP.promise(MSP_codes.MSP_SELECT_SETTING, [self.currentRateProfile + self.RATE_PROFILE_MASK]).then(function () {
|
||||
MSP.promise(MSPCodes.MSP_SELECT_SETTING, [self.currentRateProfile + self.RATE_PROFILE_MASK]).then(function () {
|
||||
self.refresh(function () {
|
||||
self.updating = false;
|
||||
|
||||
|
@ -797,35 +797,35 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
var promise;
|
||||
if (semver.gte(CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion)) {
|
||||
PID.controller = pidController_e.val();
|
||||
promise = MSP.promise(MSP_codes.MSP_SET_PID_CONTROLLER, MSP.crunch(MSP_codes.MSP_SET_PID_CONTROLLER));
|
||||
promise = MSP.promise(MSPCodes.MSP_SET_PID_CONTROLLER, mspHelper.crunch(MSPCodes.MSP_SET_PID_CONTROLLER));
|
||||
}
|
||||
return promise;
|
||||
}).then(function () {
|
||||
return MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID));
|
||||
return MSP.promise(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID));
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.0") && semver.lt(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
return MSP.promise(MSP_codes.MSP_SET_SPECIAL_PARAMETERS, MSP.crunch(MSP_codes.MSP_SET_SPECIAL_PARAMETERS));
|
||||
return MSP.promise(MSPCodes.MSP_SET_SPECIAL_PARAMETERS, mspHelper.crunch(MSPCodes.MSP_SET_SPECIAL_PARAMETERS));
|
||||
}
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
return MSP.promise(MSP_codes.MSP_SET_PID_ADVANCED, MSP.crunch(MSP_codes.MSP_SET_PID_ADVANCED));
|
||||
return MSP.promise(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED));
|
||||
}
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
return MSP.promise(MSP_codes.MSP_SET_RX_CONFIG, MSP.crunch(MSP_codes.MSP_SET_RX_CONFIG));
|
||||
return MSP.promise(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG));
|
||||
}
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||
return MSP.promise(MSP_codes.MSP_SET_FILTER_CONFIG, MSP.crunch(MSP_codes.MSP_SET_FILTER_CONFIG));
|
||||
return MSP.promise(MSPCodes.MSP_SET_FILTER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FILTER_CONFIG));
|
||||
}
|
||||
}).then(function () {
|
||||
return MSP.promise(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING));
|
||||
return MSP.promise(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING));
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||
return MSP.promise(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG));
|
||||
return MSP.promise(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG));
|
||||
}
|
||||
}).then(function () {
|
||||
return MSP.promise(MSP_codes.MSP_EEPROM_WRITE);
|
||||
return MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||
}).then(function () {
|
||||
self.updating = false;
|
||||
self.setDirty(false);
|
||||
|
@ -845,7 +845,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
@ -853,7 +853,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
};
|
||||
|
||||
TABS.pid_tuning.getRecieverData = function () {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false);
|
||||
};
|
||||
|
||||
TABS.pid_tuning.initRatesPreview = function () {
|
||||
|
|
|
@ -77,7 +77,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
load_configuration_from_fc();
|
||||
|
||||
function load_configuration_from_fc() {
|
||||
MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
|
||||
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
|
||||
|
||||
function on_configuration_loaded_handler() {
|
||||
$('#content').load("./tabs/ports.html", on_tab_loaded_handler);
|
||||
|
@ -214,7 +214,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
@ -251,17 +251,17 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
SERIAL_CONFIG.ports.push(serialPort);
|
||||
});
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
|
||||
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, on_saved_handler);
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, on_saved_handler);
|
||||
}
|
||||
|
||||
function on_saved_handler() {
|
||||
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
|
||||
|
||||
GUI.tab_switch_cleanup(function() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_REBOOT, false, false, on_reboot_success_handler);
|
||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, on_reboot_success_handler);
|
||||
});
|
||||
}
|
||||
|
||||
|
@ -275,7 +275,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
},2500);
|
||||
} else {
|
||||
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function() {
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function() {
|
||||
GUI.log(chrome.i18n.getMessage('deviceReady'));
|
||||
TABS.ports.initialize(false, $('#content').scrollTop());
|
||||
});
|
||||
|
|
|
@ -12,30 +12,30 @@ TABS.receiver.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, get_rc_tuning_data);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, get_rc_tuning_data);
|
||||
}
|
||||
|
||||
function get_rc_tuning_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC_TUNING, false, false, get_bt_config_data);
|
||||
MSP.send_message(MSPCodes.MSP_RC_TUNING, false, false, get_bt_config_data);
|
||||
}
|
||||
|
||||
function get_bt_config_data() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, get_rc_map);
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, get_rc_map);
|
||||
}
|
||||
|
||||
function get_rc_map() {
|
||||
MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_config);
|
||||
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_config);
|
||||
}
|
||||
|
||||
// Fetch features so we can check if RX_MSP is enabled:
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_rc_configs);
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_rc_configs);
|
||||
}
|
||||
|
||||
function load_rc_configs() {
|
||||
var next_callback = load_html;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_RC_DEADBAND, false, false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_RC_DEADBAND, false, false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
|
@ -45,7 +45,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
$('#content').load("./tabs/receiver.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_MISC, false, false, get_rc_data);
|
||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, get_rc_data);
|
||||
|
||||
function process_html() {
|
||||
// translate to user-selected language
|
||||
|
@ -221,25 +221,25 @@ TABS.receiver.initialize = function (callback) {
|
|||
MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val());
|
||||
|
||||
function save_misc() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_MISC, MSP.crunch(MSP_codes.MSP_SET_MISC), false, save_rc_configs);
|
||||
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_rc_configs);
|
||||
}
|
||||
|
||||
function save_rc_configs() {
|
||||
var next_callback = save_to_eeprom;
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_SET_RC_DEADBAND, MSP.crunch(MSP_codes.MSP_SET_RC_DEADBAND), false, next_callback);
|
||||
MSP.send_message(MSPCodes.MSP_SET_RC_DEADBAND, mspHelper.crunch(MSPCodes.MSP_SET_RC_DEADBAND), false, next_callback);
|
||||
} else {
|
||||
next_callback();
|
||||
}
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('receiverEepromSaved'));
|
||||
});
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_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);
|
||||
});
|
||||
|
||||
$("a.sticks").click(function() {
|
||||
|
@ -259,7 +259,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
// Give the window a callback it can use to send the channels (otherwise it can't see those objects)
|
||||
createdWindow.contentWindow.setRawRx = function(channels) {
|
||||
if (CONFIGURATOR.connectionValid && GUI.active_tab != 'cli') {
|
||||
MSP.setRawRx(channels);
|
||||
MspHelper.setRawRx(channels);
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
|
@ -278,7 +278,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
chrome.storage.local.set({'rx_refresh_rate': plot_update_rate});
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, update_ui);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, update_ui);
|
||||
}
|
||||
|
||||
// setup plot
|
||||
|
@ -384,7 +384,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
@ -392,7 +392,7 @@ TABS.receiver.initialize = function (callback) {
|
|||
};
|
||||
|
||||
TABS.receiver.getRecieverData = function () {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false);
|
||||
};
|
||||
|
||||
TABS.receiver.initModelPreview = function () {
|
||||
|
|
|
@ -363,25 +363,25 @@ TABS.sensors.initialize = function (callback) {
|
|||
// data pulling timers
|
||||
if (checkboxes[0] || checkboxes[1] || checkboxes[2]) {
|
||||
GUI.interval_add('IMU_pull', function imu_data_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_RAW_IMU, false, false, update_imu_graphs);
|
||||
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_imu_graphs);
|
||||
}, fastest, true);
|
||||
}
|
||||
|
||||
if (checkboxes[3]) {
|
||||
GUI.interval_add('altitude_pull', function altitude_data_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_ALTITUDE, false, false, update_altitude_graph);
|
||||
MSP.send_message(MSPCodes.MSP_ALTITUDE, false, false, update_altitude_graph);
|
||||
}, rates.baro, true);
|
||||
}
|
||||
|
||||
if (checkboxes[4]) {
|
||||
GUI.interval_add('sonar_pull', function sonar_data_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_SONAR, false, false, update_sonar_graphs);
|
||||
MSP.send_message(MSPCodes.MSP_SONAR, false, false, update_sonar_graphs);
|
||||
}, rates.sonar, true);
|
||||
}
|
||||
|
||||
if (checkboxes[5]) {
|
||||
GUI.interval_add('debug_pull', function debug_data_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_DEBUG, false, false, update_debug_graphs);
|
||||
MSP.send_message(MSPCodes.MSP_DEBUG, false, false, update_debug_graphs);
|
||||
}, rates.debug, true);
|
||||
}
|
||||
|
||||
|
@ -447,7 +447,7 @@ TABS.sensors.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
|
|
@ -9,29 +9,29 @@ TABS.servos.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function get_servo_configurations() {
|
||||
MSP.send_message(MSP_codes.MSP_SERVO_CONFIGURATIONS, false, false, get_servo_mix_rules);
|
||||
MSP.send_message(MSPCodes.MSP_SERVO_CONFIGURATIONS, false, false, get_servo_mix_rules);
|
||||
}
|
||||
|
||||
function get_servo_mix_rules() {
|
||||
MSP.send_message(MSP_codes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding);
|
||||
MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding);
|
||||
}
|
||||
|
||||
function get_channel_forwarding() {
|
||||
var nextFunction = get_rc_data;
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_CHANNEL_FORWARDING, false, false, nextFunction);
|
||||
MSP.send_message(MSPCodes.MSP_CHANNEL_FORWARDING, false, false, nextFunction);
|
||||
} else {
|
||||
nextFunction();
|
||||
}
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, get_boxnames_data);
|
||||
MSP.send_message(MSPCodes.MSP_RC, false, false, get_boxnames_data);
|
||||
}
|
||||
|
||||
function get_boxnames_data() {
|
||||
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false, load_html);
|
||||
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, load_html);
|
||||
}
|
||||
|
||||
function load_html() {
|
||||
|
@ -141,15 +141,15 @@ TABS.servos.initialize = function (callback) {
|
|||
//
|
||||
// send data to FC
|
||||
//
|
||||
MSP.sendServoConfigurations(send_servo_mixer_rules);
|
||||
MspHelper.sendServoConfigurations(send_servo_mixer_rules);
|
||||
|
||||
function send_servo_mixer_rules() {
|
||||
MSP.sendServoConfigurations(save_to_eeprom);
|
||||
MspHelper.sendServoConfigurations(save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_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'));
|
||||
});
|
||||
}
|
||||
|
@ -187,7 +187,7 @@ TABS.servos.initialize = function (callback) {
|
|||
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function () {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
|
|
@ -12,22 +12,22 @@ TABS.setup.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function load_status() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, load_config);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_config);
|
||||
}
|
||||
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_misc_data);
|
||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, 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() {
|
||||
$('#content').load("./tabs/setup.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_ACC_TRIM, false, false, load_status);
|
||||
MSP.send_message(MSPCodes.MSP_ACC_TRIM, false, false, load_status);
|
||||
|
||||
function process_html() {
|
||||
// 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
|
||||
// until this operation finishes, sending more commands through data_poll() will result in serial buffer overflow
|
||||
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'));
|
||||
$('#accel_calib_running').show();
|
||||
$('#accel_calib_rest').hide();
|
||||
|
@ -96,7 +96,7 @@ TABS.setup.initialize = function (callback) {
|
|||
if (!self.hasClass('calibrating') && !self.hasClass('disabled')) {
|
||||
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'));
|
||||
$('#mag_calib_running').show();
|
||||
$('#mag_calib_rest').hide();
|
||||
|
@ -112,7 +112,7 @@ TABS.setup.initialize = function (callback) {
|
|||
});
|
||||
|
||||
$('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.tab_switch_cleanup(function () {
|
||||
|
@ -169,9 +169,9 @@ TABS.setup.initialize = function (callback) {
|
|||
heading_e = $('dd.heading');
|
||||
|
||||
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_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn]));
|
||||
bat_mah_drawing_e.text(chrome.i18n.getMessage('initialSetupBatteryAValue', [ANALOG.amperage.toFixed(2)]));
|
||||
|
@ -179,7 +179,7 @@ TABS.setup.initialize = function (callback) {
|
|||
});
|
||||
|
||||
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 () {
|
||||
gpsFix_e.html((GPS_DATA.fix) ? chrome.i18n.getMessage('gpsFixTrue') : chrome.i18n.getMessage('gpsFixFalse'));
|
||||
gpsSats_e.text(GPS_DATA.numSat);
|
||||
gpsLat_e.text((GPS_DATA.lat / 10000000).toFixed(4) + ' deg');
|
||||
|
@ -189,7 +189,7 @@ TABS.setup.initialize = function (callback) {
|
|||
}
|
||||
|
||||
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]]));
|
||||
pitch_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[1]]));
|
||||
heading_e.text(chrome.i18n.getMessage('initialSetupAttitude', [SENSOR_DATA.kinematics[2]]));
|
||||
|
|
|
@ -24,7 +24,7 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
// 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
|
||||
function hexToBytes(hex) {
|
||||
|
@ -79,10 +79,10 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
|
|||
// send data to FC
|
||||
//
|
||||
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() {
|
||||
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'));
|
||||
});
|
||||
}
|
||||
|
@ -92,7 +92,7 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
// status data pulled via separate timer with static speed
|
||||
GUI.interval_add('status_pull', function status_pull() {
|
||||
MSP.send_message(MSP_codes.MSP_STATUS);
|
||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||
}, 250, true);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
|
|
Loading…
Reference in New Issue