1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-18 13:55:14 +03:00

Use updated IDs for MSP_LOOP_TIME and MSP_SET_LOOP_TIME. Cleanup and

fix backup/restore arming config.  Backup restore/looptime.  Add config
migration of looptime and arming config.  Rename MSP_RCMAP to
MSP_RX_MAP to match cleanflight code.
This commit is contained in:
Dominic Clifton 2015-03-29 14:51:28 +01:00
parent 2e046db53e
commit 045d2b0ca4
6 changed files with 77 additions and 53 deletions

View file

@ -452,10 +452,10 @@
"message": "Magnetometer Declination [deg]" "message": "Magnetometer Declination [deg]"
}, },
"configurationAutoDisarmDelay": { "configurationAutoDisarmDelay": {
"message": "Disarm motors after set delay(Seconds)- Only if feature MOTOR_STOP enabled" "message": "Disarm motors after set delay(Seconds) (Requires MOTOR_STOP feature)"
}, },
"configurationDisarmKillSwitch": { "configurationDisarmKillSwitch": {
"message": "Disarm motors regardless of throttle value - Only when arming and disarming via AUX channel" "message": "Disarm motors regardless of throttle value (When arming via AUX channel)"
}, },
"configurationThrottleMinimum": { "configurationThrottleMinimum": {
"message": "Minimum Throttle" "message": "Minimum Throttle"

View file

@ -74,17 +74,22 @@ function configuration_backup(callback) {
} }
var uniqueData = [ var uniqueData = [
// Not used by cleanflight, and it's wrong anyway - AUX settings are per-profile in baseflight.
/*
MSP_codes.MSP_BOX,
*/
MSP_codes.MSP_MISC, MSP_codes.MSP_MISC,
MSP_codes.MSP_RCMAP, MSP_codes.MSP_RX_MAP,
MSP_codes.MSP_BF_CONFIG, MSP_codes.MSP_BF_CONFIG,
MSP_codes.MSP_CF_SERIAL_CONFIG, MSP_codes.MSP_CF_SERIAL_CONFIG,
MSP_codes.MSP_LED_STRIP_CONFIG MSP_codes.MSP_LED_STRIP_CONFIG
]; ];
function update_unique_data_list() {
if (CONFIG.apiVersion >= 1.8) {
uniqueData.push(MSP_codes.MSP_LOOP_TIME);
uniqueData.push(MSP_codes.MSP_ARMING_CONFIG);
}
}
update_unique_data_list();
function fetch_unique_data() { function fetch_unique_data() {
var codeKey = 0; var codeKey = 0;
@ -95,15 +100,13 @@ function configuration_backup(callback) {
fetch_unique_data_item(); fetch_unique_data_item();
}); });
} else { } else {
// Not used by cleanflight, and it's wrong anyway - AUX settings are per-profile in baseflight.
/*
configuration.AUX = jQuery.extend(true, [], AUX_CONFIG_values);
*/
configuration.MISC = jQuery.extend(true, {}, MISC); configuration.MISC = jQuery.extend(true, {}, MISC);
configuration.RCMAP = jQuery.extend(true, [], RC_MAP); configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
configuration.BF_CONFIG = jQuery.extend(true, {}, BF_CONFIG); configuration.BF_CONFIG = jQuery.extend(true, {}, BF_CONFIG);
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG); configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG);
configuration.LED_STRIP = jQuery.extend(true, [], LED_STRIP); configuration.LED_STRIP = jQuery.extend(true, [], LED_STRIP);
configuration.FC_CONFIG = jQuery.extend(true, {}, FC_CONFIG);
configuration.ARMING_CONFIG = jQuery.extend(true, {}, ARMING_CONFIG);
save(); save();
} }
@ -408,9 +411,28 @@ function configuration_restore(callback) {
appliedMigrationsCount++; appliedMigrationsCount++;
} }
if (compareVersions(migratedVersion, '0.63.0') && !compareVersions(configuration.apiVersion, '1.8')) {
// api 1.8 exposes looptime and arming config
if (configuration.FC_CONFIG == undefined) {
configuration.FC_CONFIG = {
loopTime: 3500
};
}
if (configuration.ARMING_CONFIG == undefined) {
configuration.ARMING_CONFIG = {
auto_disarm_delay: 5,
disarm_kill_switch: 1
};
}
appliedMigrationsCount++;
}
if (appliedMigrationsCount > 0) { if (appliedMigrationsCount > 0) {
GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount])); GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
} }
return true; return true;
} }
@ -496,26 +518,27 @@ function configuration_restore(callback) {
var codeKey = 0; var codeKey = 0;
var uniqueData = [ var uniqueData = [
// Not used by cleanflight, and it's wrong anyway - AUX settings are per-profile in baseflight.
/*
MSP_codes.MSP_SET_BOX,
*/
MSP_codes.MSP_SET_MISC, MSP_codes.MSP_SET_MISC,
MSP_codes.MSP_SET_RCMAP, MSP_codes.MSP_SET_RX_MAP,
MSP_codes.MSP_SET_BF_CONFIG, MSP_codes.MSP_SET_BF_CONFIG,
MSP_codes.MSP_SET_CF_SERIAL_CONFIG MSP_codes.MSP_SET_CF_SERIAL_CONFIG
]; ];
function update_unique_data_list() {
if (CONFIG.apiVersion >= 1.8) {
uniqueData.push(MSP_codes.MSP_SET_LOOP_TIME);
uniqueData.push(MSP_codes.MSP_SET_ARMING_CONFIG);
}
}
function load_objects() { function load_objects() {
// Disabled, cleanflight does not use MSP_BOX.
/*
AUX_CONFIG_values = configuration.AUX;
*/
MISC = configuration.MISC; MISC = configuration.MISC;
RC_MAP = configuration.RCMAP; RC_MAP = configuration.RCMAP;
BF_CONFIG = configuration.BF_CONFIG; BF_CONFIG = configuration.BF_CONFIG;
SERIAL_CONFIG = configuration.SERIAL_CONFIG; SERIAL_CONFIG = configuration.SERIAL_CONFIG;
LED_STRIP = configuration.LED_STRIP; LED_STRIP = configuration.LED_STRIP;
ARMING_CONFIG = configuration.ARMING_CONFIG;
FC_CONFIG = configuration.FC_CONFIG;
} }
function send_unique_data_item() { function send_unique_data_item() {
@ -531,6 +554,8 @@ function configuration_restore(callback) {
load_objects(); load_objects();
update_unique_data_list();
// start uploading // start uploading
send_unique_data_item(); send_unique_data_item();
} }

View file

@ -77,10 +77,6 @@ var RC_tuning = {
var AUX_CONFIG = []; var AUX_CONFIG = [];
var AUX_CONFIG_IDS = []; var AUX_CONFIG_IDS = [];
//Disabled, cleanflight does not use MSP_BOX.
/*
var AUX_CONFIG_values = [];
*/
var MODE_RANGES = []; var MODE_RANGES = [];
var ADJUSTMENT_RANGES = []; var ADJUSTMENT_RANGES = [];
@ -141,7 +137,9 @@ var ARMING_CONFIG = {
disarm_kill_switch: 0 disarm_kill_switch: 0
}; };
var LOOP_TIME = 0; var FC_CONFIG = {
loopTime: 0
};
var MISC = { var MISC = {
midrc: 0, midrc: 0,

View file

@ -24,11 +24,11 @@ var MSP_codes = {
MSP_SET_PID_CONTROLLER: 60, MSP_SET_PID_CONTROLLER: 60,
MSP_ARMING_CONFIG: 61, MSP_ARMING_CONFIG: 61,
MSP_SET_ARMING_CONFIG: 62, MSP_SET_ARMING_CONFIG: 62,
MSP_LOOP_TIME: 63,
MSP_SET_LOOP_TIME: 64,
MSP_DATAFLASH_SUMMARY: 70, MSP_DATAFLASH_SUMMARY: 70,
MSP_DATAFLASH_READ: 71, MSP_DATAFLASH_READ: 71,
MSP_DATAFLASH_ERASE: 72, MSP_DATAFLASH_ERASE: 72,
MSP_LOOP_TIME: 73,
MSP_SET_LOOP_TIME: 74,
// Multiwii MSP commands // Multiwii MSP commands
MSP_IDENT: 100, MSP_IDENT: 100,
@ -82,8 +82,8 @@ var MSP_codes = {
MSP_GPS_SV_INFO: 164, // get Signal Strength MSP_GPS_SV_INFO: 164, // get Signal Strength
// Additional private MSP for baseflight configurator (yes thats us \o/) // Additional private MSP for baseflight configurator (yes thats us \o/)
MSP_RCMAP: 64, // get channel map (also returns number of channels total) MSP_RX_MAP: 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_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
MSP_SET_REBOOT: 68, // reboot settings MSP_SET_REBOOT: 68, // reboot settings
@ -360,7 +360,7 @@ var MSP = {
break; break;
case MSP_codes.MSP_LOOP_TIME: case MSP_codes.MSP_LOOP_TIME:
if (CONFIG.apiVersion >= 1.8) { if (CONFIG.apiVersion >= 1.8) {
LOOP_TIME = data.getInt16(0, 1); FC_CONFIG.loopTime = data.getInt16(0, 1);
} }
break; break;
case MSP_codes.MSP_MISC: // 22 bytes case MSP_codes.MSP_MISC: // 22 bytes
@ -519,14 +519,14 @@ var MSP = {
} }
break; break;
// Additional private MSP for baseflight configurator // Additional private MSP for baseflight configurator
case MSP_codes.MSP_RCMAP: case MSP_codes.MSP_RX_MAP:
RC_MAP = []; // empty the array as new data is coming in RC_MAP = []; // empty the array as new data is coming in
for (var i = 0; i < data.byteLength; i++) { for (var i = 0; i < data.byteLength; i++) {
RC_MAP.push(data.getUint8(i)); RC_MAP.push(data.getUint8(i));
} }
break; break;
case MSP_codes.MSP_SET_RCMAP: case MSP_codes.MSP_SET_RX_MAP:
console.log('RCMAP saved'); console.log('RCMAP saved');
break; break;
case MSP_codes.MSP_BF_CONFIG: case MSP_codes.MSP_BF_CONFIG:
@ -774,7 +774,12 @@ var MSP = {
case MSP_codes.MSP_SET_PID_CONTROLLER: case MSP_codes.MSP_SET_PID_CONTROLLER:
console.log('PID controller changed'); console.log('PID controller changed');
break; break;
case MSP_codes.MSP_SET_LOOP_TIME:
console.log('Looptime saved');
break;
case MSP_codes.MSP_SET_ARMING_CONFIG:
console.log('Arming config saved');
break;
default: default:
console.log('Unknown code detected: ' + code); console.log('Unknown code detected: ' + code);
@ -969,7 +974,7 @@ MSP.crunch = function (code) {
} }
break; break;
*/ */
case MSP_codes.MSP_SET_RCMAP: case MSP_codes.MSP_SET_RX_MAP:
for (var i = 0; i < RC_MAP.length; i++) { for (var i = 0; i < RC_MAP.length; i++) {
buffer.push(RC_MAP[i]); buffer.push(RC_MAP[i]);
} }
@ -981,16 +986,12 @@ MSP.crunch = function (code) {
buffer.push(highByte(CONFIG.accelerometerTrims[1])); buffer.push(highByte(CONFIG.accelerometerTrims[1]));
break; break;
case MSP_codes.MSP_SET_ARMING_CONFIG: case MSP_codes.MSP_SET_ARMING_CONFIG:
if (CONFIG.apiVersion >= 1.8) {
buffer.push(ARMING_CONFIG.auto_disarm_delay); buffer.push(ARMING_CONFIG.auto_disarm_delay);
buffer.push(ARMING_CONFIG.disarm_kill_switch); buffer.push(ARMING_CONFIG.disarm_kill_switch);
}
break; break;
case MSP_codes.MSP_SET_LOOP_TIME: case MSP_codes.MSP_SET_LOOP_TIME:
if (CONFIG.apiVersion >= 1.8) { buffer.push(lowByte(FC_CONFIG.loopTime));
buffer.push(lowByte(LOOP_TIME)); buffer.push(highByte(FC_CONFIG.loopTime));
buffer.push(highByte(LOOP_TIME));
}
break; break;
case MSP_codes.MSP_SET_MISC: case MSP_codes.MSP_SET_MISC:
buffer.push(lowByte(MISC.midrc)); buffer.push(lowByte(MISC.midrc));

View file

@ -23,7 +23,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
function load_rc_map() { function load_rc_map() {
MSP.send_message(MSP_codes.MSP_RCMAP, false, false, load_misc); MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_misc);
} }
function load_misc() { function load_misc() {
@ -260,7 +260,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay); $('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay);
$('input[name="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch); $('input[name="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch);
if(bit_check(BF_CONFIG.features, 4 + 1))//MOTOR_STOP if(bit_check(BF_CONFIG.features, 4 + 1))//MOTOR_STOP
$('div.disarmdelay').slideDown(); $('div.disarmdelay').show();
} }
else else
$('div.disarm').hide(); $('div.disarm').hide();
@ -293,11 +293,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
if (state) { if (state) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, index); BF_CONFIG.features = bit_set(BF_CONFIG.features, index);
if(element.attr('name') === 'MOTOR_STOP') if(element.attr('name') === 'MOTOR_STOP')
$('div.disarmdelay').slideDown(); $('div.disarmdelay').show();
} else { } else {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, index); BF_CONFIG.features = bit_clear(BF_CONFIG.features, index);
if(element.attr('name') === 'MOTOR_STOP') if(element.attr('name') === 'MOTOR_STOP')
$('div.disarmdelay').slideUp(); $('div.disarmdelay').hide();
} }
}); });

View file

@ -18,7 +18,7 @@ TABS.receiver.initialize = function (callback) {
} }
function get_rc_map() { function get_rc_map() {
MSP.send_message(MSP_codes.MSP_RCMAP, false, false, load_html); MSP.send_message(MSP_codes.MSP_RX_MAP, false, false, load_html);
} }
function load_html() { function load_html() {
@ -281,7 +281,7 @@ TABS.receiver.initialize = function (callback) {
MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val()); MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val());
function save_rc_map() { function save_rc_map() {
MSP.send_message(MSP_codes.MSP_SET_RCMAP, MSP.crunch(MSP_codes.MSP_SET_RCMAP), false, save_misc); MSP.send_message(MSP_codes.MSP_SET_RX_MAP, MSP.crunch(MSP_codes.MSP_SET_RX_MAP), false, save_misc);
} }
function save_misc() { function save_misc() {