mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 12:55:14 +03:00
Move FC global vars inside FC object
This commit is contained in:
parent
b9137a68e6
commit
24010a2e2a
32 changed files with 2799 additions and 2797 deletions
|
@ -13,7 +13,7 @@ function configuration_backup(callback) {
|
|||
|
||||
var configuration = {
|
||||
'generatedBy': version,
|
||||
'apiVersion': CONFIG.apiVersion,
|
||||
'apiVersion': FC.CONFIG.apiVersion,
|
||||
'profiles': [],
|
||||
};
|
||||
|
||||
|
@ -28,10 +28,10 @@ function configuration_backup(callback) {
|
|||
];
|
||||
|
||||
function update_profile_specific_data_list() {
|
||||
if (semver.gt(CONFIG.apiVersion, "1.12.0")) {
|
||||
if (semver.gt(FC.CONFIG.apiVersion, "1.12.0")) {
|
||||
profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
profileSpecificData.push(MSPCodes.MSP_RC_DEADBAND);
|
||||
}
|
||||
}
|
||||
|
@ -39,7 +39,7 @@ function configuration_backup(callback) {
|
|||
update_profile_specific_data_list();
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
|
||||
activeProfile = CONFIG.profile;
|
||||
activeProfile = FC.CONFIG.profile;
|
||||
select_profile();
|
||||
});
|
||||
|
||||
|
@ -56,7 +56,7 @@ function configuration_backup(callback) {
|
|||
codeKey = 0;
|
||||
|
||||
function fetch_specific_data_item() {
|
||||
if (fetchingProfile < CONFIG.numProfiles) {
|
||||
if (fetchingProfile < FC.CONFIG.numProfiles) {
|
||||
MSP.send_message(profileSpecificData[codeKey], false, false, function () {
|
||||
codeKey++;
|
||||
|
||||
|
@ -64,18 +64,18 @@ function configuration_backup(callback) {
|
|||
fetch_specific_data_item();
|
||||
} else {
|
||||
configuration.profiles.push({
|
||||
'PID': jQuery.extend(true, {}, PID),
|
||||
'PIDs': jQuery.extend(true, [], PIDs),
|
||||
'RC': jQuery.extend(true, {}, RC_tuning),
|
||||
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
|
||||
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
|
||||
'ServoRules': jQuery.extend(true, [], SERVO_RULES),
|
||||
'ModeRanges': jQuery.extend(true, [], MODE_RANGES),
|
||||
'AdjustmentRanges': jQuery.extend(true, [], ADJUSTMENT_RANGES)
|
||||
'PID': jQuery.extend(true, {}, FC.PID),
|
||||
'PIDs': jQuery.extend(true, [], FC.PIDS),
|
||||
'RC': jQuery.extend(true, {}, FC.RC_TUNING),
|
||||
'AccTrim': jQuery.extend(true, [], FC.CONFIG.accelerometerTrims),
|
||||
'ServoConfig': jQuery.extend(true, [], FC.SERVO_CONFIG),
|
||||
'ServoRules': jQuery.extend(true, [], FC.SERVO_RULES),
|
||||
'ModeRanges': jQuery.extend(true, [], FC.MODE_RANGES),
|
||||
'AdjustmentRanges': jQuery.extend(true, [], FC.ADJUSTMENT_RANGES)
|
||||
});
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.profiles[fetchingProfile].RCdeadband = jQuery.extend(true, {}, RC_DEADBAND_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.profiles[fetchingProfile].RCdeadband = jQuery.extend(true, {}, FC.RC_DEADBAND_CONFIG);
|
||||
}
|
||||
codeKey = 0;
|
||||
fetchingProfile++;
|
||||
|
@ -100,29 +100,29 @@ function configuration_backup(callback) {
|
|||
];
|
||||
|
||||
function update_unique_data_list() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.8.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_LOOP_TIME);
|
||||
uniqueData.push(MSPCodes.MSP_ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MOTOR_3D_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSPCodes.MSP_RX_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_FAILSAFE_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_RXFAIL_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_LED_STRIP_MODECOLOR);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MOTOR_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_RSSI_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_GPS_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_FEATURE_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_MODE_RANGES_EXTRA);
|
||||
}
|
||||
}
|
||||
|
@ -139,44 +139,44 @@ function configuration_backup(callback) {
|
|||
fetch_unique_data_item();
|
||||
});
|
||||
} else {
|
||||
configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
|
||||
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG);
|
||||
configuration.LED_STRIP = jQuery.extend(true, [], LED_STRIP);
|
||||
configuration.LED_COLORS = jQuery.extend(true, [], LED_COLORS);
|
||||
configuration.BOARD_ALIGNMENT_CONFIG = jQuery.extend(true, {}, BOARD_ALIGNMENT_CONFIG);
|
||||
configuration.CRAFT_NAME = CONFIG.name;
|
||||
configuration.DISPLAY_NAME = CONFIG.displayName;
|
||||
configuration.MIXER_CONFIG = jQuery.extend(true, {}, MIXER_CONFIG);
|
||||
configuration.SENSOR_CONFIG = jQuery.extend(true, {}, SENSOR_CONFIG);
|
||||
configuration.PID_ADVANCED_CONFIG = jQuery.extend(true, {}, PID_ADVANCED_CONFIG);
|
||||
configuration.RCMAP = jQuery.extend(true, [], FC.RC_MAP);
|
||||
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, FC.SERIAL_CONFIG);
|
||||
configuration.LED_STRIP = jQuery.extend(true, [], FC.LED_STRIP);
|
||||
configuration.LED_COLORS = jQuery.extend(true, [], FC.LED_COLORS);
|
||||
configuration.BOARD_ALIGNMENT_CONFIG = jQuery.extend(true, {}, FC.BOARD_ALIGNMENT_CONFIG);
|
||||
configuration.CRAFT_NAME = FC.CONFIG.name;
|
||||
configuration.DISPLAY_NAME = FC.CONFIG.displayName;
|
||||
configuration.MIXER_CONFIG = jQuery.extend(true, {}, FC.MIXER_CONFIG);
|
||||
configuration.SENSOR_CONFIG = jQuery.extend(true, {}, FC.SENSOR_CONFIG);
|
||||
configuration.PID_ADVANCED_CONFIG = jQuery.extend(true, {}, FC.PID_ADVANCED_CONFIG);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0")) {
|
||||
configuration.LED_MODE_COLORS = jQuery.extend(true, [], LED_MODE_COLORS);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0")) {
|
||||
configuration.LED_MODE_COLORS = jQuery.extend(true, [], FC.LED_MODE_COLORS);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
configuration.FC_CONFIG = jQuery.extend(true, {}, FC_CONFIG);
|
||||
configuration.ARMING_CONFIG = jQuery.extend(true, {}, ARMING_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.8.0")) {
|
||||
configuration.FC_CONFIG = jQuery.extend(true, {}, FC.FC_CONFIG);
|
||||
configuration.ARMING_CONFIG = jQuery.extend(true, {}, FC.ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
configuration.MOTOR_3D_CONFIG = jQuery.extend(true, {}, MOTOR_3D_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
configuration.MOTOR_3D_CONFIG = jQuery.extend(true, {}, FC.MOTOR_3D_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.SENSOR_ALIGNMENT = jQuery.extend(true, {}, SENSOR_ALIGNMENT);
|
||||
configuration.RX_CONFIG = jQuery.extend(true, {}, RX_CONFIG);
|
||||
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FAILSAFE_CONFIG);
|
||||
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], RXFAIL_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
configuration.SENSOR_ALIGNMENT = jQuery.extend(true, {}, FC.SENSOR_ALIGNMENT);
|
||||
configuration.RX_CONFIG = jQuery.extend(true, {}, FC.RX_CONFIG);
|
||||
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FC.FAILSAFE_CONFIG);
|
||||
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], FC.RXFAIL_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
configuration.RSSI_CONFIG = jQuery.extend(true, {}, RSSI_CONFIG);
|
||||
configuration.FEATURE_CONFIG = jQuery.extend(true, {}, FEATURE_CONFIG);
|
||||
configuration.MOTOR_CONFIG = jQuery.extend(true, {}, MOTOR_CONFIG);
|
||||
configuration.GPS_CONFIG = jQuery.extend(true, {}, GPS_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
configuration.RSSI_CONFIG = jQuery.extend(true, {}, FC.RSSI_CONFIG);
|
||||
configuration.FEATURE_CONFIG = jQuery.extend(true, {}, FC.FEATURE_CONFIG);
|
||||
configuration.MOTOR_CONFIG = jQuery.extend(true, {}, FC.MOTOR_CONFIG);
|
||||
configuration.GPS_CONFIG = jQuery.extend(true, {}, FC.GPS_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.36.0")) {
|
||||
configuration.BEEPER_CONFIG = jQuery.extend(true, {}, BEEPER_CONFIG);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.36.0")) {
|
||||
configuration.BEEPER_CONFIG = jQuery.extend(true, {}, FC.BEEPER_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
configuration.MODE_RANGES_EXTRA = jQuery.extend(true, [], MODE_RANGES_EXTRA);
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
configuration.MODE_RANGES_EXTRA = jQuery.extend(true, [], FC.MODE_RANGES_EXTRA);
|
||||
}
|
||||
|
||||
save();
|
||||
|
@ -339,7 +339,7 @@ function configuration_restore(callback) {
|
|||
return;
|
||||
}
|
||||
if (configuration.FEATURE_CONFIG.features._featureMask) {
|
||||
var features = new Features(CONFIG);
|
||||
var features = new Features(FC.CONFIG);
|
||||
features.setMask(configuration.FEATURE_CONFIG.features._featureMask);
|
||||
configuration.FEATURE_CONFIG.features = features;
|
||||
}
|
||||
|
@ -421,8 +421,8 @@ function configuration_restore(callback) {
|
|||
configuration.LED_STRIP = fixed_led_strip;
|
||||
}
|
||||
|
||||
for (var profileIndex = 0; profileIndex < 3; profileIndex++) {
|
||||
var RC = configuration.profiles[profileIndex].RC;
|
||||
for (let profileIndex = 0; profileIndex < 3; profileIndex++) {
|
||||
const RC = configuration.profiles[profileIndex].RC;
|
||||
// TPA breakpoint was added
|
||||
if (!RC.dynamic_THR_breakpoint) {
|
||||
RC.dynamic_THR_breakpoint = 1500; // firmware default
|
||||
|
@ -555,7 +555,7 @@ function configuration_restore(callback) {
|
|||
appliedMigrationsCount++;
|
||||
}
|
||||
|
||||
if (semver.lt(configuration.apiVersion, '1.14.0') && semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
if (semver.lt(configuration.apiVersion, '1.14.0') && semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
// api 1.14 removed old pid controllers
|
||||
for (var profileIndex = 0; profileIndex < configuration.profiles.length; profileIndex++) {
|
||||
var newPidControllerIndex = configuration.profiles[profileIndex].PID.controller;
|
||||
|
@ -659,8 +659,8 @@ function configuration_restore(callback) {
|
|||
|
||||
if (compareVersions(migratedVersion, '1.2.0')) {
|
||||
// old version of the configurator incorrectly had a 'disabled' option for GPS SBAS mode.
|
||||
if (GPS_CONFIG.ublox_sbas < 0) {
|
||||
GPS_CONFIG.ublox_sbas = 0;
|
||||
if (FC.GPS_CONFIG.ublox_sbas < 0) {
|
||||
FC.GPS_CONFIG.ublox_sbas = 0;
|
||||
}
|
||||
migratedVersion = '1.2.0';
|
||||
|
||||
|
@ -693,7 +693,7 @@ function configuration_restore(callback) {
|
|||
function configuration_upload(configuration, callback) {
|
||||
function upload() {
|
||||
var activeProfile = null;
|
||||
var numProfiles = CONFIG.numProfiles;
|
||||
var numProfiles = FC.CONFIG.numProfiles;
|
||||
if (configuration.profiles.length < numProfiles) {
|
||||
numProfiles = configuration.profiles.length;
|
||||
}
|
||||
|
@ -705,12 +705,12 @@ function configuration_restore(callback) {
|
|||
MSPCodes.MSP_SET_ACC_TRIM
|
||||
];
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
profileSpecificData.push(MSPCodes.MSP_SET_RC_DEADBAND);
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
|
||||
activeProfile = CONFIG.profile;
|
||||
activeProfile = FC.CONFIG.profile;
|
||||
select_profile();
|
||||
});
|
||||
|
||||
|
@ -727,15 +727,15 @@ function configuration_restore(callback) {
|
|||
codeKey = 0;
|
||||
|
||||
function load_objects(profile) {
|
||||
PID = configuration.profiles[profile].PID;
|
||||
PIDs = configuration.profiles[profile].PIDs;
|
||||
RC_tuning = configuration.profiles[profile].RC;
|
||||
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||
SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||
MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||
RC_DEADBAND_CONFIG = configuration.profiles[profile].RCdeadband;
|
||||
FC.PID = configuration.profiles[profile].PID;
|
||||
FC.PIDS = configuration.profiles[profile].PIDs;
|
||||
FC.RC_TUNING = configuration.profiles[profile].RC;
|
||||
FC.CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||
FC.SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||
FC.SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||
FC.MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||
FC.ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||
FC.RC_DEADBAND_CONFIG = configuration.profiles[profile].RCdeadband;
|
||||
}
|
||||
|
||||
function upload_using_specific_commands() {
|
||||
|
@ -768,20 +768,20 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function upload_mode_ranges() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.41.0")) {
|
||||
if (configuration.MODE_RANGES_EXTRA == undefined) {
|
||||
MODE_RANGES_EXTRA = [];
|
||||
FC.MODE_RANGES_EXTRA = [];
|
||||
|
||||
for (var modeIndex = 0; modeIndex < MODE_RANGES.length; modeIndex++) {
|
||||
for (var modeIndex = 0; modeIndex < FC.MODE_RANGES.length; modeIndex++) {
|
||||
var defaultModeRangeExtra = {
|
||||
modeId: MODE_RANGES[modeIndex].modeId,
|
||||
modeId: FC.MODE_RANGES[modeIndex].modeId,
|
||||
modeLogic: 0,
|
||||
linkedTo: 0
|
||||
};
|
||||
MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
FC.MODE_RANGES_EXTRA.push(defaultModeRangeExtra);
|
||||
}
|
||||
} else {
|
||||
MODE_RANGES_EXTRA = configuration.MODE_RANGES_EXTRA;
|
||||
FC.MODE_RANGES_EXTRA = configuration.MODE_RANGES_EXTRA;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -812,19 +812,19 @@ function configuration_restore(callback) {
|
|||
uniqueData.push(MSPCodes.MSP_SET_BOARD_ALIGNMENT_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_ADVANCED_CONFIG);
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.8.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_LOOP_TIME);
|
||||
uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.14.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_MOTOR_3D_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT);
|
||||
uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG);
|
||||
}
|
||||
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.33.0")) {
|
||||
uniqueData.push(MSPCodes.MSP_SET_FEATURE_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_MOTOR_CONFIG);
|
||||
uniqueData.push(MSPCodes.MSP_SET_GPS_CONFIG);
|
||||
|
@ -833,35 +833,35 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function load_objects() {
|
||||
MISC = configuration.MISC;
|
||||
RC_MAP = configuration.RCMAP;
|
||||
SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
||||
LED_STRIP = configuration.LED_STRIP;
|
||||
LED_COLORS = configuration.LED_COLORS;
|
||||
LED_MODE_COLORS = configuration.LED_MODE_COLORS;
|
||||
ARMING_CONFIG = configuration.ARMING_CONFIG;
|
||||
FC_CONFIG = configuration.FC_CONFIG;
|
||||
MOTOR_3D_CONFIG = configuration.MOTOR_3D_CONFIG;
|
||||
SENSOR_ALIGNMENT = configuration.SENSOR_ALIGNMENT;
|
||||
RX_CONFIG = configuration.RX_CONFIG;
|
||||
FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
|
||||
RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
|
||||
FEATURE_CONFIG = configuration.FEATURE_CONFIG;
|
||||
MOTOR_CONFIG = configuration.MOTOR_CONFIG;
|
||||
GPS_CONFIG = configuration.GPS_CONFIG;
|
||||
RSSI_CONFIG = configuration.RSSI_CONFIG;
|
||||
BOARD_ALIGNMENT_CONFIG = configuration.BOARD_ALIGNMENT_CONFIG;
|
||||
CONFIG.name = configuration.CRAFT_NAME;
|
||||
CONFIG.displayName = configuration.DISPLAY_NAME;
|
||||
MIXER_CONFIG = configuration.MIXER_CONFIG;
|
||||
SENSOR_CONFIG = configuration.SENSOR_CONFIG;
|
||||
PID_ADVANCED_CONFIG = configuration.PID_ADVANCED_CONFIG;
|
||||
FC.MISC = configuration.MISC;
|
||||
FC.RC_MAP = configuration.RCMAP;
|
||||
FC.SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
||||
FC.LED_STRIP = configuration.LED_STRIP;
|
||||
FC.LED_COLORS = configuration.LED_COLORS;
|
||||
FC.LED_MODE_COLORS = configuration.LED_MODE_COLORS;
|
||||
FC.ARMING_CONFIG = configuration.ARMING_CONFIG;
|
||||
FC.FC_CONFIG = configuration.FC_CONFIG;
|
||||
FC.MOTOR_3D_CONFIG = configuration.MOTOR_3D_CONFIG;
|
||||
FC.SENSOR_ALIGNMENT = configuration.SENSOR_ALIGNMENT;
|
||||
FC.RX_CONFIG = configuration.RX_CONFIG;
|
||||
FC.FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
|
||||
FC.RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
|
||||
FC.FEATURE_CONFIG = configuration.FEATURE_CONFIG;
|
||||
FC.MOTOR_CONFIG = configuration.MOTOR_CONFIG;
|
||||
FC.GPS_CONFIG = configuration.GPS_CONFIG;
|
||||
FC.RSSI_CONFIG = configuration.RSSI_CONFIG;
|
||||
FC.BOARD_ALIGNMENT_CONFIG = configuration.BOARD_ALIGNMENT_CONFIG;
|
||||
FC.CONFIG.name = configuration.CRAFT_NAME;
|
||||
FC.CONFIG.displayName = configuration.DISPLAY_NAME;
|
||||
FC.MIXER_CONFIG = configuration.MIXER_CONFIG;
|
||||
FC.SENSOR_CONFIG = configuration.SENSOR_CONFIG;
|
||||
FC.PID_ADVANCED_CONFIG = configuration.PID_ADVANCED_CONFIG;
|
||||
|
||||
BEEPER_CONFIG.beepers = new Beepers(CONFIG);
|
||||
BEEPER_CONFIG.beepers.setMask(configuration.BEEPER_CONFIG.beepers._beeperMask);
|
||||
BEEPER_CONFIG.dshotBeaconTone = configuration.BEEPER_CONFIG.dshotBeaconTone;
|
||||
BEEPER_CONFIG.dshotBeaconConditions = new Beepers(CONFIG, [ "RX_LOST", "RX_SET" ]);
|
||||
BEEPER_CONFIG.dshotBeaconConditions.setMask(configuration.BEEPER_CONFIG.dshotBeaconConditions._beeperMask);
|
||||
FC.BEEPER_CONFIG.beepers = new Beepers(FC.CONFIG);
|
||||
FC.BEEPER_CONFIG.beepers.setMask(configuration.BEEPER_CONFIG.beepers._beeperMask);
|
||||
FC.BEEPER_CONFIG.dshotBeaconTone = configuration.BEEPER_CONFIG.dshotBeaconTone;
|
||||
FC.BEEPER_CONFIG.dshotBeaconConditions = new Beepers(FC.CONFIG, [ "RX_LOST", "RX_SET" ]);
|
||||
FC.BEEPER_CONFIG.dshotBeaconConditions.setMask(configuration.BEEPER_CONFIG.dshotBeaconConditions._beeperMask);
|
||||
}
|
||||
|
||||
function send_unique_data_item() {
|
||||
|
@ -892,14 +892,14 @@ function configuration_restore(callback) {
|
|||
}
|
||||
|
||||
function send_led_strip_mode_colors() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.19.0"))
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.19.0"))
|
||||
mspHelper.sendLedStripModeColors(send_rxfail_config);
|
||||
else
|
||||
send_rxfail_config();
|
||||
}
|
||||
|
||||
function send_rxfail_config() {
|
||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||
if (semver.gte(FC.CONFIG.apiVersion, "1.15.0")) {
|
||||
mspHelper.sendRxFailConfig(save_to_eeprom);
|
||||
} else {
|
||||
save_to_eeprom();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue