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

Merge branch 'cleanflight/development' into NewPIDFunctions

# Conflicts:
#	_locales/en/messages.json
#	js/backup_restore.js
#	js/data_storage.js
#	js/msp.js
#	tabs/configuration.html
This commit is contained in:
skaman82 2015-12-15 01:43:24 +01:00
commit 2d6feb0e6a
25 changed files with 1425 additions and 111 deletions

View file

@ -105,6 +105,11 @@ function configuration_backup(callback) {
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
uniqueData.push(MSP_codes.MSP_3D);
}
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
uniqueData.push(MSP_codes.MSP_RX_CONFIG);
uniqueData.push(MSP_codes.MSP_FAILSAFE_CONFIG);
uniqueData.push(MSP_codes.MSP_RXFAIL_CONFIG);
}
}
update_unique_data_list();
@ -132,6 +137,11 @@ function configuration_backup(callback) {
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
configuration._3D = jQuery.extend(true, {}, _3D);
}
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
configuration.RX_CONFIG = jQuery.extend(true, {}, RX_CONFIG);
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FAILSAFE_CONFIG);
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], RXFAIL_CONFIG);
}
save();
}
@ -514,8 +524,9 @@ function configuration_restore(callback) {
}
if (compareVersions(migratedVersion, '0.66.0') && !compareVersions(configuration.apiVersion, '1.15.0')) {
// api 1.14 exposes deadband and yaw_deadband
// api 1.14 exposes deadband and yaw_deadband
for (var profileIndex = 0; profileIndex < configuration.profiles.length; profileIndex++) {
if (configuration.profile[profileIndex].RCcontrols == undefined) {
@ -530,6 +541,51 @@ function configuration_restore(callback) {
appliedMigrationsCount++;
}
// api 1.15 exposes RX_CONFIG, FAILSAFE_CONFIG and RXFAIL_CONFIG configuration
if (configuration.RX_CONFIG == undefined) {
configuration.RX_CONFIG = {
serialrx_provider: 0,
spektrum_sat_bind: 0,
midrc: 1500,
mincheck: 1100,
maxcheck: 1900,
rx_min_usec: 885,
rx_max_usec: 2115
};
}
if (configuration.FAILSAFE_CONFIG == undefined) {
configuration.FAILSAFE_CONFIG = {
failsafe_delay: 10,
failsafe_off_delay: 200,
failsafe_throttle: 1000,
failsafe_kill_switch: 0,
failsafe_throttle_low_delay: 100,
failsafe_procedure: 0
};
}
if (configuration.RXFAIL_CONFIG == undefined) {
configuration.RXFAIL_CONFIG = [
{mode: 0, value: 1500},
{mode: 0, value: 1500},
{mode: 0, value: 1500},
{mode: 0, value: 875}
];
for (var i = 0; i < 14; i++) {
var rxfailChannel = {
mode: 1,
value: 1500
};
configuration.RXFAIL_CONFIG.push(rxfailChannel);
}
}
appliedMigrationsCount++;
}
if (appliedMigrationsCount > 0) {
GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
}
@ -645,6 +701,11 @@ function configuration_restore(callback) {
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
uniqueData.push(MSP_codes.MSP_SET_3D);
}
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG);
uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG);
uniqueData.push(MSP_codes.MSP_SET_RXFAIL_CONFIG);
}
}
function load_objects() {
@ -656,6 +717,9 @@ function configuration_restore(callback) {
ARMING_CONFIG = configuration.ARMING_CONFIG;
FC_CONFIG = configuration.FC_CONFIG;
_3D = configuration._3D;
RX_CONFIG = configuration.RX_CONFIG;
FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
}
function send_unique_data_item() {
@ -708,4 +772,4 @@ function configuration_restore(callback) {
upload();
}
}
}

View file

@ -179,9 +179,32 @@ var DATAFLASH = {
usedSize: 0
};
<<<<<<< HEAD
var RC_controls = {
deadband: 0,
yaw_deadband: 0,
alt_hold_deadband: 0,
alt_hold_fast_change: 0
};
=======
var RX_CONFIG = {
serialrx_provider: 0,
maxcheck: 0,
midrc: 0,
mincheck: 0,
spektrum_sat_bind: 0,
rx_min_usec: 0,
rx_max_usec: 0
};
var FAILSAFE_CONFIG = {
failsafe_delay: 0,
failsafe_off_delay: 0,
failsafe_throttle: 0,
failsafe_kill_switch: 0,
failsafe_throttle_low_delay: 0,
failsafe_procedure: 0
};
var RXFAIL_CONFIG = [];
>>>>>>> cleanflight/development

View file

