diff --git a/_locales/en/messages.json b/_locales/en/messages.json index 3583364d..9f64c2bc 100755 --- a/_locales/en/messages.json +++ b/_locales/en/messages.json @@ -452,10 +452,10 @@ "message": "Magnetometer Declination [deg]" }, "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": { - "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": { "message": "Minimum Throttle" diff --git a/js/backup_restore.js b/js/backup_restore.js index 7e9d4523..781d8b1a 100644 --- a/js/backup_restore.js +++ b/js/backup_restore.js @@ -74,20 +74,25 @@ function configuration_backup(callback) { } 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_RCMAP, + MSP_codes.MSP_RX_MAP, MSP_codes.MSP_BF_CONFIG, MSP_codes.MSP_CF_SERIAL_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() { var codeKey = 0; - + function fetch_unique_data_item() { if (codeKey < uniqueData.length) { MSP.send_message(uniqueData[codeKey], false, false, function () { @@ -95,20 +100,18 @@ function configuration_backup(callback) { fetch_unique_data_item(); }); } 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.RCMAP = jQuery.extend(true, [], RC_MAP); configuration.BF_CONFIG = jQuery.extend(true, {}, BF_CONFIG); configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG); 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(); } } - + // start fetching fetch_unique_data_item(); } @@ -408,9 +411,28 @@ function configuration_restore(callback) { 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) { GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount])); } + return true; } @@ -496,26 +518,27 @@ function configuration_restore(callback) { var codeKey = 0; 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_RCMAP, + MSP_codes.MSP_SET_RX_MAP, MSP_codes.MSP_SET_BF_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() { - // Disabled, cleanflight does not use MSP_BOX. - /* - AUX_CONFIG_values = configuration.AUX; - */ MISC = configuration.MISC; RC_MAP = configuration.RCMAP; BF_CONFIG = configuration.BF_CONFIG; SERIAL_CONFIG = configuration.SERIAL_CONFIG; LED_STRIP = configuration.LED_STRIP; + ARMING_CONFIG = configuration.ARMING_CONFIG; + FC_CONFIG = configuration.FC_CONFIG; } function send_unique_data_item() { @@ -530,7 +553,9 @@ function configuration_restore(callback) { } load_objects(); - + + update_unique_data_list(); + // start uploading send_unique_data_item(); } diff --git a/js/data_storage.js b/js/data_storage.js index 312dce54..8323a07e 100755 --- a/js/data_storage.js +++ b/js/data_storage.js @@ -77,10 +77,6 @@ var RC_tuning = { var AUX_CONFIG = []; var AUX_CONFIG_IDS = []; -//Disabled, cleanflight does not use MSP_BOX. -/* -var AUX_CONFIG_values = []; -*/ var MODE_RANGES = []; var ADJUSTMENT_RANGES = []; @@ -141,7 +137,9 @@ var ARMING_CONFIG = { disarm_kill_switch: 0 }; -var LOOP_TIME = 0; +var FC_CONFIG = { + loopTime: 0 +}; var MISC = { midrc: 0, diff --git a/js/msp.js b/js/msp.js index c3d787f7..ebb869c3 100644 --- a/js/msp.js +++ b/js/msp.js @@ -24,11 +24,11 @@ var MSP_codes = { MSP_SET_PID_CONTROLLER: 60, MSP_ARMING_CONFIG: 61, MSP_SET_ARMING_CONFIG: 62, - MSP_LOOP_TIME: 63, - MSP_SET_LOOP_TIME: 64, MSP_DATAFLASH_SUMMARY: 70, MSP_DATAFLASH_READ: 71, MSP_DATAFLASH_ERASE: 72, + MSP_LOOP_TIME: 73, + MSP_SET_LOOP_TIME: 74, // Multiwii MSP commands MSP_IDENT: 100, @@ -82,8 +82,8 @@ var MSP_codes = { MSP_GPS_SV_INFO: 164, // get Signal Strength // 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_RX_MAP: 64, // get channel map (also returns number of channels total) + MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save MSP_SET_REBOOT: 68, // reboot settings @@ -360,7 +360,7 @@ var MSP = { break; case MSP_codes.MSP_LOOP_TIME: if (CONFIG.apiVersion >= 1.8) { - LOOP_TIME = data.getInt16(0, 1); + FC_CONFIG.loopTime = data.getInt16(0, 1); } break; case MSP_codes.MSP_MISC: // 22 bytes @@ -519,14 +519,14 @@ var MSP = { } break; // 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 for (var i = 0; i < data.byteLength; i++) { RC_MAP.push(data.getUint8(i)); } break; - case MSP_codes.MSP_SET_RCMAP: + case MSP_codes.MSP_SET_RX_MAP: console.log('RCMAP saved'); break; case MSP_codes.MSP_BF_CONFIG: @@ -774,8 +774,13 @@ var MSP = { case MSP_codes.MSP_SET_PID_CONTROLLER: console.log('PID controller changed'); 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: console.log('Unknown code detected: ' + code); } @@ -969,7 +974,7 @@ MSP.crunch = function (code) { } break; */ - case MSP_codes.MSP_SET_RCMAP: + case MSP_codes.MSP_SET_RX_MAP: for (var i = 0; i < RC_MAP.length; i++) { buffer.push(RC_MAP[i]); } @@ -981,16 +986,12 @@ MSP.crunch = function (code) { buffer.push(highByte(CONFIG.accelerometerTrims[1])); break; case MSP_codes.MSP_SET_ARMING_CONFIG: - if (CONFIG.apiVersion >= 1.8) { - buffer.push(ARMING_CONFIG.auto_disarm_delay); - buffer.push(ARMING_CONFIG.disarm_kill_switch); - } + buffer.push(ARMING_CONFIG.auto_disarm_delay); + buffer.push(ARMING_CONFIG.disarm_kill_switch); break; case MSP_codes.MSP_SET_LOOP_TIME: - if (CONFIG.apiVersion >= 1.8) { - buffer.push(lowByte(LOOP_TIME)); - buffer.push(highByte(LOOP_TIME)); - } + buffer.push(lowByte(FC_CONFIG.loopTime)); + buffer.push(highByte(FC_CONFIG.loopTime)); break; case MSP_codes.MSP_SET_MISC: buffer.push(lowByte(MISC.midrc)); diff --git a/tabs/configuration.js b/tabs/configuration.js index 45918fe7..6da1f1fc 100644 --- a/tabs/configuration.js +++ b/tabs/configuration.js @@ -23,7 +23,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { } 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() { @@ -260,7 +260,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) { $('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay); $('input[name="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch); if(bit_check(BF_CONFIG.features, 4 + 1))//MOTOR_STOP - $('div.disarmdelay').slideDown(); + $('div.disarmdelay').show(); } else $('div.disarm').hide(); @@ -293,11 +293,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) { if (state) { BF_CONFIG.features = bit_set(BF_CONFIG.features, index); if(element.attr('name') === 'MOTOR_STOP') - $('div.disarmdelay').slideDown(); + $('div.disarmdelay').show(); } else { BF_CONFIG.features = bit_clear(BF_CONFIG.features, index); if(element.attr('name') === 'MOTOR_STOP') - $('div.disarmdelay').slideUp(); + $('div.disarmdelay').hide(); } }); diff --git a/tabs/receiver.js b/tabs/receiver.js index 19d75a0d..719c5adf 100644 --- a/tabs/receiver.js +++ b/tabs/receiver.js @@ -18,7 +18,7 @@ TABS.receiver.initialize = function (callback) { } 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() { @@ -281,7 +281,7 @@ TABS.receiver.initialize = function (callback) { MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val()); 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() {