mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 21:05:30 +03:00
Changes to MSP to make it work with Betaflight branch 'msp_cleanup'.
This commit is contained in:
parent
b85e23cdcb
commit
6da7383d61
5 changed files with 74 additions and 64 deletions
25
js/fc.js
25
js/fc.js
|
@ -40,7 +40,6 @@ var RXFAIL_CONFIG;
|
||||||
var PID_ADVANCED_CONFIG;
|
var PID_ADVANCED_CONFIG;
|
||||||
var FILTER_CONFIG;
|
var FILTER_CONFIG;
|
||||||
var ADVANCED_TUNING;
|
var ADVANCED_TUNING;
|
||||||
var SPECIAL_PARAMETERS;
|
|
||||||
var SENSOR_CONFIG;
|
var SENSOR_CONFIG;
|
||||||
|
|
||||||
var FC = {
|
var FC = {
|
||||||
|
@ -111,7 +110,8 @@ var FC = {
|
||||||
throttle_MID: 0,
|
throttle_MID: 0,
|
||||||
throttle_EXPO: 0,
|
throttle_EXPO: 0,
|
||||||
dynamic_THR_breakpoint: 0,
|
dynamic_THR_breakpoint: 0,
|
||||||
RC_YAW_EXPO: 0
|
RC_YAW_EXPO: 0,
|
||||||
|
rcYawRate: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
AUX_CONFIG = [];
|
AUX_CONFIG = [];
|
||||||
|
@ -266,16 +266,16 @@ var FC = {
|
||||||
yawItermIgnoreRate: 0,
|
yawItermIgnoreRate: 0,
|
||||||
yaw_p_limit: 0,
|
yaw_p_limit: 0,
|
||||||
deltaMethod: 0,
|
deltaMethod: 0,
|
||||||
vbatPidCompensation: 0
|
vbatPidCompensation: 0,
|
||||||
|
ptermSetpointWeight: 0,
|
||||||
|
dtermSetpointWeight: 0,
|
||||||
|
toleranceBand: 0,
|
||||||
|
toleranceBandReduction: 0,
|
||||||
|
itermThrottleGain: 0,
|
||||||
|
pidMaxVelocity: 0,
|
||||||
|
pidMaxVelocityYaw: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
SPECIAL_PARAMETERS = {
|
|
||||||
RC_RATE_YAW: 0,
|
|
||||||
airModeActivateThreshold: 0,
|
|
||||||
rcSmoothInterval: 0,
|
|
||||||
escDesyncProtection: 0
|
|
||||||
};
|
|
||||||
|
|
||||||
SENSOR_CONFIG = {
|
SENSOR_CONFIG = {
|
||||||
acc_hardware: 0,
|
acc_hardware: 0,
|
||||||
baro_hardware: 0,
|
baro_hardware: 0,
|
||||||
|
@ -289,7 +289,10 @@ var FC = {
|
||||||
mincheck: 0,
|
mincheck: 0,
|
||||||
spektrum_sat_bind: 0,
|
spektrum_sat_bind: 0,
|
||||||
rx_min_usec: 0,
|
rx_min_usec: 0,
|
||||||
rx_max_usec: 0
|
rx_max_usec: 0,
|
||||||
|
rcSmoothing: 0,
|
||||||
|
rcSmoothInterval: 0,
|
||||||
|
airModeActivateThreshold: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
FAILSAFE_CONFIG = {
|
FAILSAFE_CONFIG = {
|
||||||
|
|
82
js/msp.js
82
js/msp.js
|
@ -51,16 +51,14 @@ var MSP_codes = {
|
||||||
MSP_OSD_CHAR_WRITE: 87,
|
MSP_OSD_CHAR_WRITE: 87,
|
||||||
MSP_VTX_CONFIG: 88,
|
MSP_VTX_CONFIG: 88,
|
||||||
MSP_SET_VTX_CONFIG: 89,
|
MSP_SET_VTX_CONFIG: 89,
|
||||||
MSP_PID_ADVANCED_CONFIG: 90,
|
MSP_ADVANCED_CONFIG: 90,
|
||||||
MSP_SET_PID_ADVANCED_CONFIG: 91,
|
MSP_SET_ADVANCED_CONFIG: 91,
|
||||||
MSP_FILTER_CONFIG: 92,
|
MSP_FILTER_CONFIG: 92,
|
||||||
MSP_SET_FILTER_CONFIG: 93,
|
MSP_SET_FILTER_CONFIG: 93,
|
||||||
MSP_ADVANCED_TUNING: 94,
|
MSP_PID_ADVANCED: 94,
|
||||||
MSP_SET_ADVANCED_TUNING: 95,
|
MSP_SET_PID_ADVANCED: 95,
|
||||||
MSP_SENSOR_CONFIG: 96,
|
MSP_SENSOR_CONFIG: 96,
|
||||||
MSP_SET_SENSOR_CONFIG: 97,
|
MSP_SET_SENSOR_CONFIG: 97,
|
||||||
MSP_SPECIAL_PARAMETERS: 98,
|
|
||||||
MSP_SET_SPECIAL_PARAMETERS: 99,
|
|
||||||
|
|
||||||
// Multiwii MSP commands
|
// Multiwii MSP commands
|
||||||
MSP_IDENT: 100,
|
MSP_IDENT: 100,
|
||||||
|
@ -406,6 +404,11 @@ 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")) {
|
||||||
|
RC_tuning.rcYawRate = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
|
||||||
|
} else {
|
||||||
|
RC_tuning.rcYawRate = 0;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
RC_tuning.RC_YAW_EXPO = 0;
|
RC_tuning.RC_YAW_EXPO = 0;
|
||||||
}
|
}
|
||||||
|
@ -901,6 +904,10 @@ var MSP = {
|
||||||
offset += 2;
|
offset += 2;
|
||||||
RX_CONFIG.rx_max_usec = data.getUint16(offset, 1);
|
RX_CONFIG.rx_max_usec = data.getUint16(offset, 1);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
|
RX_CONFIG.rcSmoothing = data.getUint8(offset, 1);
|
||||||
|
RX_CONFIG.rcSmoothInterval = data.getUint8(offset, 1);
|
||||||
|
RX_CONFIG.airModeActivateThreshold = data.getUint16(offset, 1);
|
||||||
|
offset += 2;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_FAILSAFE_CONFIG:
|
case MSP_codes.MSP_FAILSAFE_CONFIG:
|
||||||
|
@ -936,7 +943,7 @@ var MSP = {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_PID_ADVANCED_CONFIG:
|
case MSP_codes.MSP_ADVANCED_CONFIG:
|
||||||
var offset = 0;
|
var offset = 0;
|
||||||
PID_ADVANCED_CONFIG.gyro_sync_denom = data.getUint8(offset++, 1);
|
PID_ADVANCED_CONFIG.gyro_sync_denom = data.getUint8(offset++, 1);
|
||||||
PID_ADVANCED_CONFIG.pid_process_denom = data.getUint8(offset++, 1);
|
PID_ADVANCED_CONFIG.pid_process_denom = data.getUint8(offset++, 1);
|
||||||
|
@ -952,8 +959,8 @@ var MSP = {
|
||||||
FILTER_CONFIG.yaw_lpf_hz = data.getUint16(offset, 1);
|
FILTER_CONFIG.yaw_lpf_hz = data.getUint16(offset, 1);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_ADVANCED_TUNING:
|
case MSP_codes.MSP_PID_ADVANCED:
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
var offset = 0;
|
var offset = 0;
|
||||||
ADVANCED_TUNING.rollPitchItermIgnoreRate = data.getUint16(offset, 1);
|
ADVANCED_TUNING.rollPitchItermIgnoreRate = data.getUint16(offset, 1);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
|
@ -963,17 +970,15 @@ var MSP = {
|
||||||
offset += 2;
|
offset += 2;
|
||||||
ADVANCED_TUNING.deltaMethod = data.getUint8(offset++, 1);
|
ADVANCED_TUNING.deltaMethod = data.getUint8(offset++, 1);
|
||||||
ADVANCED_TUNING.vbatPidCompensation = data.getUint8(offset++, 1);
|
ADVANCED_TUNING.vbatPidCompensation = data.getUint8(offset++, 1);
|
||||||
}
|
ADVANCED_TUNING.ptermSetpointWeight = data.getUint8(offset++, 1);
|
||||||
break;
|
ADVANCED_TUNING.dtermSetpointWeight = data.getUint8(offset++, 1);
|
||||||
|
ADVANCED_TUNING.toleranceBand = data.getUint8(offset++, 1);
|
||||||
case MSP_codes.MSP_SPECIAL_PARAMETERS:
|
ADVANCED_TUNING.toleranceBandReduction = data.getUint8(offset++, 1);
|
||||||
var offset = 0;
|
ADVANCED_TUNING.itermThrottleGain = data.getUint8(offset++, 1);
|
||||||
SPECIAL_PARAMETERS.RC_RATE_YAW = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
|
ADVANCED_TUNING.pidMaxVelocity = data.getUint16(offset, 1);
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
offset += 2;
|
||||||
SPECIAL_PARAMETERS.airModeActivateThreshold = data.getUint16(offset, 1);
|
ADVANCED_TUNING.pidMaxVelocityYaw = data.getUint16(offset, 1);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
SPECIAL_PARAMETERS.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:
|
||||||
|
@ -1235,6 +1240,12 @@ var MSP = {
|
||||||
case MSP_codes.MSP_SET_NAME:
|
case MSP_codes.MSP_SET_NAME:
|
||||||
console.log('Name set');
|
console.log('Name set');
|
||||||
break;
|
break;
|
||||||
|
case MSP_codes.MSP_SET_FILTER_CONFIG:
|
||||||
|
console.log('Filter config set');
|
||||||
|
break;
|
||||||
|
case MSP_codes.MSP_SET_PID_ADVANCED:
|
||||||
|
console.log('Advanced tuning parameters set');
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
console.log('Unknown code detected: ' + code);
|
console.log('Unknown code detected: ' + code);
|
||||||
} else {
|
} else {
|
||||||
|
@ -1434,6 +1445,9 @@ 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")) {
|
||||||
|
buffer.push(Math.round(RC_tuning.rcYawRate));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
// Disabled, cleanflight does not use MSP_SET_BOX.
|
// Disabled, cleanflight does not use MSP_SET_BOX.
|
||||||
|
@ -1507,6 +1521,13 @@ MSP.crunch = function (code) {
|
||||||
buffer.push(highByte(RX_CONFIG.rx_min_usec));
|
buffer.push(highByte(RX_CONFIG.rx_min_usec));
|
||||||
buffer.push(lowByte(RX_CONFIG.rx_max_usec));
|
buffer.push(lowByte(RX_CONFIG.rx_max_usec));
|
||||||
buffer.push(highByte(RX_CONFIG.rx_max_usec));
|
buffer.push(highByte(RX_CONFIG.rx_max_usec));
|
||||||
|
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
|
||||||
|
buffer.push(RX_CONFIG.rcSmoothing);
|
||||||
|
buffer.push(RX_CONFIG.rcSmoothInterval);
|
||||||
|
buffer.push(lowByte(RX_CONFIG.airModeActivateThreshold));
|
||||||
|
buffer.push(highByte(RX_CONFIG.airModeActivateThreshold));
|
||||||
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_SET_FAILSAFE_CONFIG:
|
case MSP_codes.MSP_SET_FAILSAFE_CONFIG:
|
||||||
|
@ -1604,7 +1625,7 @@ MSP.crunch = function (code) {
|
||||||
buffer.push(SENSOR_ALIGNMENT.align_acc);
|
buffer.push(SENSOR_ALIGNMENT.align_acc);
|
||||||
buffer.push(SENSOR_ALIGNMENT.align_mag);
|
buffer.push(SENSOR_ALIGNMENT.align_mag);
|
||||||
break
|
break
|
||||||
case MSP_codes.MSP_SET_PID_ADVANCED_CONFIG:
|
case MSP_codes.MSP_SET_ADVANCED_CONFIG:
|
||||||
buffer.push(PID_ADVANCED_CONFIG.gyro_sync_denom);
|
buffer.push(PID_ADVANCED_CONFIG.gyro_sync_denom);
|
||||||
buffer.push(PID_ADVANCED_CONFIG.pid_process_denom);
|
buffer.push(PID_ADVANCED_CONFIG.pid_process_denom);
|
||||||
buffer.push(PID_ADVANCED_CONFIG.use_unsyncedPwm);
|
buffer.push(PID_ADVANCED_CONFIG.use_unsyncedPwm);
|
||||||
|
@ -1617,21 +1638,20 @@ MSP.crunch = function (code) {
|
||||||
.push16(FILTER_CONFIG.dterm_lpf_hz)
|
.push16(FILTER_CONFIG.dterm_lpf_hz)
|
||||||
.push16(FILTER_CONFIG.yaw_lpf_hz);
|
.push16(FILTER_CONFIG.yaw_lpf_hz);
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_ADVANCED_TUNING:
|
case MSP_codes.MSP_SET_PID_ADVANCED:
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
buffer.push16(ADVANCED_TUNING.rollPitchItermIgnoreRate)
|
buffer.push16(ADVANCED_TUNING.rollPitchItermIgnoreRate)
|
||||||
.push16(ADVANCED_TUNING.yawItermIgnoreRate)
|
.push16(ADVANCED_TUNING.yawItermIgnoreRate)
|
||||||
.push16(ADVANCED_TUNING.yaw_p_limit)
|
.push16(ADVANCED_TUNING.yaw_p_limit)
|
||||||
.push8(ADVANCED_TUNING.deltaMethod)
|
.push8(ADVANCED_TUNING.deltaMethod)
|
||||||
.push8(ADVANCED_TUNING.vbatPidCompensation);
|
.push8(ADVANCED_TUNING.vbatPidCompensation)
|
||||||
}
|
.push8(ADVANCED_TUNING.ptermSetpointWeight)
|
||||||
break;
|
.push8(ADVANCED_TUNING.dtermSetpointWeight)
|
||||||
case MSP_codes.MSP_SET_SPECIAL_PARAMETERS:
|
.push8(ADVANCED_TUNING.toleranceBand)
|
||||||
buffer.push(Math.round(SPECIAL_PARAMETERS.RC_RATE_YAW * 100));
|
.push8(ADVANCED_TUNING.toleranceBandReduction)
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
.push8(ADVANCED_TUNING.itermThrottleGain)
|
||||||
buffer.push16(SPECIAL_PARAMETERS.airModeActivateThreshold);
|
.push16(ADVANCED_TUNING.pidMaxVelocity)
|
||||||
buffer.push(SPECIAL_PARAMETERS.rcSmoothInterval);
|
.push16(ADVANCED_TUNING.pidMaxVelocityYaw);
|
||||||
buffer.push16(SPECIAL_PARAMETERS.escDesyncProtection);
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_SENSOR_CONFIG:
|
case MSP_codes.MSP_SET_SENSOR_CONFIG:
|
||||||
|
|
|
@ -64,7 +64,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
function esc_protocol() {
|
function esc_protocol() {
|
||||||
var next_callback = sensor_config;
|
var next_callback = sensor_config;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
MSP.send_message(MSP_codes.MSP_PID_ADVANCED_CONFIG, false, false, next_callback);
|
MSP.send_message(MSP_codes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
|
@ -541,7 +541,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
function save_esc_protocol() {
|
function save_esc_protocol() {
|
||||||
var next_callback = save_acc_trim;
|
var next_callback = save_acc_trim;
|
||||||
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
MSP.send_message(MSP_codes.MSP_SET_PID_ADVANCED_CONFIG, MSP.crunch(MSP_codes.MSP_SET_PID_ADVANCED_CONFIG), false, next_callback);
|
MSP.send_message(MSP_codes.MSP_SET_ADVANCED_CONFIG, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
|
|
|
@ -25,9 +25,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
return MSP.promise(MSP_codes.MSP_RC_TUNING);
|
return MSP.promise(MSP_codes.MSP_RC_TUNING);
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
return MSP.promise(MSP_codes.MSP_SPECIAL_PARAMETERS);
|
return MSP.promise(MSP_codes.MSP_PID_ADVANCED);
|
||||||
}).then(function() {
|
|
||||||
return MSP.promise(MSP_codes.MSP_ADVANCED_TUNING);
|
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
return MSP.promise(MSP_codes.MSP_FILTER_CONFIG);
|
return MSP.promise(MSP_codes.MSP_FILTER_CONFIG);
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
|
@ -193,7 +191,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
$('.pid_tuning input[name="yaw_rate"]').val(RC_tuning.yaw_rate.toFixed(2));
|
$('.pid_tuning input[name="yaw_rate"]').val(RC_tuning.yaw_rate.toFixed(2));
|
||||||
$('.pid_tuning input[name="rc_expo"]').val(RC_tuning.RC_EXPO.toFixed(2));
|
$('.pid_tuning input[name="rc_expo"]').val(RC_tuning.RC_EXPO.toFixed(2));
|
||||||
$('.pid_tuning input[name="rc_yaw_expo"]').val(RC_tuning.RC_YAW_EXPO.toFixed(2));
|
$('.pid_tuning input[name="rc_yaw_expo"]').val(RC_tuning.RC_YAW_EXPO.toFixed(2));
|
||||||
$('.pid_tuning input[name="rc_rate_yaw"]').val(SPECIAL_PARAMETERS.RC_RATE_YAW.toFixed(2));
|
$('.pid_tuning input[name="rc_rate_yaw"]').val(RC_tuning.rcYawRate.toFixed(2));
|
||||||
|
|
||||||
$('.throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2));
|
$('.throttle input[name="mid"]').val(RC_tuning.throttle_MID.toFixed(2));
|
||||||
$('.throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2));
|
$('.throttle input[name="expo"]').val(RC_tuning.throttle_EXPO.toFixed(2));
|
||||||
|
@ -292,7 +290,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
RC_tuning.yaw_rate = parseFloat($('.pid_tuning input[name="yaw_rate"]').val());
|
RC_tuning.yaw_rate = parseFloat($('.pid_tuning input[name="yaw_rate"]').val());
|
||||||
RC_tuning.RC_EXPO = parseFloat($('.pid_tuning input[name="rc_expo"]').val());
|
RC_tuning.RC_EXPO = parseFloat($('.pid_tuning input[name="rc_expo"]').val());
|
||||||
RC_tuning.RC_YAW_EXPO = parseFloat($('.pid_tuning input[name="rc_yaw_expo"]').val());
|
RC_tuning.RC_YAW_EXPO = parseFloat($('.pid_tuning input[name="rc_yaw_expo"]').val());
|
||||||
SPECIAL_PARAMETERS.RC_RATE_YAW = parseFloat($('.pid_tuning input[name="rc_rate_yaw"]').val());
|
RC_tuning.rcYawRate = parseFloat($('.pid_tuning input[name="rc_rate_yaw"]').val());
|
||||||
|
|
||||||
RC_tuning.throttle_MID = parseFloat($('.throttle input[name="mid"]').val());
|
RC_tuning.throttle_MID = parseFloat($('.throttle input[name="mid"]').val());
|
||||||
RC_tuning.throttle_EXPO = parseFloat($('.throttle input[name="expo"]').val())
|
RC_tuning.throttle_EXPO = parseFloat($('.throttle input[name="expo"]').val())
|
||||||
|
@ -420,7 +418,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
pitch_rate: RC_tuning.pitch_rate,
|
pitch_rate: RC_tuning.pitch_rate,
|
||||||
yaw_rate: RC_tuning.yaw_rate,
|
yaw_rate: RC_tuning.yaw_rate,
|
||||||
rc_rate: RC_tuning.RC_RATE,
|
rc_rate: RC_tuning.RC_RATE,
|
||||||
rc_rate_yaw: SPECIAL_PARAMETERS.RC_RATE_YAW,
|
rc_rate_yaw: RC_tuning.rcYawRate,
|
||||||
rc_expo: RC_tuning.RC_EXPO,
|
rc_expo: RC_tuning.RC_EXPO,
|
||||||
rc_yaw_expo: RC_tuning.RC_YAW_EXPO,
|
rc_yaw_expo: RC_tuning.RC_YAW_EXPO,
|
||||||
superexpo: BF_CONFIG.features.isEnabled('SUPEREXPO_RATES')
|
superexpo: BF_CONFIG.features.isEnabled('SUPEREXPO_RATES')
|
||||||
|
@ -700,14 +698,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
return MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID));
|
return MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID));
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
var promise;
|
return MSP.promise(MSP_codes.MSP_SET_PID_ADVANCED, MSP.crunch(MSP_codes.MSP_SET_PID_ADVANCED));
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
|
||||||
promise = MSP.promise(MSP_codes.MSP_SET_SPECIAL_PARAMETERS, MSP.crunch(MSP_codes.MSP_SET_SPECIAL_PARAMETERS));
|
|
||||||
}
|
|
||||||
|
|
||||||
return promise;
|
|
||||||
}).then(function () {
|
|
||||||
return MSP.promise(MSP_codes.MSP_SET_ADVANCED_TUNING, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_TUNING));
|
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
var promise;
|
var promise;
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "2.8.1")) {
|
||||||
|
|
|
@ -20,11 +20,7 @@ TABS.receiver.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_bt_config_data() {
|
function get_bt_config_data() {
|
||||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, get_special_parameters_data);
|
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, get_rc_map);
|
||||||
}
|
|
||||||
|
|
||||||
function get_special_parameters_data() {
|
|
||||||
MSP.send_message(MSP_codes.MSP_SPECIAL_PARAMETERS, false, false, get_rc_map);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_map() {
|
function get_rc_map() {
|
||||||
|
@ -423,7 +419,7 @@ TABS.receiver.renderModel = function () {
|
||||||
|
|
||||||
var roll = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[0], RC_tuning.roll_rate, RC_tuning.RC_RATE, RC_tuning.RC_EXPO, this.useSuperExpo),
|
var roll = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[0], RC_tuning.roll_rate, RC_tuning.RC_RATE, RC_tuning.RC_EXPO, this.useSuperExpo),
|
||||||
pitch = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[1], RC_tuning.pitch_rate, RC_tuning.RC_RATE, RC_tuning.RC_EXPO, this.useSuperExpo),
|
pitch = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[1], RC_tuning.pitch_rate, RC_tuning.RC_RATE, RC_tuning.RC_EXPO, this.useSuperExpo),
|
||||||
yaw = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[2], RC_tuning.yaw_rate, SPECIAL_PARAMETERS.RC_RATE_YAW, RC_tuning.RC_YAW_EXPO, this.useSuperExpo);
|
yaw = delta * this.rateCurve.rcCommandRawToDegreesPerSecond(RC.channels[2], RC_tuning.yaw_rate, RC_tuning.rcYawRate, RC_tuning.RC_YAW_EXPO, this.useSuperExpo);
|
||||||
|
|
||||||
this.model.rotateBy(-degToRad(pitch), -degToRad(yaw), -degToRad(roll));
|
this.model.rotateBy(-degToRad(pitch), -degToRad(yaw), -degToRad(roll));
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue