Removed hack for MSP_SPECIAL_PARAMETERS.
parent
1ddd3f4dbe
commit
95c3bf272f
7
js/fc.js
7
js/fc.js
|
@ -39,7 +39,6 @@ var FAILSAFE_CONFIG;
|
|||
var RXFAIL_CONFIG;
|
||||
var PID_ADVANCED_CONFIG;
|
||||
var FILTER_CONFIG;
|
||||
var SPECIAL_PARAMETERS;
|
||||
var ADVANCED_TUNING;
|
||||
var SENSOR_CONFIG;
|
||||
|
||||
|
@ -287,15 +286,11 @@ var FC = {
|
|||
pidMaxVelocityYaw: 0
|
||||
};
|
||||
|
||||
SPECIAL_PARAMETERS = {
|
||||
escDesyncProtection: 0
|
||||
};
|
||||
|
||||
SENSOR_CONFIG = {
|
||||
acc_hardware: 0,
|
||||
baro_hardware: 0,
|
||||
mag_hardware: 0
|
||||
}
|
||||
};
|
||||
|
||||
RX_CONFIG = {
|
||||
serialrx_provider: 0,
|
||||
|
|
|
@ -71,8 +71,8 @@ var MSPCodes = {
|
|||
MSP_SET_PID_ADVANCED: 95,
|
||||
MSP_SENSOR_CONFIG: 96,
|
||||
MSP_SET_SENSOR_CONFIG: 97,
|
||||
MSP_SPECIAL_PARAMETERS: 98,
|
||||
MSP_SET_SPECIAL_PARAMETERS: 99,
|
||||
// MSP_SPECIAL_PARAMETERS: 98, removed
|
||||
//MSP_SET_SPECIAL_PARAMETERS: 99, removed
|
||||
MSP_IDENT: 100, // Not used
|
||||
MSP_STATUS: 101,
|
||||
MSP_RAW_IMU: 102,
|
||||
|
|
|
@ -155,7 +155,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
RC_tuning.RC_YAW_EXPO = parseFloat((data.readU8() / 100).toFixed(2));
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
RC_tuning.rcYawRate = parseFloat((data.readU8() / 100).toFixed(2));
|
||||
} else if (semver.lt(CONFIG.flightControllerVersion, "2.9.0")) {
|
||||
} else {
|
||||
RC_tuning.rcYawRate = 0;
|
||||
}
|
||||
} else {
|
||||
|
@ -652,18 +652,6 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
ADVANCED_TUNING.pidMaxVelocityYaw = data.readU16();
|
||||
}
|
||||
break;
|
||||
case MSPCodes.MSP_SPECIAL_PARAMETERS:
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.0")) {
|
||||
RC_tuning.rcYawRate = parseFloat((data.readU8() / 100).toFixed(2));
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
RX_CONFIG.airModeActivateThreshold = data.readU16();
|
||||
RX_CONFIG.rcSmoothInterval = data.readU8()
|
||||
SPECIAL_PARAMETERS.escDesyncProtection = data.readU16();
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSPCodes.MSP_SENSOR_CONFIG:
|
||||
SENSOR_CONFIG.acc_hardware = data.readU8();
|
||||
SENSOR_CONFIG.baro_hardware = data.readU8();
|
||||
|
@ -916,9 +904,6 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
case MSPCodes.MSP_SET_SENSOR_CONFIG:
|
||||
console.log('Sensor config parameters set');
|
||||
break;
|
||||
case MSPCodes.MSP_SET_SPECIAL_PARAMETERS:
|
||||
console.log('Special parameters set');
|
||||
break;
|
||||
default:
|
||||
console.log('Unknown code detected: ' + code);
|
||||
} else {
|
||||
|
@ -1185,16 +1170,6 @@ MspHelper.prototype.crunch = function(code) {
|
|||
.push8(ADVANCED_TUNING.vbatPidCompensation);
|
||||
}
|
||||
break;
|
||||
case MSPCodes.MSP_SET_SPECIAL_PARAMETERS:
|
||||
if (semver.lt(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
buffer.push8(Math.round(RC_tuning.rcYawRate * 100));
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
buffer.push16(RX_CONFIG.airModeActivateThreshold)
|
||||
.push8(RX_CONFIG.rcSmoothInterval)
|
||||
.push16(SPECIAL_PARAMETERS.escDesyncProtection);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSPCodes.MSP_SET_SENSOR_CONFIG:
|
||||
buffer.push8(SENSOR_CONFIG.acc_hardware)
|
||||
.push8(SENSOR_CONFIG.baro_hardware)
|
||||
|
|
|
@ -25,10 +25,6 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
return MSP.promise(MSPCodes.MSP_PIDNAMES)
|
||||
}).then(function() {
|
||||
return MSP.promise(MSPCodes.MSP_PID);
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.0") && semver.lt(CONFIG.flightControllerVersion, "2.9.1")) {
|
||||
return MSP.promise(MSPCodes.MSP_SPECIAL_PARAMETERS);
|
||||
}
|
||||
}).then(function() {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
return MSP.promise(MSPCodes.MSP_PID_ADVANCED);
|
||||
|
@ -844,10 +840,6 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
return promise;
|
||||
}).then(function () {
|
||||
return MSP.promise(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID));
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.9.0") && semver.lt(CONFIG.flightControllerVersion, "3.0.0")) {
|
||||
return MSP.promise(MSPCodes.MSP_SET_SPECIAL_PARAMETERS, mspHelper.crunch(MSPCodes.MSP_SET_SPECIAL_PARAMETERS));
|
||||
}
|
||||
}).then(function () {
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||
return MSP.promise(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED));
|
||||
|
|
Loading…
Reference in New Issue