mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 12:55:14 +03:00
Updating to use API version 1.1.
This commit is contained in:
parent
64a8dfd4d2
commit
32820853ce
7 changed files with 117 additions and 55 deletions
|
@ -100,7 +100,7 @@
|
|||
"message": "No configuration received within <span style=\"color: red\">10 seconds</span>, communication <span style=\"color: red\">failed</span>"
|
||||
},
|
||||
"firmwareVersionNotSupported": {
|
||||
"message": "This firmware version is <span style=\"color: red\">not supported</span>. Please upgrade to version <strong>$1</strong> or higher"
|
||||
"message": "This firmware version is <span style=\"color: red\">not supported</span>. Please upgrade to firmware that supports api version <strong>$1</strong> or higher"
|
||||
},
|
||||
"firmwareVersion": {
|
||||
"message": "Firmware Version: <strong>$1</strong>"
|
||||
|
@ -111,6 +111,15 @@
|
|||
"uniqueDeviceIdReceived": {
|
||||
"message": "Unique device ID <span style=\"color: green\">received</span> - <strong>0x$1</strong>"
|
||||
},
|
||||
"boardInfoReceived": {
|
||||
"message": "Board: <strong>$1</strong>, version: <strong>$2</strong>"
|
||||
},
|
||||
"buildInfoReceived": {
|
||||
"message": "Running firmware released on: <strong>$1</strong>"
|
||||
},
|
||||
"fcInfoReceived": {
|
||||
"message": "Flight controller info, identifier: <strong>$1</strong>, version: <strong>$2</strong>"
|
||||
},
|
||||
|
||||
"notifications_app_just_updated_to_version": {
|
||||
"message": "Application just updated to version: $1"
|
||||
|
|
|
@ -23,7 +23,7 @@ function configuration_backup(callback) {
|
|||
*/
|
||||
MSP_codes.MSP_MISC,
|
||||
MSP_codes.MSP_RCMAP,
|
||||
MSP_codes.MSP_CONFIG
|
||||
MSP_codes.MSP_BF_CONFIG
|
||||
];
|
||||
|
||||
var configuration = {
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
var CONFIGURATOR = {
|
||||
'releaseDate': 1417875879820, // new Date().getTime() - 2014.12.06
|
||||
'firmwareVersionAccepted': 2.3,
|
||||
'apiVersionAccepted': 1.1,
|
||||
'backupFileMinVersionAccepted': '0.55', // chrome.runtime.getManifest().version is stored as string, so does this one
|
||||
'connectionValid': false,
|
||||
'cliActive': false,
|
||||
|
|
84
js/msp.js
84
js/msp.js
|
@ -3,6 +3,10 @@
|
|||
// MSP_codes needs to be re-integrated inside MSP object
|
||||
var MSP_codes = {
|
||||
MSP_API_VERSION: 1,
|
||||
MSP_FC_VARIANT: 2,
|
||||
MSP_FC_VERSION: 3,
|
||||
MSP_BOARD_INFO: 4,
|
||||
MSP_BUILD_INFO: 5,
|
||||
|
||||
// MSP commands for Cleanflight original features
|
||||
MSP_CHANNEL_FORWARDING: 32,
|
||||
|
@ -61,15 +65,15 @@ var MSP_codes = {
|
|||
MSP_UID: 160, // Unique device ID
|
||||
MSP_ACC_TRIM: 240, // get acc angle trim values
|
||||
MSP_SET_ACC_TRIM: 239, // set acc angle trim values
|
||||
MSP_GPSSVINFO: 164, // get Signal Strength (only U-Blox)
|
||||
MSP_GPS_SV_INFO: 164, // get Signal Strength (only U-Blox)
|
||||
|
||||
// Additional private MSP for baseflight configurator (yes thats us \o/)
|
||||
MSP_RCMAP: 64, // get channel map (also returns number of channels total)
|
||||
MSP_SET_RCMAP: 65, // set rc map, numchannels to set comes from MSP_RCMAP
|
||||
MSP_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
|
||||
MSP_SET_CONFIG: 67, // baseflight-specific settings save
|
||||
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
|
||||
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
|
||||
MSP_SET_REBOOT: 68, // reboot settings
|
||||
MSP_BUILDINFO: 69 // build date as well as some space for future expansion
|
||||
MSP_BF_BUILD_INFO: 69 // build date as well as some space for future expansion
|
||||
};
|
||||
|
||||
var MSP = {
|
||||
|
@ -169,6 +173,8 @@ var MSP = {
|
|||
|
||||
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);
|
||||
|
@ -436,7 +442,7 @@ var MSP = {
|
|||
case MSP_codes.MSP_SET_ACC_TRIM:
|
||||
console.log('Accelerometer trimms saved.');
|
||||
break;
|
||||
case MSP_codes.MSP_GPSSVINFO:
|
||||
case MSP_codes.MSP_GPS_SV_INFO:
|
||||
if (data.byteLength > 0) {
|
||||
var numCh = data.getUint8(0);
|
||||
|
||||
|
@ -462,7 +468,7 @@ var MSP = {
|
|||
case MSP_codes.MSP_SET_RCMAP:
|
||||
console.log('RCMAP saved');
|
||||
break;
|
||||
case MSP_codes.MSP_CONFIG:
|
||||
case MSP_codes.MSP_BF_CONFIG:
|
||||
BF_CONFIG.mixerConfiguration = data.getUint8(0);
|
||||
BF_CONFIG.features = data.getUint32(1, 1);
|
||||
BF_CONFIG.serialrx_type = data.getUint8(5);
|
||||
|
@ -472,36 +478,66 @@ var MSP = {
|
|||
BF_CONFIG.currentscale = data.getUint16(12, 1);
|
||||
BF_CONFIG.currentoffset = data.getUint16(14, 1);
|
||||
break;
|
||||
case MSP_codes.MSP_SET_CONFIG:
|
||||
case MSP_codes.MSP_SET_BF_CONFIG:
|
||||
break;
|
||||
case MSP_codes.MSP_SET_REBOOT:
|
||||
case MSP_codes.MSP_REBOOT:
|
||||
console.log('Reboot request accepted');
|
||||
break;
|
||||
case MSP_codes.MSP_BUILDINFO:
|
||||
var buff = [];
|
||||
|
||||
for (var i = 0; i < data.byteLength; i++) {
|
||||
buff.push(data.getUint8(i));
|
||||
}
|
||||
|
||||
CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
|
||||
break;
|
||||
|
||||
//
|
||||
// Cleanflight specific
|
||||
//
|
||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
console.log('Channel forwarding saved');
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_API_VERSION:
|
||||
CONFIG.apiVersion = data.getUint8(1) + '.' + data.getUint8(2);
|
||||
var offset = 0;
|
||||
CONFIG.mspProtocolVersion = data.getUint8(offset++);
|
||||
CONFIG.apiVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++);
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_FC_VARIANT:
|
||||
var identifier = '';
|
||||
for (i = 0; i < 4; i++) {
|
||||
identifier += String.fromCharCode(data.getUint8(3 + i));
|
||||
var offset;
|
||||
for (offset = 0; offset < 4; offset++) {
|
||||
identifier += String.fromCharCode(data.getUint8(offset));
|
||||
}
|
||||
CONFIG.flightControllerIdentifier = identifier;
|
||||
CONFIG.flightControllerVersion = data.getUint8(7) + '.' + data.getUint8(8) + '.' + data.getUint8(9);
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_FC_VERSION:
|
||||
var offset = 0;
|
||||
CONFIG.flightControllerVersion = data.getUint8(offset++) + '.' + data.getUint8(offset++) + '.' + data.getUint8(offset++);
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_BUILD_INFO:
|
||||
var offset = 0;
|
||||
|
||||
var dateLength = 11;
|
||||
var buff = [];
|
||||
for (var i = 0; i < dateLength; i++) {
|
||||
buff.push(data.getUint8(offset++));
|
||||
}
|
||||
buff.push(32); // ascii space
|
||||
|
||||
var timeLength = 8;
|
||||
for (var i = 0; i < timeLength; i++) {
|
||||
buff.push(data.getUint8(offset++));
|
||||
}
|
||||
CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_BOARD_INFO:
|
||||
var identifier = '';
|
||||
var offset;
|
||||
for (offset = 0; offset < 4; offset++) {
|
||||
identifier += String.fromCharCode(data.getUint8(offset));
|
||||
}
|
||||
CONFIG.boardIdentifier = identifier;
|
||||
CONFIG.boardVersion = data.getUint16(offset);
|
||||
offset+=2;
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
console.log('Channel forwarding saved');
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_MODE_RANGES:
|
||||
|
|
|
@ -135,33 +135,50 @@ function onOpen(openInfo) {
|
|||
}
|
||||
}, 10000);
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_API_VERSION, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
||||
});
|
||||
|
||||
|
||||
// request configuration data
|
||||
MSP.send_message(MSP_codes.MSP_UID, false, false, function () {
|
||||
GUI.timeout_remove('connecting'); // kill connecting timer
|
||||
MSP.send_message(MSP_codes.MSP_API_VERSION, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
||||
|
||||
GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
|
||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () {
|
||||
if (CONFIG.apiVersion >= CONFIGURATOR.apiVersionAccepted) {
|
||||
|
||||
if (CONFIG.version >= CONFIGURATOR.firmwareVersionAccepted) {
|
||||
MSP.send_message(MSP_codes.MSP_BUILDINFO, false, false, function () {
|
||||
googleAnalytics.sendEvent('Firmware', 'Using', CONFIG.buildInfo);
|
||||
GUI.log('Running firmware released on: <strong>' + CONFIG.buildInfo + '</strong>');
|
||||
MSP.send_message(MSP_codes.MSP_FC_VARIANT, false, false, function () {
|
||||
|
||||
// continue as usually
|
||||
CONFIGURATOR.connectionValid = true;
|
||||
MSP.send_message(MSP_codes.MSP_FC_VERSION, false, false, function () {
|
||||
|
||||
$('div#port-picker a.connect').text(chrome.i18n.getMessage('disconnect')).addClass('active');
|
||||
$('#tabs li a:first').click();
|
||||
googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion);
|
||||
GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_BUILD_INFO, false, false, function () {
|
||||
|
||||
googleAnalytics.sendEvent('Firmware', 'Using', CONFIG.buildInfo);
|
||||
GUI.log(chrome.i18n.getMessage('buildInfoReceived', [CONFIG.buildInfo]));
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_BOARD_INFO, false, false, function () {
|
||||
|
||||
googleAnalytics.sendEvent('Board', 'Using', CONFIG.boardIdentifier + ',' + CONFIG.boardVersion);
|
||||
GUI.log(chrome.i18n.getMessage('boardInfoReceived', [CONFIG.boardIdentifier, CONFIG.boardVersion]));
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_UID, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
|
||||
|
||||
GUI.timeout_remove('connecting'); // kill connecting timer
|
||||
|
||||
// continue as usually
|
||||
CONFIGURATOR.connectionValid = true;
|
||||
|
||||
$('div#port-picker a.connect').text(chrome.i18n.getMessage('disconnect')).addClass('active');
|
||||
$('#tabs li a:first').click();
|
||||
});
|
||||
});
|
||||
});
|
||||
});
|
||||
} else {
|
||||
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.firmwareVersionAccepted]));
|
||||
$('div#port-picker a.connect').click(); // disconnect
|
||||
}
|
||||
});
|
||||
});
|
||||
} else {
|
||||
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.apiVersionAccepted]));
|
||||
$('div#port-picker a.connect').click(); // disconnect
|
||||
}
|
||||
});
|
||||
} else {
|
||||
console.log('Failed to open serial port');
|
||||
|
|
|
@ -11,7 +11,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_CONFIG, false, false, load_rc_map);
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_rc_map);
|
||||
}
|
||||
|
||||
function load_rc_map() {
|
||||
|
@ -268,7 +268,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
},1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CONFIG), false, save_misc);
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CONFIG), false, save_misc);
|
||||
});
|
||||
|
||||
// status data pulled via separate timer with static speed
|
||||
|
|
|
@ -21,7 +21,7 @@ TABS.setup.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function load_config() {
|
||||
MSP.send_message(MSP_codes.MSP_CONFIG, false, false, load_misc_data);
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, load_misc_data);
|
||||
}
|
||||
|
||||
function load_misc_data() {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue