mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
Preparation for conversion to parameter groups 6
This commit is contained in:
parent
cb2356ba76
commit
4c435fccae
23 changed files with 93 additions and 88 deletions
|
@ -35,6 +35,7 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "config/config_master.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
|
@ -1183,7 +1184,7 @@ static bool blackboxWriteSysinfo()
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
|
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
|
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
|
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", systemConfig()->name);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
|
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", blackboxConfig()->rate_num, blackboxConfig()->rate_denom);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", motorConfig()->minthrottle);
|
BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", motorConfig()->minthrottle);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", motorConfig()->maxthrottle);
|
BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", motorConfig()->maxthrottle);
|
||||||
|
@ -1295,8 +1296,8 @@ static bool blackboxWriteSysinfo()
|
||||||
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", motorConfig()->motorPwmProtocol);
|
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", motorConfig()->motorPwmProtocol);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", motorConfig()->motorPwmRate);
|
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", motorConfig()->motorPwmRate);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("digitalIdleOffset:%d", (int)(motorConfig()->digitalIdleOffsetPercent * 100.0f));
|
BLACKBOX_PRINT_HEADER_LINE("digitalIdleOffset:%d", (int)(motorConfig()->digitalIdleOffsetPercent * 100.0f));
|
||||||
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", masterConfig.debug_mode);
|
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", systemConfig()->debug_mode);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
|
BLACKBOX_PRINT_HEADER_LINE("features:%d", featureConfig()->enabledFeatures);
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -20,6 +20,7 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
#include "blackbox/blackbox.h"
|
#include "blackbox/blackbox.h"
|
||||||
|
|
||||||
|
@ -67,6 +68,8 @@
|
||||||
#include "sensors/compass.h"
|
#include "sensors/compass.h"
|
||||||
|
|
||||||
#ifndef USE_PARAMETER_GROUPS
|
#ifndef USE_PARAMETER_GROUPS
|
||||||
|
#define featureConfig(x) (&masterConfig.featureConfig)
|
||||||
|
#define systemConfig(x) (&masterConfig.systemConfig)
|
||||||
#define motorConfig(x) (&masterConfig.motorConfig)
|
#define motorConfig(x) (&masterConfig.motorConfig)
|
||||||
#define flight3DConfig(x) (&masterConfig.flight3DConfig)
|
#define flight3DConfig(x) (&masterConfig.flight3DConfig)
|
||||||
#define servoConfig(x) (&masterConfig.servoConfig)
|
#define servoConfig(x) (&masterConfig.servoConfig)
|
||||||
|
@ -115,6 +118,8 @@
|
||||||
#define displayPortProfileOled(x) (&masterConfig.displayPortProfileOled)
|
#define displayPortProfileOled(x) (&masterConfig.displayPortProfileOled)
|
||||||
|
|
||||||
|
|
||||||
|
#define featureConfigMutable(x) (&masterConfig.featureConfig)
|
||||||
|
#define systemConfigMutable(x) (&masterConfig.systemConfig)
|
||||||
#define motorConfigMutable(x) (&masterConfig.motorConfig)
|
#define motorConfigMutable(x) (&masterConfig.motorConfig)
|
||||||
#define flight3DConfigMutable(x) (&masterConfig.flight3DConfig)
|
#define flight3DConfigMutable(x) (&masterConfig.flight3DConfig)
|
||||||
#define servoConfigMutable(x) (&masterConfig.servoConfig)
|
#define servoConfigMutable(x) (&masterConfig.servoConfig)
|
||||||
|
@ -180,7 +185,9 @@ typedef struct master_s {
|
||||||
uint16_t size;
|
uint16_t size;
|
||||||
uint8_t magic_be; // magic number, should be 0xBE
|
uint8_t magic_be; // magic number, should be 0xBE
|
||||||
|
|
||||||
uint32_t enabledFeatures;
|
featureConfig_t featureConfig;
|
||||||
|
|
||||||
|
systemConfig_t systemConfig;
|
||||||
|
|
||||||
// motor/esc/servo related stuff
|
// motor/esc/servo related stuff
|
||||||
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
|
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
|
||||||
|
@ -205,7 +212,6 @@ typedef struct master_s {
|
||||||
|
|
||||||
pidConfig_t pidConfig;
|
pidConfig_t pidConfig;
|
||||||
|
|
||||||
uint8_t debug_mode; // Processing denominator for PID controller vs gyro sampling rate
|
|
||||||
uint8_t task_statistics;
|
uint8_t task_statistics;
|
||||||
|
|
||||||
gyroConfig_t gyroConfig;
|
gyroConfig_t gyroConfig;
|
||||||
|
@ -318,7 +324,6 @@ typedef struct master_s {
|
||||||
uint32_t beeper_off_flags;
|
uint32_t beeper_off_flags;
|
||||||
uint32_t preferred_beeper_off_flags;
|
uint32_t preferred_beeper_off_flags;
|
||||||
|
|
||||||
char name[MAX_NAME_LENGTH + 1];
|
|
||||||
char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER)];
|
char boardIdentifier[sizeof(TARGET_BOARD_IDENTIFIER)];
|
||||||
|
|
||||||
uint8_t magic_ef; // magic number, should be 0xEF
|
uint8_t magic_ef; // magic number, should be 0xEF
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "config/config_master.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
#include "config/parameter_group.h"
|
#include "config/parameter_group.h"
|
||||||
#include "config/parameter_group_ids.h"
|
#include "config/parameter_group_ids.h"
|
||||||
|
@ -45,12 +46,12 @@ void intFeatureClearAll(uint32_t *features)
|
||||||
|
|
||||||
void latchActiveFeatures()
|
void latchActiveFeatures()
|
||||||
{
|
{
|
||||||
activeFeaturesLatch = masterConfig.enabledFeatures;
|
activeFeaturesLatch = featureConfig()->enabledFeatures;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool featureConfigured(uint32_t mask)
|
bool featureConfigured(uint32_t mask)
|
||||||
{
|
{
|
||||||
return masterConfig.enabledFeatures & mask;
|
return featureConfig()->enabledFeatures & mask;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool feature(uint32_t mask)
|
bool feature(uint32_t mask)
|
||||||
|
@ -60,22 +61,22 @@ bool feature(uint32_t mask)
|
||||||
|
|
||||||
void featureSet(uint32_t mask)
|
void featureSet(uint32_t mask)
|
||||||
{
|
{
|
||||||
intFeatureSet(mask, &masterConfig.enabledFeatures);
|
intFeatureSet(mask, &featureConfigMutable()->enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
void featureClear(uint32_t mask)
|
void featureClear(uint32_t mask)
|
||||||
{
|
{
|
||||||
intFeatureClear(mask, &masterConfig.enabledFeatures);
|
intFeatureClear(mask, &featureConfigMutable()->enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
void featureClearAll()
|
void featureClearAll()
|
||||||
{
|
{
|
||||||
intFeatureClearAll(&masterConfig.enabledFeatures);
|
intFeatureClearAll(&featureConfigMutable()->enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t featureMask(void)
|
uint32_t featureMask(void)
|
||||||
{
|
{
|
||||||
return masterConfig.enabledFeatures;
|
return featureConfig()->enabledFeatures;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -46,6 +46,7 @@ uint8_t cliMode = 0;
|
||||||
#include "common/printf.h"
|
#include "common/printf.h"
|
||||||
#include "common/typeconversion.h"
|
#include "common/typeconversion.h"
|
||||||
|
|
||||||
|
#include "config/config_master.h"
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
@ -522,7 +523,7 @@ static const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
{ "fpv_mix_degrees", VAR_UINT8 | MASTER_VALUE, &rxConfig()->fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
|
{ "fpv_mix_degrees", VAR_UINT8 | MASTER_VALUE, &rxConfig()->fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
|
||||||
{ "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &rxConfig()->max_aux_channel, .config.minmax = { 0, MAX_AUX_CHANNELS } },
|
{ "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &rxConfig()->max_aux_channel, .config.minmax = { 0, MAX_AUX_CHANNELS } },
|
||||||
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
|
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &systemConfig()->debug_mode, .config.lookup = { TABLE_DEBUG } },
|
||||||
|
|
||||||
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &motorConfig()->minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &motorConfig()->minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &motorConfig()->maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &motorConfig()->maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||||
|
@ -2140,7 +2141,7 @@ static void cliRxRange(char *cmdline)
|
||||||
if (isEmpty(cmdline)) {
|
if (isEmpty(cmdline)) {
|
||||||
printRxRange(DUMP_MASTER, rxConfig(), NULL);
|
printRxRange(DUMP_MASTER, rxConfig(), NULL);
|
||||||
} else if (strcasecmp(cmdline, "reset") == 0) {
|
} else if (strcasecmp(cmdline, "reset") == 0) {
|
||||||
resetAllRxChannelRangeConfigurations(rxConfig()->channelRanges);
|
resetAllRxChannelRangeConfigurations(rxConfigMutable()->channelRanges);
|
||||||
} else {
|
} else {
|
||||||
ptr = cmdline;
|
ptr = cmdline;
|
||||||
i = atoi(ptr);
|
i = atoi(ptr);
|
||||||
|
@ -2164,7 +2165,7 @@ static void cliRxRange(char *cmdline)
|
||||||
} else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
|
} else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
|
||||||
cliShowParseError();
|
cliShowParseError();
|
||||||
} else {
|
} else {
|
||||||
rxChannelRangeConfiguration_t *channelRangeConfiguration = &rxConfig()->channelRanges[i];
|
rxChannelRangeConfiguration_t *channelRangeConfiguration = &rxConfigMutable()->channelRanges[i];
|
||||||
channelRangeConfiguration->min = rangeMin;
|
channelRangeConfiguration->min = rangeMin;
|
||||||
channelRangeConfiguration->max = rangeMax;
|
channelRangeConfiguration->max = rangeMax;
|
||||||
}
|
}
|
||||||
|
@ -2879,26 +2880,26 @@ static void cliVtx(char *cmdline)
|
||||||
|
|
||||||
static void printName(uint8_t dumpMask)
|
static void printName(uint8_t dumpMask)
|
||||||
{
|
{
|
||||||
bool equalsDefault = strlen(masterConfig.name) == 0;
|
const bool equalsDefault = strlen(systemConfig()->name) == 0;
|
||||||
cliDumpPrintf(dumpMask, equalsDefault, "name %s\r\n", equalsDefault ? emptyName : masterConfig.name);
|
cliDumpPrintf(dumpMask, equalsDefault, "name %s\r\n", equalsDefault ? emptyName : systemConfig()->name);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliName(char *cmdline)
|
static void cliName(char *cmdline)
|
||||||
{
|
{
|
||||||
uint32_t len = strlen(cmdline);
|
const uint32_t len = strlen(cmdline);
|
||||||
if (len > 0) {
|
if (len > 0) {
|
||||||
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
|
memset(systemConfigMutable()->name, 0, ARRAYLEN(systemConfig()->name));
|
||||||
if (strncmp(cmdline, emptyName, len)) {
|
if (strncmp(cmdline, emptyName, len)) {
|
||||||
strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
|
strncpy(systemConfigMutable()->name, cmdline, MIN(len, MAX_NAME_LENGTH));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
printName(DUMP_MASTER);
|
printName(DUMP_MASTER);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void printFeature(uint8_t dumpMask, const master_t *defaultConfig)
|
static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfigDefault)
|
||||||
{
|
{
|
||||||
uint32_t mask = featureMask();
|
const uint32_t mask = featureMask();
|
||||||
uint32_t defaultMask = defaultConfig->enabledFeatures;
|
const uint32_t defaultMask = featureConfigDefault->enabledFeatures;
|
||||||
for (uint32_t i = 0; ; i++) { // disable all feature first
|
for (uint32_t i = 0; ; i++) { // disable all feature first
|
||||||
if (featureNames[i] == NULL)
|
if (featureNames[i] == NULL)
|
||||||
break;
|
break;
|
||||||
|
@ -4039,7 +4040,7 @@ static void printConfig(char *cmdline, bool doDiff)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
cliPrintHashLine("feature");
|
cliPrintHashLine("feature");
|
||||||
printFeature(dumpMask, &defaultConfig);
|
printFeature(dumpMask, &defaultConfig.featureConfig);
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef BEEPER
|
||||||
cliPrintHashLine("beeper");
|
cliPrintHashLine("beeper");
|
||||||
|
|
|
@ -581,7 +581,7 @@ void createDefaultConfig(master_t *config)
|
||||||
// Clear all configuration
|
// Clear all configuration
|
||||||
memset(config, 0, sizeof(master_t));
|
memset(config, 0, sizeof(master_t));
|
||||||
|
|
||||||
uint32_t *featuresPtr = &config->enabledFeatures;
|
uint32_t *featuresPtr = &config->featureConfig.enabledFeatures;
|
||||||
|
|
||||||
intFeatureClearAll(featuresPtr);
|
intFeatureClearAll(featuresPtr);
|
||||||
intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
|
intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
|
||||||
|
@ -635,7 +635,7 @@ void createDefaultConfig(master_t *config)
|
||||||
config->gyroConfig.gyro_soft_notch_hz_2 = 200;
|
config->gyroConfig.gyro_soft_notch_hz_2 = 200;
|
||||||
config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
|
config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
|
||||||
|
|
||||||
config->debug_mode = DEBUG_MODE;
|
config->systemConfig.debug_mode = DEBUG_MODE;
|
||||||
config->task_statistics = true;
|
config->task_statistics = true;
|
||||||
|
|
||||||
resetAccelerometerTrims(&config->accelerometerConfig.accZero);
|
resetAccelerometerTrims(&config->accelerometerConfig.accZero);
|
||||||
|
@ -891,7 +891,7 @@ void activateConfig(void)
|
||||||
|
|
||||||
resetAdjustmentStates();
|
resetAdjustmentStates();
|
||||||
|
|
||||||
useRcControlsConfig(modeActivationProfile()->modeActivationConditions, ¤tProfile->pidProfile);
|
useRcControlsConfig(modeActivationConditions(0), ¤tProfile->pidProfile);
|
||||||
useAdjustmentConfig(¤tProfile->pidProfile);
|
useAdjustmentConfig(¤tProfile->pidProfile);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
@ -909,11 +909,7 @@ void activateConfig(void)
|
||||||
servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.gimbalConfig, &masterConfig.channelForwardingConfig);
|
servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.gimbalConfig, &masterConfig.channelForwardingConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
imuConfigure(
|
imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
|
||||||
&masterConfig.imuConfig,
|
|
||||||
¤tProfile->pidProfile,
|
|
||||||
throttleCorrectionConfig()->throttle_correction_angle
|
|
||||||
);
|
|
||||||
|
|
||||||
configureAltitudeHold(¤tProfile->pidProfile);
|
configureAltitudeHold(¤tProfile->pidProfile);
|
||||||
}
|
}
|
||||||
|
@ -925,7 +921,7 @@ void validateAndFixConfig(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((motorConfig()->motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
|
if ((motorConfig()->motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
|
||||||
motorConfig()->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
|
motorConfigMutable()->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
|
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
|
||||||
|
|
|
@ -63,9 +63,11 @@ typedef enum {
|
||||||
|
|
||||||
typedef struct systemConfig_s {
|
typedef struct systemConfig_s {
|
||||||
uint8_t debug_mode;
|
uint8_t debug_mode;
|
||||||
|
char name[MAX_NAME_LENGTH + 1];
|
||||||
} systemConfig_t;
|
} systemConfig_t;
|
||||||
|
|
||||||
//!!TODOPG_DECLARE(systemConfig_t, systemConfig);
|
PG_DECLARE(systemConfig_t, systemConfig);
|
||||||
|
|
||||||
struct profile_s;
|
struct profile_s;
|
||||||
extern struct profile_s *currentProfile;
|
extern struct profile_s *currentProfile;
|
||||||
struct controlRateConfig_s;
|
struct controlRateConfig_s;
|
||||||
|
|
|
@ -45,11 +45,13 @@
|
||||||
#include "sensors/gyro.h"
|
#include "sensors/gyro.h"
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
|
||||||
|
#include "fc/cli.h"
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
#include "fc/fc_core.h"
|
||||||
|
#include "fc/fc_rc.h"
|
||||||
|
#include "fc/rc_adjustments.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
#include "fc/cli.h"
|
|
||||||
#include "fc/fc_rc.h"
|
|
||||||
|
|
||||||
#include "msp/msp_serial.h"
|
#include "msp/msp_serial.h"
|
||||||
|
|
||||||
|
@ -359,10 +361,10 @@ void processRx(timeUs_t currentTimeUs)
|
||||||
updateInflightCalibrationState();
|
updateInflightCalibrationState();
|
||||||
}
|
}
|
||||||
|
|
||||||
updateActivatedModes(modeActivationProfile()->modeActivationConditions);
|
updateActivatedModes();
|
||||||
|
|
||||||
if (!cliMode) {
|
if (!cliMode) {
|
||||||
updateAdjustmentStates(adjustmentProfile()->adjustmentRanges);
|
updateAdjustmentStates();
|
||||||
processRcAdjustments(currentControlRateProfile);
|
processRcAdjustments(currentControlRateProfile);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -527,6 +529,8 @@ static void subTaskMainSubprocesses(timeUs_t currentTimeUs)
|
||||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||||
handleBlackbox(currentTimeUs);
|
handleBlackbox(currentTimeUs);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
UNUSED(currentTimeUs);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
|
|
|
@ -188,7 +188,7 @@ void init(void)
|
||||||
|
|
||||||
//i2cSetOverclock(masterConfig.i2c_overclock);
|
//i2cSetOverclock(masterConfig.i2c_overclock);
|
||||||
|
|
||||||
debugMode = masterConfig.debug_mode;
|
debugMode = systemConfig()->debug_mode;
|
||||||
|
|
||||||
// Latch active features to be used for feature() in the remainder of init().
|
// Latch active features to be used for feature() in the remainder of init().
|
||||||
latchActiveFeatures();
|
latchActiveFeatures();
|
||||||
|
@ -271,7 +271,7 @@ void init(void)
|
||||||
serialInit(feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
serialInit(feature(FEATURE_SOFTSERIAL), SERIAL_PORT_NONE);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
mixerInit(mixerConfig()->mixerMode, masterConfig.customMotorMixer);
|
mixerInit(mixerConfig()->mixerMode, customMotorMixerMutable(0));
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
servoMixerInit(masterConfig.customServoMixer);
|
servoMixerInit(masterConfig.customServoMixer);
|
||||||
#endif
|
#endif
|
||||||
|
@ -445,7 +445,7 @@ void init(void)
|
||||||
|
|
||||||
failsafeInit();
|
failsafeInit();
|
||||||
|
|
||||||
rxInit(rxConfig(), modeActivationProfile()->modeActivationConditions);
|
rxInit(rxConfig(), modeActivationConditions(0));
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
|
|
|
@ -34,6 +34,7 @@
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/streambuf.h"
|
#include "common/streambuf.h"
|
||||||
|
|
||||||
|
#include "config/config_master.h"
|
||||||
#include "config/config_eeprom.h"
|
#include "config/config_eeprom.h"
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
#include "config/feature.h"
|
#include "config/feature.h"
|
||||||
|
@ -60,6 +61,7 @@
|
||||||
#include "fc/fc_core.h"
|
#include "fc/fc_core.h"
|
||||||
#include "fc/fc_msp.h"
|
#include "fc/fc_msp.h"
|
||||||
#include "fc/fc_rc.h"
|
#include "fc/fc_rc.h"
|
||||||
|
#include "fc/rc_adjustments.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
@ -638,9 +640,9 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
||||||
|
|
||||||
case MSP_NAME:
|
case MSP_NAME:
|
||||||
{
|
{
|
||||||
const int nameLen = strlen(masterConfig.name);
|
const int nameLen = strlen(systemConfig()->name);
|
||||||
for (int i = 0; i < nameLen; i++) {
|
for (int i = 0; i < nameLen; i++) {
|
||||||
sbufWriteU8(dst, masterConfig.name[i]);
|
sbufWriteU8(dst, systemConfig()->name[i]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -795,7 +797,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
||||||
|
|
||||||
case MSP_MODE_RANGES:
|
case MSP_MODE_RANGES:
|
||||||
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||||
modeActivationCondition_t *mac = &modeActivationProfile()->modeActivationConditions[i];
|
const modeActivationCondition_t *mac = modeActivationConditions(i);
|
||||||
const box_t *box = &boxes[mac->modeId];
|
const box_t *box = &boxes[mac->modeId];
|
||||||
sbufWriteU8(dst, box->permanentId);
|
sbufWriteU8(dst, box->permanentId);
|
||||||
sbufWriteU8(dst, mac->auxChannelIndex);
|
sbufWriteU8(dst, mac->auxChannelIndex);
|
||||||
|
@ -1935,9 +1937,9 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case MSP_SET_NAME:
|
case MSP_SET_NAME:
|
||||||
memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
|
memset(systemConfigMutable()->name, 0, ARRAYLEN(systemConfig()->name));
|
||||||
for (unsigned int i = 0; i < MIN(MAX_NAME_LENGTH, dataSize); i++) {
|
for (unsigned int i = 0; i < MIN(MAX_NAME_LENGTH, dataSize); i++) {
|
||||||
masterConfig.name[i] = sbufReadU8(src);
|
systemConfigMutable()->name[i] = sbufReadU8(src);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
|
@ -435,10 +435,15 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges)
|
void resetAdjustmentStates(void)
|
||||||
|
{
|
||||||
|
memset(adjustmentStates, 0, sizeof(adjustmentStates));
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateAdjustmentStates(void)
|
||||||
{
|
{
|
||||||
for (int index = 0; index < MAX_ADJUSTMENT_RANGE_COUNT; index++) {
|
for (int index = 0; index < MAX_ADJUSTMENT_RANGE_COUNT; index++) {
|
||||||
adjustmentRange_t *adjustmentRange = &adjustmentRanges[index];
|
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(index);
|
||||||
if (isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range)) {
|
if (isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range)) {
|
||||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentFunction - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentFunction - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||||
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
|
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
|
||||||
|
@ -446,11 +451,6 @@ void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void resetAdjustmentStates(void)
|
|
||||||
{
|
|
||||||
memset(adjustmentStates, 0, sizeof(adjustmentStates));
|
|
||||||
}
|
|
||||||
|
|
||||||
void useAdjustmentConfig(pidProfile_t *pidProfileToUse)
|
void useAdjustmentConfig(pidProfile_t *pidProfileToUse)
|
||||||
{
|
{
|
||||||
pidProfile = pidProfileToUse;
|
pidProfile = pidProfileToUse;
|
||||||
|
|
|
@ -109,7 +109,7 @@ typedef struct adjustmentProfile_s {
|
||||||
} adjustmentProfile_t;
|
} adjustmentProfile_t;
|
||||||
|
|
||||||
void resetAdjustmentStates(void);
|
void resetAdjustmentStates(void);
|
||||||
void updateAdjustmentStates(adjustmentRange_t *adjustmentRanges);
|
void updateAdjustmentStates(void);
|
||||||
struct controlRateConfig_s;
|
struct controlRateConfig_s;
|
||||||
void processRcAdjustments(struct controlRateConfig_s *controlRateConfig);
|
void processRcAdjustments(struct controlRateConfig_s *controlRateConfig);
|
||||||
struct pidProfile_s;
|
struct pidProfile_s;
|
||||||
|
|
|
@ -302,24 +302,22 @@ bool isModeActivationConditionPresent(const modeActivationCondition_t *modeActiv
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool isRangeActive(uint8_t auxChannelIndex, channelRange_t *range) {
|
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) {
|
||||||
if (!IS_RANGE_USABLE(range)) {
|
if (!IS_RANGE_USABLE(range)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t channelValue = constrain(rcData[auxChannelIndex + NON_AUX_CHANNEL_COUNT], CHANNEL_RANGE_MIN, CHANNEL_RANGE_MAX - 1);
|
const uint16_t channelValue = constrain(rcData[auxChannelIndex + NON_AUX_CHANNEL_COUNT], CHANNEL_RANGE_MIN, CHANNEL_RANGE_MAX - 1);
|
||||||
return (channelValue >= 900 + (range->startStep * 25) &&
|
return (channelValue >= 900 + (range->startStep * 25) &&
|
||||||
channelValue < 900 + (range->endStep * 25));
|
channelValue < 900 + (range->endStep * 25));
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateActivatedModes(modeActivationCondition_t *modeActivationConditions)
|
void updateActivatedModes(void)
|
||||||
{
|
{
|
||||||
rcModeActivationMask = 0;
|
rcModeActivationMask = 0;
|
||||||
|
|
||||||
uint8_t index;
|
for (int index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
|
||||||
|
const modeActivationCondition_t *modeActivationCondition = modeActivationConditions(index);
|
||||||
for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) {
|
|
||||||
modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index];
|
|
||||||
|
|
||||||
if (isRangeActive(modeActivationCondition->auxChannelIndex, &modeActivationCondition->range)) {
|
if (isRangeActive(modeActivationCondition->auxChannelIndex, &modeActivationCondition->range)) {
|
||||||
ACTIVATE_RC_MODE(modeActivationCondition->modeId);
|
ACTIVATE_RC_MODE(modeActivationCondition->modeId);
|
||||||
|
|
|
@ -200,8 +200,8 @@ bool areSticksInApModePosition(uint16_t ap_mode);
|
||||||
throttleStatus_e calculateThrottleStatus(void);
|
throttleStatus_e calculateThrottleStatus(void);
|
||||||
void processRcStickPositions(throttleStatus_e throttleStatus);
|
void processRcStickPositions(throttleStatus_e throttleStatus);
|
||||||
|
|
||||||
bool isRangeActive(uint8_t auxChannelIndex, channelRange_t *range);
|
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range);
|
||||||
void updateActivatedModes(modeActivationCondition_t *modeActivationConditions);
|
void updateActivatedModes(void);
|
||||||
|
|
||||||
bool isAirmodeActive(void);
|
bool isAirmodeActive(void);
|
||||||
|
|
||||||
|
|
|
@ -70,7 +70,6 @@ static float smallAngleCosZ = 0;
|
||||||
static float magneticDeclination = 0.0f; // calculated at startup from config
|
static float magneticDeclination = 0.0f; // calculated at startup from config
|
||||||
|
|
||||||
static imuRuntimeConfig_t imuRuntimeConfig;
|
static imuRuntimeConfig_t imuRuntimeConfig;
|
||||||
static pidProfile_t *pidProfile;
|
|
||||||
|
|
||||||
STATIC_UNIT_TESTED float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to earth frame
|
STATIC_UNIT_TESTED float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to earth frame
|
||||||
static float rMat[3][3];
|
static float rMat[3][3];
|
||||||
|
@ -116,18 +115,13 @@ static float calculateThrottleAngleScale(uint16_t throttle_correction_angle)
|
||||||
return (1800.0f / M_PIf) * (900.0f / throttle_correction_angle);
|
return (1800.0f / M_PIf) * (900.0f / throttle_correction_angle);
|
||||||
}
|
}
|
||||||
|
|
||||||
void imuConfigure(
|
void imuConfigure(uint16_t throttle_correction_angle)
|
||||||
imuConfig_t *imuConfig,
|
|
||||||
pidProfile_t *initialPidProfile,
|
|
||||||
uint16_t throttle_correction_angle
|
|
||||||
)
|
|
||||||
{
|
{
|
||||||
imuRuntimeConfig.dcm_kp = imuConfig->dcm_kp / 10000.0f;
|
imuRuntimeConfig.dcm_kp = imuConfig()->dcm_kp / 10000.0f;
|
||||||
imuRuntimeConfig.dcm_ki = imuConfig->dcm_ki / 10000.0f;
|
imuRuntimeConfig.dcm_ki = imuConfig()->dcm_ki / 10000.0f;
|
||||||
imuRuntimeConfig.acc_unarmedcal = imuConfig->acc_unarmedcal;
|
imuRuntimeConfig.acc_unarmedcal = imuConfig()->acc_unarmedcal;
|
||||||
imuRuntimeConfig.small_angle = imuConfig->small_angle;
|
imuRuntimeConfig.small_angle = imuConfig()->small_angle;
|
||||||
|
|
||||||
pidProfile = initialPidProfile;
|
|
||||||
fc_acc = calculateAccZLowPassFilterRCTimeConstant(5.0f); // Set to fix value
|
fc_acc = calculateAccZLowPassFilterRCTimeConstant(5.0f); // Set to fix value
|
||||||
throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
|
throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
|
||||||
}
|
}
|
||||||
|
|
|
@ -64,8 +64,7 @@ typedef struct imuRuntimeConfig_s {
|
||||||
accDeadband_t accDeadband;
|
accDeadband_t accDeadband;
|
||||||
} imuRuntimeConfig_t;
|
} imuRuntimeConfig_t;
|
||||||
|
|
||||||
struct pidProfile_s;
|
void imuConfigure(uint16_t throttle_correction_angle);
|
||||||
void imuConfigure(imuConfig_t *imuConfig, struct pidProfile_s *initialPidProfile, uint16_t throttle_correction_angle);
|
|
||||||
|
|
||||||
float getCosTiltAngle(void);
|
float getCosTiltAngle(void);
|
||||||
void calculateEstimatedAltitude(timeUs_t currentTimeUs);
|
void calculateEstimatedAltitude(timeUs_t currentTimeUs);
|
||||||
|
|
|
@ -232,7 +232,7 @@ const mixer_t mixers[] = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static motorMixer_t *customMixers;
|
static const motorMixer_t *customMixers;
|
||||||
|
|
||||||
static uint16_t disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
|
static uint16_t disarmMotorOutput, deadbandMotor3dHigh, deadbandMotor3dLow;
|
||||||
uint16_t motorOutputHigh, motorOutputLow;
|
uint16_t motorOutputHigh, motorOutputLow;
|
||||||
|
@ -296,7 +296,7 @@ void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse)
|
||||||
airplaneConfig = airplaneConfigToUse;
|
airplaneConfig = airplaneConfigToUse;
|
||||||
}
|
}
|
||||||
|
|
||||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMixers)
|
void mixerInit(mixerMode_e mixerMode, const motorMixer_t *initialCustomMixers)
|
||||||
{
|
{
|
||||||
currentMixerMode = mixerMode;
|
currentMixerMode = mixerMode;
|
||||||
|
|
||||||
|
|
|
@ -135,7 +135,7 @@ float getMotorMixRange();
|
||||||
void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse);
|
void mixerUseConfigs(airplaneConfig_t *airplaneConfigToUse);
|
||||||
|
|
||||||
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
||||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers);
|
void mixerInit(mixerMode_e mixerMode, const motorMixer_t *customMotorMixers);
|
||||||
|
|
||||||
void mixerConfigureOutput(void);
|
void mixerConfigureOutput(void);
|
||||||
|
|
||||||
|
|
|
@ -85,7 +85,7 @@ typedef struct pidProfile_s {
|
||||||
float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
|
float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
|
||||||
} pidProfile_t;
|
} pidProfile_t;
|
||||||
|
|
||||||
PG_DECLARE_PROFILE(pidProfile_t, pidProfile);
|
//PG_DECLARE_PROFILE(pidProfile_t, pidProfile);
|
||||||
|
|
||||||
typedef struct pidConfig_s {
|
typedef struct pidConfig_s {
|
||||||
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
|
uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
|
||||||
|
|
|
@ -248,12 +248,12 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
|
|
||||||
case OSD_CRAFT_NAME:
|
case OSD_CRAFT_NAME:
|
||||||
{
|
{
|
||||||
if (strlen(masterConfig.name) == 0)
|
if (strlen(systemConfig()->name) == 0)
|
||||||
strcpy(buff, "CRAFT_NAME");
|
strcpy(buff, "CRAFT_NAME");
|
||||||
else {
|
else {
|
||||||
for (uint8_t i = 0; i < MAX_NAME_LENGTH; i++) {
|
for (uint8_t i = 0; i < MAX_NAME_LENGTH; i++) {
|
||||||
buff[i] = toupper((unsigned char)masterConfig.name[i]);
|
buff[i] = toupper((unsigned char)systemConfig()->name[i]);
|
||||||
if (masterConfig.name[i] == 0)
|
if (systemConfig()->name[i] == 0)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -33,6 +33,8 @@
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "io/beeper.h"
|
#include "io/beeper.h"
|
||||||
|
@ -273,7 +275,7 @@ void updateCurrentMeter(int32_t lastUpdateAt)
|
||||||
case CURRENT_SENSOR_VIRTUAL:
|
case CURRENT_SENSOR_VIRTUAL:
|
||||||
amperageLatest = (int32_t)batteryConfig()->currentMeterOffset;
|
amperageLatest = (int32_t)batteryConfig()->currentMeterOffset;
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
throttleStatus_e throttleStatus = calculateThrottleStatus();
|
const throttleStatus_e throttleStatus = calculateThrottleStatus();
|
||||||
int throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
|
int throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000;
|
||||||
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) {
|
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) {
|
||||||
throttleOffset = 0;
|
throttleOffset = 0;
|
||||||
|
|
|
@ -75,7 +75,7 @@ void targetConfiguration(master_t *config)
|
||||||
config->rxConfig.sbus_inversion = 0;
|
config->rxConfig.sbus_inversion = 0;
|
||||||
config->serialConfig.portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
config->serialConfig.portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||||
config->telemetryConfig.telemetry_inversion = 0;
|
config->telemetryConfig.telemetry_inversion = 0;
|
||||||
intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY, &config->enabledFeatures);
|
intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY, &config->featureConfig.enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
config->profile[0].pidProfile.P8[ROLL] = 53;
|
config->profile[0].pidProfile.P8[ROLL] = 53;
|
||||||
|
|
|
@ -39,7 +39,7 @@ void targetConfiguration(master_t *config)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) {
|
if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) {
|
||||||
intFeatureClear(FEATURE_SDCARD, &config->enabledFeatures);
|
intFeatureClear(FEATURE_SDCARD, &config->featureConfig.enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hardwareRevision == BJF4_MINI_REV3A) {
|
if (hardwareRevision == BJF4_MINI_REV3A) {
|
||||||
|
@ -51,7 +51,7 @@ void targetValidateConfiguration(master_t *config)
|
||||||
{
|
{
|
||||||
/* make sure the SDCARD cannot be turned on */
|
/* make sure the SDCARD cannot be turned on */
|
||||||
if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) {
|
if (hardwareRevision == BJF4_MINI_REV3A || hardwareRevision == BJF4_REV1) {
|
||||||
intFeatureClear(FEATURE_SDCARD, &config->enabledFeatures);
|
intFeatureClear(FEATURE_SDCARD, &config->featureConfig.enabledFeatures);
|
||||||
|
|
||||||
if (config->blackboxConfig.device == BLACKBOX_DEVICE_SDCARD) {
|
if (config->blackboxConfig.device == BLACKBOX_DEVICE_SDCARD) {
|
||||||
config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
|
config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
|
||||||
|
|
|
@ -51,6 +51,6 @@ void targetConfiguration(master_t *config)
|
||||||
config->telemetryConfig.telemetry_inversion = 0;
|
config->telemetryConfig.telemetry_inversion = 0;
|
||||||
config->rxConfig.sbus_inversion = 0;
|
config->rxConfig.sbus_inversion = 0;
|
||||||
|
|
||||||
intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, &config->enabledFeatures);
|
intFeatureSet(FEATURE_CURRENT_METER | FEATURE_VBAT, &config->featureConfig.enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue