Merge pull request #6036 from ctzsnooze/3.4-defaults
Initial default suggestions for 3.4
This commit is contained in:
commit
fed5696f8d
|
@ -34,7 +34,7 @@ static uint32_t activeFeaturesLatch = 0;
|
|||
PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
|
||||
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE
|
||||
.enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_DYNAMIC_FILTER | FEATURE_ANTI_GRAVITY,
|
||||
);
|
||||
|
||||
void intFeatureSet(uint32_t mask, uint32_t *features)
|
||||
|
|
|
@ -100,9 +100,9 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
|||
{
|
||||
RESET_CONFIG(pidProfile_t, pidProfile,
|
||||
.pid = {
|
||||
[PID_ROLL] = { 40, 40, 30 },
|
||||
[PID_PITCH] = { 58, 50, 35 },
|
||||
[PID_YAW] = { 70, 45, 20 },
|
||||
[PID_ROLL] = { 46, 45, 25 },
|
||||
[PID_PITCH] = { 50, 50, 27 },
|
||||
[PID_YAW] = { 65, 45, 20 },
|
||||
[PID_ALT] = { 50, 0, 0 },
|
||||
[PID_POS] = { 15, 0, 0 }, // POSHOLD_P * 100, POSHOLD_I * 100,
|
||||
[PID_POSR] = { 34, 14, 53 }, // POSHOLD_RATE_P * 10, POSHOLD_RATE_I * 100, POSHOLD_RATE_D * 1000,
|
||||
|
@ -115,21 +115,21 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
|||
.pidSumLimit = PIDSUM_LIMIT,
|
||||
.pidSumLimitYaw = PIDSUM_LIMIT_YAW,
|
||||
.yaw_lowpass_hz = 0,
|
||||
.dterm_lowpass_hz = 100, // filtering ON by default
|
||||
.dterm_lowpass2_hz = 0, // second Dterm LPF OFF by default
|
||||
.dterm_notch_hz = 260,
|
||||
.dterm_lowpass_hz = 100, // dual PT1 filtering ON by default
|
||||
.dterm_lowpass2_hz = 200, // second Dterm LPF ON by default
|
||||
.dterm_notch_hz = 0,
|
||||
.dterm_notch_cutoff = 160,
|
||||
.dterm_filter_type = FILTER_BIQUAD,
|
||||
.itermWindupPointPercent = 50,
|
||||
.dterm_filter_type = FILTER_PT1,
|
||||
.itermWindupPointPercent = 40,
|
||||
.vbatPidCompensation = 0,
|
||||
.pidAtMinThrottle = PID_STABILISATION_ON,
|
||||
.levelAngleLimit = 55,
|
||||
.setpointRelaxRatio = 100,
|
||||
.dtermSetpointWeight = 45,
|
||||
.setpointRelaxRatio = 0,
|
||||
.dtermSetpointWeight = 60,
|
||||
.yawRateAccelLimit = 100,
|
||||
.rateAccelLimit = 0,
|
||||
.itermThrottleThreshold = 350,
|
||||
.itermAcceleratorGain = 1000,
|
||||
.itermAcceleratorGain = 5000,
|
||||
.crash_time = 500, // ms
|
||||
.crash_delay = 0, // ms
|
||||
.crash_recovery_angle = 10, // degrees
|
||||
|
@ -142,9 +142,9 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
|||
.horizon_tilt_expert_mode = false,
|
||||
.crash_limit_yaw = 200,
|
||||
.itermLimit = 150,
|
||||
.throttle_boost = 0,
|
||||
.throttle_boost = 5,
|
||||
.throttle_boost_cutoff = 15,
|
||||
.iterm_rotation = false,
|
||||
.iterm_rotation = true,
|
||||
.smart_feedforward = false,
|
||||
.iterm_relax = ITERM_RELAX_OFF,
|
||||
.iterm_relax_cutoff = 11,
|
||||
|
|
|
@ -56,7 +56,7 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
|||
.rssi_offset = 0,
|
||||
.rssi_invert = 0,
|
||||
.rcInterpolation = RC_SMOOTHING_AUTO,
|
||||
.rcInterpolationChannels = INTERPOLATION_CHANNELS_RP,
|
||||
.rcInterpolationChannels = INTERPOLATION_CHANNELS_RPT,
|
||||
.rcInterpolationInterval = 19,
|
||||
.fpvCamAngleDegrees = 0,
|
||||
.airModeActivateThreshold = 32,
|
||||
|
|
|
@ -183,16 +183,16 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
|
|||
.gyro_hardware_lpf = GYRO_HARDWARE_LPF_NORMAL,
|
||||
.gyro_32khz_hardware_lpf = GYRO_32KHZ_HARDWARE_LPF_NORMAL,
|
||||
.gyro_lowpass_type = FILTER_PT1,
|
||||
.gyro_lowpass_hz = 90,
|
||||
.gyro_lowpass_hz = 100,
|
||||
.gyro_lowpass2_type = FILTER_PT1,
|
||||
.gyro_lowpass2_hz = 0,
|
||||
.gyro_lowpass2_hz = 300,
|
||||
.gyro_high_fsr = false,
|
||||
.gyro_use_32khz = false,
|
||||
.gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT,
|
||||
.gyro_soft_notch_hz_1 = 400,
|
||||
.gyro_soft_notch_cutoff_1 = 300,
|
||||
.gyro_soft_notch_hz_2 = 200,
|
||||
.gyro_soft_notch_cutoff_2 = 100,
|
||||
.gyro_soft_notch_hz_1 = 0,
|
||||
.gyro_soft_notch_cutoff_1 = 0,
|
||||
.gyro_soft_notch_hz_2 = 0,
|
||||
.gyro_soft_notch_cutoff_2 = 0,
|
||||
.checkOverflow = GYRO_OVERFLOW_CHECK_ALL_AXES,
|
||||
.gyro_offset_yaw = 0,
|
||||
.yaw_spin_recovery = true,
|
||||
|
|
Loading…
Reference in New Issue