Skip to content

Commit

Permalink
Get setting default values from settings.yaml
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Feb 11, 2021
1 parent 730e1a7 commit 5087026
Show file tree
Hide file tree
Showing 80 changed files with 1,568 additions and 1,814 deletions.
342 changes: 171 additions & 171 deletions docs/Settings.md

Large diffs are not rendered by default.

21 changes: 16 additions & 5 deletions src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "fc/settings.h"

#include "flight/failsafe.h"
#include "flight/imu.h"
Expand Down Expand Up @@ -91,18 +92,18 @@
#endif

#ifdef SDCARD_DETECT_INVERTED
#define BLACKBOX_INTERVED_CARD_DETECTION 1
#define BLACKBOX_INVERTED_CARD_DETECTION 1
#else
#define BLACKBOX_INTERVED_CARD_DETECTION 0
#define BLACKBOX_INVERTED_CARD_DETECTION 0
#endif

PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 1);

PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
.device = DEFAULT_BLACKBOX_DEVICE,
.rate_num = 1,
.rate_denom = 1,
.invertedCardDetection = BLACKBOX_INTERVED_CARD_DETECTION,
.rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
.rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
.invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
);

#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
Expand Down Expand Up @@ -1656,6 +1657,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),motorConfig()->maxthrottle);
BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G);

#ifdef USE_ADC
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
blackboxPrintfHeaderLine("vbat_scale", "%u", batteryMetersConfig()->voltage.scale / 10);
Expand All @@ -1667,6 +1669,7 @@ static bool blackboxWriteSysinfo(void)
currentBatteryProfile->voltage.cellWarning / 10,
currentBatteryProfile->voltage.cellMax / 10);
BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
#endif

BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
Expand Down Expand Up @@ -1723,17 +1726,25 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_hz", "%d", gyroConfig()->gyro_soft_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_type", "%d", gyroConfig()->gyro_soft_lpf_type);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf2_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz);
#ifdef USE_DYNAMIC_FILTERS
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchRange", "%d", gyroConfig()->dynamicGyroNotchRange);
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ);
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz);
#endif
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_notch_hz,
0);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_notch_cutoff,
1);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", accelerometerConfig()->acc_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
#ifdef USE_BARO
BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
#endif
#ifdef USE_MAG
BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", compassConfig()->mag_hardware);
#else
BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", MAG_NONE);
#endif
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->motorPwmRate);
Expand Down
6 changes: 6 additions & 0 deletions src/main/common/log.c
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "io/serial.h"

#include "fc/config.h"
#include "fc/settings.h"

#include "msp/msp.h"
#include "msp/msp_serial.h"
Expand All @@ -54,6 +55,11 @@ static mspPort_t * mspLogPort = NULL;

PG_REGISTER(logConfig_t, logConfig, PG_LOG_CONFIG, 0);

PG_RESET_TEMPLATE(logConfig_t, logConfig,
.level = SETTING_LOG_LEVEL_DEFAULT,
.topics = SETTING_LOG_TOPICS_DEFAULT
);

void logInit(void)
{
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LOG);
Expand Down
6 changes: 4 additions & 2 deletions src/main/common/time.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include "drivers/time.h"

#include "fc/settings.h"

// For the "modulo 4" arithmetic to work, we need a leap base year
#define REFERENCE_YEAR 2000
// Offset (seconds) from the UNIX epoch (1970-01-01) to 2000-01-01
Expand All @@ -55,8 +57,8 @@ static const uint16_t days[4][12] =
PG_REGISTER_WITH_RESET_TEMPLATE(timeConfig_t, timeConfig, PG_TIME_CONFIG, 1);

PG_RESET_TEMPLATE(timeConfig_t, timeConfig,
.tz_offset = 0,
.tz_automatic_dst = TZ_AUTO_DST_OFF,
.tz_offset = SETTING_TZ_OFFSET_DEFAULT,
.tz_automatic_dst = SETTING_TZ_AUTOMATIC_DST_DEFAULT,
);

static rtcTime_t dateTimeToRtcTime(const dateTime_t *dt)
Expand Down
6 changes: 4 additions & 2 deletions src/main/config/general_settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,10 @@

#include "config/general_settings.h"

#include "fc/settings.h"

PG_REGISTER_WITH_RESET_TEMPLATE(generalSettings_t, generalSettings, PG_GENERAL_SETTINGS, 0);

PG_RESET_TEMPLATE(generalSettings_t, generalSettings,
.appliedDefaults = APPLIED_DEFAULTS_NONE,
);
.appliedDefaults = SETTING_APPLIED_DEFAULTS_DEFAULT,
);
3 changes: 2 additions & 1 deletion src/main/drivers/display.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include "drivers/display_font_metadata.h"
#include "drivers/time.h"

#include "fc/settings.h"

#define SW_BLINK_CYCLE_MS 200 // 200ms on / 200ms off

Expand All @@ -43,7 +44,7 @@
PG_REGISTER_WITH_RESET_TEMPLATE(displayConfig_t, displayConfig, PG_DISPLAY_CONFIG, 0);

PG_RESET_TEMPLATE(displayConfig_t, displayConfig,
.force_sw_blink = false,
.force_sw_blink = SETTING_DISPLAY_FORCE_SW_BLINK_DEFAULT
);

static bool displayAttributesRequireEmulation(displayPort_t *instance, textAttributes_t attr)
Expand Down
14 changes: 9 additions & 5 deletions src/main/fc/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -112,11 +112,15 @@ PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG,
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.current_profile_index = 0,
.current_battery_profile_index = 0,
.debug_mode = DEBUG_NONE,
.i2c_speed = I2C_SPEED_400KHZ,
.cpuUnderclock = 0,
.throttle_tilt_compensation_strength = 0, // 0-100, 0 - disabled
.name = { 0 }
.debug_mode = SETTING_DEBUG_MODE_DEFAULT,
#ifdef USE_I2C
.i2c_speed = SETTING_I2C_SPEED_DEFAULT,
#endif
#ifdef USE_UNDERCLOCK
.cpuUnderclock = SETTING_CPU_UNDERCLOCK_DEFAULT,
#endif
.throttle_tilt_compensation_strength = SETTING_THROTTLE_TILT_COMP_STR_DEFAULT, // 0-100, 0 - disabled
.name = SETTING_NAME_DEFAULT
);

PG_REGISTER(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 0);
Expand Down
4 changes: 4 additions & 0 deletions src/main/fc/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,12 @@ typedef struct systemConfig_s {
uint8_t current_profile_index;
uint8_t current_battery_profile_index;
uint8_t debug_mode;
#ifdef USE_I2C
uint8_t i2c_speed;
#endif
#ifdef USE_UNDERCLOCK
uint8_t cpuUnderclock;
#endif
uint8_t throttle_tilt_compensation_strength; // the correction that will be applied at throttle_correction_angle.
char name[MAX_NAME_LENGTH + 1];
} systemConfig_t;
Expand Down
33 changes: 17 additions & 16 deletions src/main/fc/controlrate_profile.c
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_curves.h"
#include "fc/settings.h"

const controlRateConfig_t *currentControlRateProfile;

Expand All @@ -40,31 +41,31 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance)
for (int i = 0; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
RESET_CONFIG(controlRateConfig_t, &instance[i],
.throttle = {
.rcMid8 = 50,
.rcExpo8 = 0,
.dynPID = 0,
.pa_breakpoint = 1500,
.fixedWingTauMs = 0
.rcMid8 = SETTING_THR_MID_DEFAULT,
.rcExpo8 = SETTING_THR_EXPO_DEFAULT,
.dynPID = SETTING_TPA_RATE_DEFAULT,
.pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT,
.fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT
},

.stabilized = {
.rcExpo8 = 70,
.rcYawExpo8 = 20,
.rates[FD_ROLL] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT,
.rates[FD_PITCH] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT,
.rates[FD_YAW] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT,
.rcExpo8 = SETTING_RC_EXPO_DEFAULT,
.rcYawExpo8 = SETTING_RC_YAW_EXPO_DEFAULT,
.rates[FD_ROLL] = SETTING_ROLL_RATE_DEFAULT,
.rates[FD_PITCH] = SETTING_PITCH_RATE_DEFAULT,
.rates[FD_YAW] = SETTING_YAW_RATE_DEFAULT,
},

.manual = {
.rcExpo8 = 70,
.rcYawExpo8 = 20,
.rates[FD_ROLL] = 100,
.rates[FD_PITCH] = 100,
.rates[FD_YAW] = 100
.rcExpo8 = SETTING_MANUAL_RC_EXPO_DEFAULT,
.rcYawExpo8 = SETTING_MANUAL_RC_YAW_EXPO_DEFAULT,
.rates[FD_ROLL] = SETTING_MANUAL_ROLL_RATE_DEFAULT,
.rates[FD_PITCH] = SETTING_MANUAL_PITCH_RATE_DEFAULT,
.rates[FD_YAW] = SETTING_MANUAL_YAW_RATE_DEFAULT
},

.misc = {
.fpvCamAngleDegrees = 0
.fpvCamAngleDegrees = SETTING_FPV_MIX_DEGREES_DEFAULT
}
);
}
Expand Down
2 changes: 0 additions & 2 deletions src/main/fc/controlrate_profile.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,8 @@ and so on.
*/
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 180
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN 6
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_YAW_RATE_MAX 180
#define CONTROL_RATE_CONFIG_YAW_RATE_MIN 2
#define CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT 20

#define CONTROL_RATE_CONFIG_TPA_MAX 100

Expand Down
8 changes: 8 additions & 0 deletions src/main/fc/fc_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -391,7 +391,11 @@ void disarm(disarmReason_t disarmReason)

statsOnDisarm();
logicConditionReset();

#ifdef USE_PROGRAMMING_FRAMEWORK
programmingPidReset();
#endif

beeper(BEEPER_DISARMING); // emit disarm tone
}
}
Expand Down Expand Up @@ -482,7 +486,11 @@ void tryArm(void)
//It is required to inform the mixer that arming was executed and it has to switch to the FORWARD direction
ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD);
logicConditionReset();

#ifdef USE_PROGRAMMING_FRAMEWORK
programmingPidReset();
#endif

headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);

resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
Expand Down
4 changes: 4 additions & 0 deletions src/main/fc/fc_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -219,8 +219,12 @@ void init(void)
ensureEEPROMContainsValidData();
readEEPROM();

#ifdef USE_UNDERCLOCK
// Re-initialize system clock to their final values (if necessary)
systemClockSetup(systemConfig()->cpuUnderclock);
#else
systemClockSetup(false);
#endif

#ifdef USE_I2C
i2cSetSpeed(systemConfig()->i2c_speed);
Expand Down

0 comments on commit 5087026

Please sign in to comment.