mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-23 16:25:22 +03:00
Fix TPA (#3078)
This commit is contained in:
parent
6b92a90b23
commit
40d204c546
4 changed files with 24 additions and 1 deletions
|
@ -1290,6 +1290,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
|||
FC.ADVANCED_TUNING.thrustLinearization = data.readU8();
|
||||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45)) {
|
||||
FC.ADVANCED_TUNING.tpaMode = data.readU8();
|
||||
FC.ADVANCED_TUNING.tpaRate = parseFloat((data.readU8() / 100).toFixed(2));
|
||||
FC.ADVANCED_TUNING.tpaBreakpoint = data.readU16();
|
||||
}
|
||||
|
@ -2316,6 +2317,7 @@ MspHelper.prototype.crunch = function(code, modifierCode = undefined) {
|
|||
.push8(FC.ADVANCED_TUNING.thrustLinearization);
|
||||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45)) {
|
||||
buffer.push8(FC.ADVANCED_TUNING.tpaMode);
|
||||
buffer.push8(Math.round(FC.ADVANCED_TUNING.tpaRate * 100));
|
||||
buffer.push16(FC.ADVANCED_TUNING.tpaBreakpoint);
|
||||
}
|
||||
|
|
|
@ -111,6 +111,7 @@ pid_tuning.initialize = function (callback) {
|
|||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45)) {
|
||||
// Moved tpa to profile
|
||||
$('select[id="tpaMode"]').val(FC.ADVANCED_TUNING.tpaMode);
|
||||
$('input[id="tpaRate"]').val(FC.ADVANCED_TUNING.tpaRate.toFixed(2));
|
||||
$('input[id="tpaBreakpoint"]').val(FC.ADVANCED_TUNING.tpaBreakpoint);
|
||||
} else {
|
||||
|
@ -1186,6 +1187,7 @@ pid_tuning.initialize = function (callback) {
|
|||
FC.RC_TUNING.throttle_EXPO = parseFloat($('.throttle input[name="expo"]').val());
|
||||
|
||||
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_45)) {
|
||||
FC.ADVANCED_TUNING.tpaMode = $('select[id="tpaMode"]').val();
|
||||
FC.ADVANCED_TUNING.tpaRate = parseFloat($('input[id="tpaRate"]').val());
|
||||
FC.ADVANCED_TUNING.tpaBreakpoint = parseInt($('input[id="tpaBreakpoint"]').val());
|
||||
} else {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue