mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-18 13:55:14 +03:00
Refactor and Implement version checking part 1
This commit is contained in:
parent
2738549032
commit
c7d89ed710
3 changed files with 29 additions and 17 deletions
9
js/fc.js
9
js/fc.js
|
@ -38,7 +38,7 @@ var RXFAIL_CONFIG;
|
||||||
var PID_ADVANCED_CONFIG;
|
var PID_ADVANCED_CONFIG;
|
||||||
var FILTER_CONFIG;
|
var FILTER_CONFIG;
|
||||||
var ADVANCED_TUNING;
|
var ADVANCED_TUNING;
|
||||||
var TEMPORARY_COMMANDS;
|
var SPECIAL_PARAMETERS;
|
||||||
|
|
||||||
var FC = {
|
var FC = {
|
||||||
resetState: function() {
|
resetState: function() {
|
||||||
|
@ -261,8 +261,11 @@ var FC = {
|
||||||
vbatPidCompensation: 0
|
vbatPidCompensation: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
TEMPORARY_COMMANDS = {
|
SPECIAL_PARAMETERS = {
|
||||||
RC_RATE_YAW: 0
|
RC_RATE_YAW: 0,
|
||||||
|
airModeActivateThreshold: 0,
|
||||||
|
rcSmoothInterval: 0,
|
||||||
|
escDesyncProtection: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
RX_CONFIG = {
|
RX_CONFIG = {
|
||||||
|
|
21
js/msp.js
21
js/msp.js
|
@ -47,8 +47,8 @@ var MSP_codes = {
|
||||||
MSP_SET_FILTER_CONFIG: 93,
|
MSP_SET_FILTER_CONFIG: 93,
|
||||||
MSP_ADVANCED_TUNING: 94,
|
MSP_ADVANCED_TUNING: 94,
|
||||||
MSP_SET_ADVANCED_TUNING: 95,
|
MSP_SET_ADVANCED_TUNING: 95,
|
||||||
MSP_TEMPORARY_COMMANDS: 98,
|
MSP_SPECIAL_PARAMETERS: 98,
|
||||||
MSP_SET_TEMPORARY_COMMANDS: 99,
|
MSP_SET_SPECIAL_PARAMETERS: 99,
|
||||||
|
|
||||||
// Multiwii MSP commands
|
// Multiwii MSP commands
|
||||||
MSP_IDENT: 100,
|
MSP_IDENT: 100,
|
||||||
|
@ -900,13 +900,22 @@ var MSP = {
|
||||||
ADVANCED_TUNING.yawItermIgnoreRate = data.getUint16(offset, 1);
|
ADVANCED_TUNING.yawItermIgnoreRate = data.getUint16(offset, 1);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
ADVANCED_TUNING.yaw_p_limit = data.getUint16(offset, 1);
|
ADVANCED_TUNING.yaw_p_limit = data.getUint16(offset, 1);
|
||||||
|
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
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);
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_codes.MSP_TEMPORARY_COMMANDS:
|
case MSP_codes.MSP_SPECIAL_PARAMETERS:
|
||||||
TEMPORARY_COMMANDS.RC_RATE_YAW = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
|
var offset = 0;
|
||||||
|
SPECIAL_PARAMETERS.RC_RATE_YAW = parseFloat((data.getUint8(offset++) / 100).toFixed(2));
|
||||||
|
if (CONFIG.flightControllerIdentifier == "BTFL" && semver.gte(CONFIG.flightControllerVersion, "2.8.2")) {
|
||||||
|
SPECIAL_PARAMETERS.airModeActivateThreshold = data.getUint16(offset, 1);
|
||||||
|
offset += 2;
|
||||||
|
SPECIAL_PARAMETERS.rcSmoothInterval = data.getUint8(offset++, 1)
|
||||||
|
SPECIAL_PARAMETERS.escDesyncProtection = data.getUint16(offset, 1);
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_LED_STRIP_CONFIG:
|
case MSP_codes.MSP_LED_STRIP_CONFIG:
|
||||||
LED_STRIP = [];
|
LED_STRIP = [];
|
||||||
|
@ -1434,8 +1443,8 @@ MSP.crunch = function (code) {
|
||||||
.push8(ADVANCED_TUNING.deltaMethod)
|
.push8(ADVANCED_TUNING.deltaMethod)
|
||||||
.push8(ADVANCED_TUNING.vbatPidCompensation);
|
.push8(ADVANCED_TUNING.vbatPidCompensation);
|
||||||
break;
|
break;
|
||||||
case MSP_codes.MSP_SET_TEMPORARY_COMMANDS:
|
case MSP_codes.MSP_SET_SPECIAL_PARAMETERS:
|
||||||
buffer.push(Math.round(TEMPORARY_COMMANDS.RC_RATE_YAW * 100));
|
buffer.push(Math.round(SPECIAL_PARAMETERS.RC_RATE_YAW * 100));
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -23,7 +23,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_TEMPORARY_COMMANDS);
|
return MSP.promise(MSP_codes.MSP_SPECIAL_PARAMETERS);
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
return MSP.promise(MSP_codes.MSP_ADVANCED_TUNING);
|
return MSP.promise(MSP_codes.MSP_ADVANCED_TUNING);
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
|
@ -172,7 +172,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(TEMPORARY_COMMANDS.RC_RATE_YAW.toFixed(2));
|
$('.pid_tuning input[name="rc_rate_yaw"]').val(SPECIAL_PARAMETERS.RC_RATE_YAW.toFixed(2));
|
||||||
|
|
||||||
$('.tpa input[name="tpa"]').val(RC_tuning.dynamic_THR_PID.toFixed(2));
|
$('.tpa input[name="tpa"]').val(RC_tuning.dynamic_THR_PID.toFixed(2));
|
||||||
$('.tpa input[name="tpa-breakpoint"]').val(RC_tuning.dynamic_THR_breakpoint);
|
$('.tpa input[name="tpa-breakpoint"]').val(RC_tuning.dynamic_THR_breakpoint);
|
||||||
|
@ -248,7 +248,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());
|
||||||
TEMPORARY_COMMANDS.RC_RATE_YAW = parseFloat($('.pid_tuning input[name="rc_rate_yaw"]').val());
|
SPECIAL_PARAMETERS.RC_RATE_YAW = parseFloat($('.pid_tuning input[name="rc_rate_yaw"]').val());
|
||||||
|
|
||||||
RC_tuning.dynamic_THR_PID = parseFloat($('.tpa input[name="tpa"]').val());
|
RC_tuning.dynamic_THR_PID = parseFloat($('.tpa input[name="tpa"]').val());
|
||||||
RC_tuning.dynamic_THR_breakpoint = parseInt($('.tpa input[name="tpa-breakpoint"]').val());
|
RC_tuning.dynamic_THR_breakpoint = parseInt($('.tpa input[name="tpa-breakpoint"]').val());
|
||||||
|
@ -442,7 +442,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
if (TABS.pid_tuning.controllerChanged) { return; }
|
if (TABS.pid_tuning.controllerChanged) { return; }
|
||||||
MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID)).then(function() {
|
MSP.promise(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID)).then(function() {
|
||||||
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
||||||
return MSP.promise(MSP_codes.MSP_SET_TEMPORARY_COMMANDS, MSP.crunch(MSP_codes.MSP_SET_TEMPORARY_COMMANDS));
|
return MSP.promise(MSP_codes.MSP_SET_SPECIAL_PARAMETERS, MSP.crunch(MSP_codes.MSP_SET_SPECIAL_PARAMETERS));
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
if (TABS.pid_tuning.controllerChanged) { Promise.reject('pid controller changed'); }
|
||||||
return MSP.promise(MSP_codes.MSP_SET_ADVANCED_TUNING, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_TUNING));
|
return MSP.promise(MSP_codes.MSP_SET_ADVANCED_TUNING, MSP.crunch(MSP_codes.MSP_SET_ADVANCED_TUNING));
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue