mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-19 06:15:13 +03:00
update servo tab on configurator
1) work around 1.9.0 MSP buffer size bug. 2) support updated API for 1.12 (CF >= 1.10.0)
This commit is contained in:
parent
c0138f5f82
commit
1cb64130cc
4 changed files with 250 additions and 78 deletions
220
js/msp.js
220
js/msp.js
|
@ -51,7 +51,7 @@ var MSP_codes = {
|
|||
MSP_PIDNAMES: 117,
|
||||
MSP_WP: 118,
|
||||
MSP_BOXIDS: 119,
|
||||
MSP_SERVO_CONF: 120,
|
||||
MSP_SERVO_CONFIGURATIONS: 120,
|
||||
|
||||
MSP_SET_RAW_RC: 200,
|
||||
MSP_SET_RAW_GPS: 201,
|
||||
|
@ -65,10 +65,13 @@ var MSP_codes = {
|
|||
MSP_SET_WP: 209,
|
||||
MSP_SELECT_SETTING: 210,
|
||||
MSP_SET_HEAD: 211,
|
||||
MSP_SET_SERVO_CONF: 212,
|
||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||
MSP_SET_MOTOR: 214,
|
||||
|
||||
// MSP_BIND: 240,
|
||||
|
||||
MSP_SERVO_MIX_RULES: 241,
|
||||
MSP_SET_SERVO_MIX_RULE: 242,
|
||||
|
||||
MSP_EEPROM_WRITE: 250,
|
||||
|
||||
|
@ -80,7 +83,7 @@ var MSP_codes = {
|
|||
MSP_ACC_TRIM: 240, // get acc angle trim values
|
||||
MSP_SET_ACC_TRIM: 239, // set acc angle trim values
|
||||
MSP_GPS_SV_INFO: 164, // get Signal Strength
|
||||
|
||||
|
||||
// Additional private MSP for baseflight configurator (yes thats us \o/)
|
||||
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
|
||||
|
@ -444,22 +447,48 @@ var MSP = {
|
|||
AUX_CONFIG_IDS.push(data.getUint8(i));
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SERVO_CONF:
|
||||
case MSP_codes.MSP_SERVO_MIX_RULES:
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_SERVO_CONFIGURATIONS:
|
||||
SERVO_CONFIG = []; // empty the array as new data is coming in
|
||||
|
||||
if (data.byteLength % 13 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 13) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'angleAtMin': data.getInt8(i + 7),
|
||||
'angleAtMax': data.getInt8(i + 8),
|
||||
'reversedChannels': data.getInt32(i + 9)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.12.0")) {
|
||||
if (data.byteLength % 14 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 14) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'angleAtMin': data.getUint8(i + 7),
|
||||
'angleAtMax': data.getUint8(i + 8),
|
||||
'indexOfChannelToForward': data.getInt8(i + 9),
|
||||
'reversedInputSources': data.getUint32(i + 10)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (data.byteLength % 7 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 7) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
|
||||
if (semver.eq(CONFIG.apiVersion, '1.10.0')) {
|
||||
// drop two unused servo configurations due to MSP rx buffer to small)
|
||||
while (SERVO_CONFIG.length > 8) {
|
||||
SERVO_CONFIG.pop();
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -493,7 +522,7 @@ var MSP = {
|
|||
case MSP_codes.MSP_SELECT_SETTING:
|
||||
console.log('Profile selected');
|
||||
break;
|
||||
case MSP_codes.MSP_SET_SERVO_CONF:
|
||||
case MSP_codes.MSP_SET_SERVO_CONFIGURATION:
|
||||
console.log('Servo Configuration saved');
|
||||
break;
|
||||
case MSP_codes.MSP_EEPROM_WRITE:
|
||||
|
@ -1038,32 +1067,6 @@ MSP.crunch = function (code) {
|
|||
buffer.push(MISC.vbatmaxcellvoltage * 10);
|
||||
buffer.push(MISC.vbatwarningcellvoltage * 10);
|
||||
break;
|
||||
case MSP_codes.MSP_SET_SERVO_CONF:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].min));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].min));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].max));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].max));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].middle));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].middle));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].rate));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.11.0")) {
|
||||
buffer.push(SERVO_CONFIG[i].angleAtMin);
|
||||
buffer.push(SERVO_CONFIG[i].angleAtMax);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.12.0")) {
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 0));
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 1));
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 2));
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 3));
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
var out = SERVO_CONFIG[i].indexOfChannelToForward;
|
||||
|
@ -1143,7 +1146,102 @@ MSP.dataflashRead = function(address, onDataCallback) {
|
|||
onDataCallback(address, null);
|
||||
}
|
||||
});
|
||||
} ;
|
||||
};
|
||||
|
||||
MSP.sendServoMixRules = function(onCompleteCallback) {
|
||||
// TODO implement
|
||||
onCompleteCallback();
|
||||
};
|
||||
|
||||
MSP.sendServoConfigurations = function(onCompleteCallback) {
|
||||
var nextFunction = send_next_servo_configuration;
|
||||
|
||||
var servoIndex = 0;
|
||||
|
||||
if (SERVO_CONFIG.length == 0) {
|
||||
onCompleteCallback();
|
||||
}
|
||||
|
||||
nextFunction();
|
||||
|
||||
function send_next_servo_configuration() {
|
||||
|
||||
var buffer = [];
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
// send all in one go
|
||||
// 1.9.0 had a bug where the MSP input buffer was too small, limit to 8.
|
||||
for (var i = 0; i < SERVO_CONFIG.length && i < 8; i++) {
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].min));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].min));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].max));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].max));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].middle));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].middle));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].rate));
|
||||
}
|
||||
|
||||
nextFunction = send_channel_forwarding;
|
||||
} else {
|
||||
// send one at a time, with index
|
||||
|
||||
var servoConfiguration = SERVO_CONFIG[servoIndex];
|
||||
|
||||
buffer.push(servoIndex);
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.min));
|
||||
buffer.push(highByte(servoConfiguration.min));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.max));
|
||||
buffer.push(highByte(servoConfiguration.max));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.middle));
|
||||
buffer.push(highByte(servoConfiguration.middle));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.rate));
|
||||
|
||||
buffer.push(servoConfiguration.angleAtMin);
|
||||
buffer.push(servoConfiguration.angleAtMax);
|
||||
|
||||
var out = servoConfiguration.indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 0));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 1));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 2));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 3));
|
||||
|
||||
// prepare for next iteration
|
||||
servoIndex++;
|
||||
if (servoIndex == SERVO_CONFIG.length) {
|
||||
nextFunction = onCompleteCallback;
|
||||
}
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_SERVO_CONFIGURATION, buffer, false, nextFunction);
|
||||
}
|
||||
|
||||
function send_channel_forwarding() {
|
||||
var buffer = [];
|
||||
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
var out = SERVO_CONFIG[i].indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
}
|
||||
|
||||
nextFunction = onCompleteCallback;
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_CHANNEL_FORWARDING, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
MSP.sendModeRanges = function(onCompleteCallback) {
|
||||
var nextFunction = send_next_mode_range;
|
||||
|
@ -1161,12 +1259,12 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
|||
|
||||
var modeRange = MODE_RANGES[modeRangeIndex];
|
||||
|
||||
var AUX_val_buffer_out = [];
|
||||
AUX_val_buffer_out.push(modeRangeIndex);
|
||||
AUX_val_buffer_out.push(modeRange.id);
|
||||
AUX_val_buffer_out.push(modeRange.auxChannelIndex);
|
||||
AUX_val_buffer_out.push((modeRange.range.start - 900) / 25);
|
||||
AUX_val_buffer_out.push((modeRange.range.end - 900) / 25);
|
||||
var buffer = [];
|
||||
buffer.push(modeRangeIndex);
|
||||
buffer.push(modeRange.id);
|
||||
buffer.push(modeRange.auxChannelIndex);
|
||||
buffer.push((modeRange.range.start - 900) / 25);
|
||||
buffer.push((modeRange.range.end - 900) / 25);
|
||||
|
||||
// prepare for next iteration
|
||||
modeRangeIndex++;
|
||||
|
@ -1174,7 +1272,7 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
|||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, AUX_val_buffer_out, false, nextFunction);
|
||||
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1194,14 +1292,14 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
|||
|
||||
var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex];
|
||||
|
||||
var ADJUSTMENT_val_buffer_out = [];
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRangeIndex);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.slotIndex);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxChannelIndex);
|
||||
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.start - 900) / 25);
|
||||
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.end - 900) / 25);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.adjustmentFunction);
|
||||
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxSwitchChannelIndex);
|
||||
var buffer = [];
|
||||
buffer.push(adjustmentRangeIndex);
|
||||
buffer.push(adjustmentRange.slotIndex);
|
||||
buffer.push(adjustmentRange.auxChannelIndex);
|
||||
buffer.push((adjustmentRange.range.start - 900) / 25);
|
||||
buffer.push((adjustmentRange.range.end - 900) / 25);
|
||||
buffer.push(adjustmentRange.adjustmentFunction);
|
||||
buffer.push(adjustmentRange.auxSwitchChannelIndex);
|
||||
|
||||
// prepare for next iteration
|
||||
adjustmentRangeIndex++;
|
||||
|
@ -1209,7 +1307,7 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
|||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, ADJUSTMENT_val_buffer_out, false, nextFunction);
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue