mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 21:05:30 +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:
commit
2d6feb0e6a
25 changed files with 1425 additions and 111 deletions
104
js/msp.js
104
js/msp.js
|
@ -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;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue