1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-17 21:35:33 +03:00

Add Support for v2.9.1 MSP

This commit is contained in:
U-DESKTOP-12PPI61\boris.bozic 2016-08-02 21:54:50 +02:00
parent 33f14df10d
commit 9f5cce77d8
3 changed files with 29 additions and 24 deletions

View file

@ -297,10 +297,12 @@ var MSP = {
CONFIG.mode = data.getUint32(6, 1); CONFIG.mode = data.getUint32(6, 1);
CONFIG.profile = data.getUint8(10); CONFIG.profile = data.getUint8(10);
CONFIG.cpuload = data.getUint16(11, 1); CONFIG.cpuload = data.getUint16(11, 1);
CONFIG.numProfiles = data.getUint8(13); if (semver.gt(CONFIG.flightControllerVersion, "2.9.1")) {
CONFIG.rateProfile = data.getUint8(14); CONFIG.numProfiles = data.getUint8(13);
CONFIG.rateProfile = data.getUint8(14);
TABS.pid_tuning.checkUpdateProfile(true); TABS.pid_tuning.checkUpdateProfile(true);
}
sensor_status(CONFIG.activeSensors); sensor_status(CONFIG.activeSensors);
$('span.i2c-error').text(CONFIG.i2cError); $('span.i2c-error').text(CONFIG.i2cError);
@ -407,9 +409,9 @@ var MSP = {
} }
if (semver.gte(CONFIG.apiVersion, "1.10.0")) { if (semver.gte(CONFIG.apiVersion, "1.10.0")) {
RC_tuning.RC_YAW_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); RC_tuning.RC_YAW_EXPO = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
if (semver.gte(CONFIG.apiVersion, "1.20.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
RC_tuning.rcYawRate = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); RC_tuning.rcYawRate = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
} else if (semver.lt(CONFIG.apiVersion, "1.16.0")) { } else if (semver.lt(CONFIG.flightControllerVersion, "2.9.0")) {
RC_tuning.rcYawRate = 0; RC_tuning.rcYawRate = 0;
} }
} else { } else {
@ -1001,15 +1003,16 @@ var MSP = {
} }
break; break;
case MSP_codes.MSP_SPECIAL_PARAMETERS: case MSP_codes.MSP_SPECIAL_PARAMETERS:
var offset = 0; var offset = 0;
RC_tuning.rcYawRate = parseFloat((data.getUint8(offset++) / 100).toFixed(2)); if (semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) { RC_tuning.rcYawRate = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
RX_CONFIG.airModeActivateThreshold = data.getUint16(offset, 1); } else if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
offset += 2; RX_CONFIG.airModeActivateThreshold = data.getUint16(offset, 1);
RX_CONFIG.rcSmoothInterval = data.getUint8(offset++, 1) offset += 2;
SPECIAL_PARAMETERS.escDesyncProtection = data.getUint16(offset, 1); RX_CONFIG.rcSmoothInterval = data.getUint8(offset++, 1)
} SPECIAL_PARAMETERS.escDesyncProtection = data.getUint16(offset, 1);
break; }
break;
case MSP_codes.MSP_SENSOR_CONFIG: case MSP_codes.MSP_SENSOR_CONFIG:
var offset = 0; var offset = 0;
SENSOR_CONFIG.acc_hardware = data.getUint8(offset++, 1); SENSOR_CONFIG.acc_hardware = data.getUint8(offset++, 1);
@ -1477,8 +1480,8 @@ MSP.crunch = function (code) {
} }
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)); buffer.push(Math.round(RC_tuning.RC_YAW_EXPO * 100));
if (semver.gte(CONFIG.apiVersion, "1.20.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
buffer.push(Math.round(RC_tuning.rcYawRate * 100)); buffer.push(Math.round(RC_tuning.rcYawRate * 100));
} }
} }
break; break;
@ -1695,11 +1698,13 @@ MSP.crunch = function (code) {
} }
break; break;
case MSP_codes.MSP_SET_SPECIAL_PARAMETERS: case MSP_codes.MSP_SET_SPECIAL_PARAMETERS:
buffer.push(Math.round(RC_tuning.rcYawRate * 100)); if (semver.lt(CONFIG.flightControllerVersion, "2.9.1")) {
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) { buffer.push(Math.round(RC_tuning.rcYawRate * 100));
buffer.push16(RX_CONFIG.airModeActivateThreshold); if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
buffer.push(RX_CONFIG.rcSmoothInterval); buffer.push16(RX_CONFIG.airModeActivateThreshold);
buffer.push16(SPECIAL_PARAMETERS.escDesyncProtection); buffer.push(RX_CONFIG.rcSmoothInterval);
buffer.push16(SPECIAL_PARAMETERS.escDesyncProtection);
}
} }
break; break;
case MSP_codes.MSP_SET_SENSOR_CONFIG: case MSP_codes.MSP_SET_SENSOR_CONFIG:

View file

@ -267,7 +267,7 @@ function onConnect() {
$('#tabs ul.mode-connected').show(); $('#tabs ul.mode-connected').show();
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false); MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false);
} else { } else {
MSP.send_message(MSP_codes.MSP_STATUS, false, false); MSP.send_message(MSP_codes.MSP_STATUS, false, false);
@ -462,7 +462,7 @@ function update_live_status() {
if (GUI.active_tab != 'cli') { if (GUI.active_tab != 'cli') {
MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false); MSP.send_message(MSP_codes.MSP_BOXNAMES, false, false);
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")) if (semver.gte(CONFIG.flightControllerVersion, "2.9.1"))
MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false); MSP.send_message(MSP_codes.MSP_STATUS_EX, false, false);
else else
MSP.send_message(MSP_codes.MSP_STATUS, false, false); MSP.send_message(MSP_codes.MSP_STATUS, false, false);

View file

@ -26,7 +26,7 @@ TABS.pid_tuning.initialize = function (callback) {
}).then(function() { }).then(function() {
return MSP.promise(MSP_codes.MSP_PID); return MSP.promise(MSP_codes.MSP_PID);
}).then(function () { }).then(function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.9.0") && semver.lt(CONFIG.flightControllerVersion, "3.0.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.9.0") && semver.lt(CONFIG.flightControllerVersion, "2.9.1")) {
return MSP.promise(MSP_codes.MSP_SPECIAL_PARAMETERS); return MSP.promise(MSP_codes.MSP_SPECIAL_PARAMETERS);
} }
}).then(function() { }).then(function() {