@ -18,6 +18,7 @@ var GUI_control = function () {
'help'
];
this.defaultAllowedTabsWhenConnected = [
'failsafe',
'adjustments',
'auxiliary',
'cli',

104
js/msp.js
View file

@ -13,6 +13,8 @@ var MSP_codes = {
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_STRIP_CONFIG: 48,
MSP_SET_LED_STRIP_CONFIG: 49,
MSP_ADJUSTMENT_RANGES: 52,
@ -29,6 +31,10 @@ var MSP_codes = {
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,
// Multiwii MSP commands
MSP_IDENT: 100,
@ -766,6 +772,7 @@ var MSP = {
ADJUSTMENT_RANGES.push(adjustmentRange);
}
break;
case MSP_codes.MSP_CHANNEL_FORWARDING:
for (var i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i ++) {
var channelIndex = data.getUint8(i);
@ -777,6 +784,56 @@ var MSP = {
}
break;
case MSP_codes.MSP_RX_CONFIG:
var offset = 0;
RX_CONFIG.serialrx_provider = data.getUint8(offset, 1);
offset++;
RX_CONFIG.maxcheck = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.midrc = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.mincheck = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.spektrum_sat_bind = data.getUint8(offset, 1);
offset++;
RX_CONFIG.rx_min_usec = data.getUint16(offset, 1);
offset += 2;
RX_CONFIG.rx_max_usec = data.getUint16(offset, 1);
offset += 2;
break;
case MSP_codes.MSP_FAILSAFE_CONFIG:
var offset = 0;
FAILSAFE_CONFIG.failsafe_delay = data.getUint8(offset, 1);
offset++;
FAILSAFE_CONFIG.failsafe_off_delay = data.getUint8(offset, 1);
offset++;
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1);
offset += 2;
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1);
offset++;
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1);
offset += 2;
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1);
offset++;
break;
case MSP_codes.MSP_RXFAIL_CONFIG:
RXFAIL_CONFIG = []; // empty the array as new data is coming in
var channelCount = data.byteLength / 3;
var offset = 0;
for (var i = 0; offset < data.byteLength && i < channelCount; i++, offset++) {
var rxfailChannel = {
mode: data.getUint8(offset++, 1),
value: data.getUint16(offset++, 1)
};
RXFAIL_CONFIG.push(rxfailChannel);
}
break;
case MSP_codes.MSP_LED_STRIP_CONFIG:
LED_STRIP = [];
@ -863,7 +920,15 @@ var MSP = {
case MSP_codes.MSP_SET_RESET_CURR_PID:
console.log('Current PID profile reset');
break;
case MSP_codes.MSP_SET_RX_CONFIG:
console.log('Rx config saved');
break;
case MSP_codes.MSP_SET_RXFAIL_CONFIG:
console.log('Rxfail config saved');
break;
case MSP_codes.MSP_SET_FAILSAFE_CONFIG:
console.log('Failsafe config saved');
break;
default:
console.log('Unknown code detected: ' + code);
} else {
@ -1049,7 +1114,7 @@ MSP.crunch = function (code) {
buffer.push(lowByte(RC_tuning.dynamic_THR_breakpoint));
buffer.push(highByte(RC_tuning.dynamic_THR_breakpoint));
}
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
buffer.push(Math.round(RC_tuning.RC_YAW_EXPO * 100));
}
break;
@ -1105,6 +1170,41 @@ MSP.crunch = function (code) {
buffer.push(Math.round(MISC.vbatmaxcellvoltage * 10));
buffer.push(Math.round(MISC.vbatwarningcellvoltage * 10));
break;
case MSP_codes.MSP_SET_RX_CONFIG:
buffer.push(RX_CONFIG.serialrx_provider);
buffer.push(lowByte(RX_CONFIG.maxcheck));
buffer.push(highByte(RX_CONFIG.maxcheck));
buffer.push(lowByte(RX_CONFIG.midrc));
buffer.push(highByte(RX_CONFIG.midrc));
buffer.push(lowByte(RX_CONFIG.mincheck));
buffer.push(highByte(RX_CONFIG.mincheck));
buffer.push(RX_CONFIG.spektrum_sat_bind);
buffer.push(lowByte(RX_CONFIG.rx_min_usec));
buffer.push(highByte(RX_CONFIG.rx_min_usec));
buffer.push(lowByte(RX_CONFIG.rx_max_usec));
buffer.push(highByte(RX_CONFIG.rx_max_usec));
break;
case MSP_codes.MSP_SET_FAILSAFE_CONFIG:
buffer.push(FAILSAFE_CONFIG.failsafe_delay);
buffer.push(FAILSAFE_CONFIG.failsafe_off_delay);
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle));
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle));
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
break;
case MSP_codes.MSP_SET_RXFAIL_CONFIG:
for (var i = 0; i < RXFAIL_CONFIG.length; i++) {
buffer.push(RXFAIL_CONFIG[i].mode);
buffer.push(lowByte(RXFAIL_CONFIG[i].value));
buffer.push(highByte(RXFAIL_CONFIG[i].value));
}
break;
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
for (var i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;