1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 05:45:31 +03:00

Second dterm pt1 (#5458)

* Second PT1 on DTerm

This PR replaces the default biquad filter with a second PT1 set to
200Hz.

Basically allows the user to enable a second, set point configurable,
PT1 type first order low-pass filter on DTerm.

This is useful because most noise in most logs arises from D, not P.

The default is set to on, at twice the normal Dterm setpoint.  This
provides greater Dterm cut than a single PT1, and twice the steepness
of cut above the second setpoint.  Modelling shows significant
reductions in higher frequency Dterm noise with only minor additional
delay.

The improvement in noise performance will be less than for biquad, but
the delay is considerably less.

If with the default settings the overall noise improves a lot, it may
be possible bring D both filtering set points to higher numbers (e.g.
140/280), or alternatively remove other filters such as the notch
filters, while maintaining an adequate level of control over noise.

* Update names, old defaults, fix whitespace

Defaults restored to biquad with second PT1 off.  ‘lpf’ retained as
abbreviation for values, otherwise generally remove ‘Filter’ where
redundant, replace ‘FilterLpf’ with ‘Lowpass’, etc, thanks Fujin and
DieHertz

* Remove underscore in lowpass_2, add hz to setpoint for lowpass

Thanks DieHertz

* completed replacing lpf with lowpass, added _hz to all lowpass set points in profile

Thanks DieHertz

* fix whitespace

fixed whitespace in settings.c

* whitespace attempt #57

* change lpf to lowpass where appropriate elsewhere

Note did not change OSD abbreviations, they are still LPF, and did not
change gyro_lpf anywhere.

* second attempt at a simple PT1 implementation

Basically copied from the DtermNotch implementation

* Second PT1 on DTerm

This PR replaces the default biquad filter with a second PT1 set to
200Hz.

Basically allows the user to enable a second, set point configurable,
PT1 type first order low-pass filter on DTerm.

This is useful because most noise in most logs arises from D, not P.

The default is set to on, at twice the normal Dterm setpoint.  This
provides greater Dterm cut than a single PT1, and twice the steepness
of cut above the second setpoint.  Modelling shows significant
reductions in higher frequency Dterm noise with only minor additional
delay.

The improvement in noise performance will be less than for biquad, but
the delay is considerably less.

If with the default settings the overall noise improves a lot, it may
be possible bring D both filtering set points to higher numbers (e.g.
140/280), or alternatively remove other filters such as the notch
filters, while maintaining an adequate level of control over noise.

* Rebase

* Remove underscore in lowpass_2, add hz to setpoint for lowpass

Thanks DieHertz

* completed replacing lpf with lowpass, added _hz to all lowpass set points in profile

Thanks DieHertz

* fix whitespace

fixed whitespace in settings.c

* whitespace attempt #57

* change lpf to lowpass where appropriate elsewhere

Note did not change OSD abbreviations, they are still LPF, and did not
change gyro_lpf anywhere.

* second attempt at a simple PT1 implementation

Basically copied from the DtermNotch implementation

* Whitespace fix - thanks, Ledvinap

* Fix PG issue

by moving added dterm_lowpass2_hz to bottom of struct

* Got rid of redundant indirection

* Fixed indentantion shifts
This commit is contained in:
ctzsnooze 2018-03-20 23:40:23 +11:00 committed by Michael Keller
parent d2bc4e5af5
commit ab231b7c84
6 changed files with 70 additions and 62 deletions

View file

@ -1268,8 +1268,8 @@ static bool blackboxWriteSysinfo(void)
currentPidProfile->pid[PID_VEL].I, currentPidProfile->pid[PID_VEL].I,
currentPidProfile->pid[PID_VEL].D); currentPidProfile->pid[PID_VEL].D);
BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type", "%d", currentPidProfile->dterm_filter_type); BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type", "%d", currentPidProfile->dterm_filter_type);
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_hz", "%d", currentPidProfile->dterm_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lowpass_hz", "%d", currentPidProfile->dterm_lowpass_hz);
BLACKBOX_PRINT_HEADER_LINE("yaw_lpf_hz", "%d", currentPidProfile->yaw_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("yaw_lowpass_hz", "%d", currentPidProfile->yaw_lowpass_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", currentPidProfile->dterm_notch_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", currentPidProfile->dterm_notch_hz);
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", currentPidProfile->dterm_notch_cutoff); BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", currentPidProfile->dterm_notch_cutoff);
BLACKBOX_PRINT_HEADER_LINE("iterm_windup", "%d", currentPidProfile->itermWindupPointPercent); BLACKBOX_PRINT_HEADER_LINE("iterm_windup", "%d", currentPidProfile->itermWindupPointPercent);

View file

@ -358,18 +358,18 @@ static CMS_Menu cmsx_menuFilterGlobal = {
.entries = cmsx_menuFilterGlobalEntries, .entries = cmsx_menuFilterGlobalEntries,
}; };
static uint16_t cmsx_dterm_lpf_hz; static uint16_t cmsx_dterm_lowpass_hz;
static uint16_t cmsx_dterm_notch_hz; static uint16_t cmsx_dterm_notch_hz;
static uint16_t cmsx_dterm_notch_cutoff; static uint16_t cmsx_dterm_notch_cutoff;
static uint16_t cmsx_yaw_lpf_hz; static uint16_t cmsx_yaw_lowpass_hz;
static long cmsx_FilterPerProfileRead(void) static long cmsx_FilterPerProfileRead(void)
{ {
const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex); const pidProfile_t *pidProfile = pidProfiles(pidProfileIndex);
cmsx_dterm_lpf_hz = pidProfile->dterm_lpf_hz; cmsx_dterm_lowpass_hz = pidProfile->dterm_lowpass_hz;
cmsx_dterm_notch_hz = pidProfile->dterm_notch_hz; cmsx_dterm_notch_hz = pidProfile->dterm_notch_hz;
cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff; cmsx_dterm_notch_cutoff = pidProfile->dterm_notch_cutoff;
cmsx_yaw_lpf_hz = pidProfile->yaw_lpf_hz; cmsx_yaw_lowpass_hz = pidProfile->yaw_lowpass_hz;
return 0; return 0;
} }
@ -379,10 +379,10 @@ static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
UNUSED(self); UNUSED(self);
pidProfile_t *pidProfile = currentPidProfile; pidProfile_t *pidProfile = currentPidProfile;
pidProfile->dterm_lpf_hz = cmsx_dterm_lpf_hz; pidProfile->dterm_lowpass_hz = cmsx_dterm_lowpass_hz;
pidProfile->dterm_notch_hz = cmsx_dterm_notch_hz; pidProfile->dterm_notch_hz = cmsx_dterm_notch_hz;
pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff; pidProfile->dterm_notch_cutoff = cmsx_dterm_notch_cutoff;
pidProfile->yaw_lpf_hz = cmsx_yaw_lpf_hz; pidProfile->yaw_lowpass_hz = cmsx_yaw_lowpass_hz;
return 0; return 0;
} }
@ -391,10 +391,10 @@ static OSD_Entry cmsx_menuFilterPerProfileEntries[] =
{ {
{ "-- FILTER PP --", OME_Label, NULL, NULL, 0 }, { "-- FILTER PP --", OME_Label, NULL, NULL, 0 },
{ "DTERM LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf_hz, 0, 500, 1 }, 0 }, { "DTERM LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lowpass_hz, 0, 500, 1 }, 0 },
{ "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, 500, 1 }, 0 }, { "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, 500, 1 }, 0 },
{ "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, 500, 1 }, 0 }, { "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, 500, 1 }, 0 },
{ "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lpf_hz, 0, 500, 1 }, 0 }, { "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lowpass_hz, 0, 500, 1 }, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 }, { "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 } { NULL, OME_END, NULL, NULL, 0 }

View file

@ -103,8 +103,9 @@ void resetPidProfile(pidProfile_t *pidProfile)
.pidSumLimit = PIDSUM_LIMIT, .pidSumLimit = PIDSUM_LIMIT,
.pidSumLimitYaw = PIDSUM_LIMIT_YAW, .pidSumLimitYaw = PIDSUM_LIMIT_YAW,
.yaw_lpf_hz = 0, .yaw_lowpass_hz = 0,
.dterm_lpf_hz = 100, // filtering ON by default .dterm_lowpass_hz = 100, // filtering ON by default
.dterm_lowpass2_hz = 0, // second Dterm LPF OFF by default
.dterm_notch_hz = 260, .dterm_notch_hz = 260,
.dterm_notch_cutoff = 160, .dterm_notch_cutoff = 160,
.dterm_filter_type = FILTER_BIQUAD, .dterm_filter_type = FILTER_BIQUAD,
@ -167,20 +168,22 @@ void pidStabilisationState(pidStabilisationState_e pidControllerState)
const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH }; const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
static FAST_RAM filterApplyFnPtr dtermNotchFilterApplyFn; typedef union dtermLowpass_u {
static FAST_RAM void *dtermFilterNotch[2]; pt1Filter_t pt1Filter;
static FAST_RAM filterApplyFnPtr dtermLpfApplyFn; biquadFilter_t biquadFilter;
static FAST_RAM void *dtermFilterLpf[2];
static FAST_RAM filterApplyFnPtr ptermYawFilterApplyFn;
static FAST_RAM void *ptermYawFilter;
typedef union dtermFilterLpf_u {
pt1Filter_t pt1Filter[2];
biquadFilter_t biquadFilter[2];
#if defined(USE_FIR_FILTER_DENOISE) #if defined(USE_FIR_FILTER_DENOISE)
firFilterDenoise_t denoisingFilter[2]; firFilterDenoise_t denoisingFilter;
#endif #endif
} dtermFilterLpf_t; } dtermLowpass_t;
static FAST_RAM filterApplyFnPtr dtermNotchApplyFn;
static FAST_RAM biquadFilter_t dtermNotch[2];
static FAST_RAM filterApplyFnPtr dtermLowpassApplyFn;
static FAST_RAM dtermLowpass_t dtermLowpass[2];
static FAST_RAM filterApplyFnPtr dtermLowpass2ApplyFn;
static FAST_RAM pt1Filter_t dtermLowpass2[2];
static FAST_RAM filterApplyFnPtr ptermYawLowpassApplyFn;
static FAST_RAM pt1Filter_t ptermYawLowpass;
void pidInitFilters(const pidProfile_t *pidProfile) void pidInitFilters(const pidProfile_t *pidProfile)
{ {
@ -188,9 +191,9 @@ void pidInitFilters(const pidProfile_t *pidProfile)
if (targetPidLooptime == 0) { if (targetPidLooptime == 0) {
// no looptime set, so set all the filters to null // no looptime set, so set all the filters to null
dtermNotchFilterApplyFn = nullFilterApply; dtermNotchApplyFn = nullFilterApply;
dtermLpfApplyFn = nullFilterApply; dtermLowpassApplyFn = nullFilterApply;
ptermYawFilterApplyFn = nullFilterApply; ptermYawLowpassApplyFn = nullFilterApply;
return; return;
} }
@ -208,58 +211,60 @@ void pidInitFilters(const pidProfile_t *pidProfile)
} }
if (dTermNotchHz != 0 && pidProfile->dterm_notch_cutoff != 0) { if (dTermNotchHz != 0 && pidProfile->dterm_notch_cutoff != 0) {
static biquadFilter_t biquadFilterNotch[2]; dtermNotchApplyFn = (filterApplyFnPtr)biquadFilterApply;
dtermNotchFilterApplyFn = (filterApplyFnPtr)biquadFilterApply;
const float notchQ = filterGetNotchQ(dTermNotchHz, pidProfile->dterm_notch_cutoff); const float notchQ = filterGetNotchQ(dTermNotchHz, pidProfile->dterm_notch_cutoff);
for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) { for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) {
dtermFilterNotch[axis] = &biquadFilterNotch[axis]; biquadFilterInit(&dtermNotch[axis], dTermNotchHz, targetPidLooptime, notchQ, FILTER_NOTCH);
biquadFilterInit(dtermFilterNotch[axis], dTermNotchHz, targetPidLooptime, notchQ, FILTER_NOTCH);
} }
} else { } else {
dtermNotchFilterApplyFn = nullFilterApply; dtermNotchApplyFn = nullFilterApply;
} }
static dtermFilterLpf_t dtermFilterLpfUnion; //2nd Dterm Lowpass Filter
if (pidProfile->dterm_lpf_hz == 0 || pidProfile->dterm_lpf_hz > pidFrequencyNyquist) { if (pidProfile->dterm_lowpass2_hz == 0 || pidProfile->dterm_lowpass2_hz > pidFrequencyNyquist) {
dtermLpfApplyFn = nullFilterApply; dtermLowpass2ApplyFn = nullFilterApply;
} else {
dtermLowpass2ApplyFn = (filterApplyFnPtr)pt1FilterApply;
for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) {
pt1FilterInit(&dtermLowpass2[axis], pidProfile->dterm_lowpass2_hz, dT);
}
}
if (pidProfile->dterm_lowpass_hz == 0 || pidProfile->dterm_lowpass_hz > pidFrequencyNyquist) {
dtermLowpassApplyFn = nullFilterApply;
} else { } else {
switch (pidProfile->dterm_filter_type) { switch (pidProfile->dterm_filter_type) {
default: default:
dtermLpfApplyFn = nullFilterApply; dtermLowpassApplyFn = nullFilterApply;
break; break;
case FILTER_PT1: case FILTER_PT1:
dtermLpfApplyFn = (filterApplyFnPtr)pt1FilterApply; dtermLowpassApplyFn = (filterApplyFnPtr)pt1FilterApply;
for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) { for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) {
dtermFilterLpf[axis] = &dtermFilterLpfUnion.pt1Filter[axis]; pt1FilterInit(&dtermLowpass[axis].pt1Filter, pidProfile->dterm_lowpass_hz, dT);
pt1FilterInit(dtermFilterLpf[axis], pidProfile->dterm_lpf_hz, dT);
} }
break; break;
case FILTER_BIQUAD: case FILTER_BIQUAD:
dtermLpfApplyFn = (filterApplyFnPtr)biquadFilterApply; dtermLowpassApplyFn = (filterApplyFnPtr)biquadFilterApply;
for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) { for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) {
dtermFilterLpf[axis] = &dtermFilterLpfUnion.biquadFilter[axis]; biquadFilterInitLPF(&dtermLowpass[axis].biquadFilter, pidProfile->dterm_lowpass_hz, targetPidLooptime);
biquadFilterInitLPF(dtermFilterLpf[axis], pidProfile->dterm_lpf_hz, targetPidLooptime);
} }
break; break;
#if defined(USE_FIR_FILTER_DENOISE) #if defined(USE_FIR_FILTER_DENOISE)
case FILTER_FIR: case FILTER_FIR:
dtermLpfApplyFn = (filterApplyFnPtr)firFilterDenoiseUpdate; dtermLowpassApplyFn = (filterApplyFnPtr)firFilterDenoiseUpdate;
for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) { for (int axis = FD_ROLL; axis <= FD_PITCH; axis++) {
dtermFilterLpf[axis] = &dtermFilterLpfUnion.denoisingFilter[axis]; firFilterDenoiseInit(&dtermLowpass[axis].denoisingFilter, pidProfile->dterm_lowpass_hz, targetPidLooptime);
firFilterDenoiseInit(dtermFilterLpf[axis], pidProfile->dterm_lpf_hz, targetPidLooptime);
} }
break; break;
#endif #endif
} }
} }
static pt1Filter_t pt1FilterYaw; if (pidProfile->yaw_lowpass_hz == 0 || pidProfile->yaw_lowpass_hz > pidFrequencyNyquist) {
if (pidProfile->yaw_lpf_hz == 0 || pidProfile->yaw_lpf_hz > pidFrequencyNyquist) { ptermYawLowpassApplyFn = nullFilterApply;
ptermYawFilterApplyFn = nullFilterApply;
} else { } else {
ptermYawFilterApplyFn = (filterApplyFnPtr)pt1FilterApply; ptermYawLowpassApplyFn = (filterApplyFnPtr)pt1FilterApply;
ptermYawFilter = &pt1FilterYaw; pt1FilterInit(&ptermYawLowpass, pidProfile->yaw_lowpass_hz, dT);
pt1FilterInit(ptermYawFilter, pidProfile->yaw_lpf_hz, dT);
} }
} }
@ -498,7 +503,7 @@ void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *an
// -----calculate P component and add Dynamic Part based on stick input // -----calculate P component and add Dynamic Part based on stick input
axisPID_P[axis] = Kp[axis] * errorRate * tpaFactor; axisPID_P[axis] = Kp[axis] * errorRate * tpaFactor;
if (axis == FD_YAW) { if (axis == FD_YAW) {
axisPID_P[axis] = ptermYawFilterApplyFn(ptermYawFilter, axisPID_P[axis]); axisPID_P[axis] = ptermYawLowpassApplyFn((filter_t *) &ptermYawLowpass, axisPID_P[axis]);
} }
// -----calculate I component // -----calculate I component
@ -513,8 +518,9 @@ void pidController(const pidProfile_t *pidProfile, const rollAndPitchTrims_t *an
// -----calculate D component // -----calculate D component
if (axis != FD_YAW) { if (axis != FD_YAW) {
// apply filters // apply filters
float gyroRateFiltered = dtermNotchFilterApplyFn(dtermFilterNotch[axis], gyroRate); float gyroRateFiltered = dtermNotchApplyFn((filter_t *) &dtermNotch[axis], gyroRate);
gyroRateFiltered = dtermLpfApplyFn(dtermFilterLpf[axis], gyroRateFiltered); gyroRateFiltered = dtermLowpassApplyFn((filter_t *) &dtermLowpass[axis], gyroRateFiltered);
gyroRateFiltered = dtermLowpass2ApplyFn((filter_t *) &dtermLowpass2[axis], gyroRateFiltered);
const float rD = dynCd * MIN(getRcDeflectionAbs(axis) * relaxFactor, 1.0f) * currentPidSetpoint - gyroRateFiltered; // cr - y const float rD = dynCd * MIN(getRcDeflectionAbs(axis) * relaxFactor, 1.0f) * currentPidSetpoint - gyroRateFiltered; // cr - y
// Divide rate change by deltaT to get differential (ie dr/dt) // Divide rate change by deltaT to get differential (ie dr/dt)

View file

@ -73,8 +73,8 @@ typedef struct pid8_s {
typedef struct pidProfile_s { typedef struct pidProfile_s {
pid8_t pid[PID_ITEM_COUNT]; pid8_t pid[PID_ITEM_COUNT];
uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy uint16_t yaw_lowpass_hz; // Additional yaw filter when yaw axis too noisy
uint16_t dterm_lpf_hz; // Delta Filter in hz uint16_t dterm_lowpass_hz; // Delta Filter in hz
uint16_t dterm_notch_hz; // Biquad dterm notch hz uint16_t dterm_notch_hz; // Biquad dterm notch hz
uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff
uint8_t dterm_filter_type; // Filter selection for dterm uint8_t dterm_filter_type; // Filter selection for dterm
@ -105,6 +105,7 @@ typedef struct pidProfile_s {
pidCrashRecovery_e crash_recovery; // off, on, on and beeps when it is in crash recovery mode pidCrashRecovery_e crash_recovery; // off, on, on and beeps when it is in crash recovery mode
uint16_t crash_limit_yaw; // limits yaw errorRate, so crashes don't cause huge throttle increase uint16_t crash_limit_yaw; // limits yaw errorRate, so crashes don't cause huge throttle increase
uint16_t itermLimit; uint16_t itermLimit;
uint16_t dterm_lowpass2_hz; // Extra PT1 Filter on D in hz
} pidProfile_t; } pidProfile_t;
#ifndef USE_OSD_SLAVE #ifndef USE_OSD_SLAVE

View file

@ -1186,8 +1186,8 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
case MSP_FILTER_CONFIG : case MSP_FILTER_CONFIG :
sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz); sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz);
sbufWriteU16(dst, currentPidProfile->dterm_lpf_hz); sbufWriteU16(dst, currentPidProfile->dterm_lowpass_hz);
sbufWriteU16(dst, currentPidProfile->yaw_lpf_hz); sbufWriteU16(dst, currentPidProfile->yaw_lowpass_hz);
sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1); sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1);
sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1); sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1);
sbufWriteU16(dst, currentPidProfile->dterm_notch_hz); sbufWriteU16(dst, currentPidProfile->dterm_notch_hz);
@ -1658,8 +1658,8 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_FILTER_CONFIG: case MSP_SET_FILTER_CONFIG:
gyroConfigMutable()->gyro_soft_lpf_hz = sbufReadU8(src); gyroConfigMutable()->gyro_soft_lpf_hz = sbufReadU8(src);
currentPidProfile->dterm_lpf_hz = sbufReadU16(src); currentPidProfile->dterm_lowpass_hz = sbufReadU16(src);
currentPidProfile->yaw_lpf_hz = sbufReadU16(src); currentPidProfile->yaw_lowpass_hz = sbufReadU16(src);
if (sbufBytesRemaining(src) >= 8) { if (sbufBytesRemaining(src) >= 8) {
gyroConfigMutable()->gyro_soft_notch_hz_1 = sbufReadU16(src); gyroConfigMutable()->gyro_soft_notch_hz_1 = sbufReadU16(src);
gyroConfigMutable()->gyro_soft_notch_cutoff_1 = sbufReadU16(src); gyroConfigMutable()->gyro_soft_notch_cutoff_1 = sbufReadU16(src);

View file

@ -652,7 +652,8 @@ const clivalue_t valueTable[] = {
// PG_PID_PROFILE // PG_PID_PROFILE
{ "dterm_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_filter_type) }, { "dterm_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_filter_type) },
{ "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lpf_hz) }, { "dterm_lowpass_hz", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lowpass_hz) },
{ "dterm_lowpass2_hz", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lowpass2_hz) },
{ "dterm_notch_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_hz) }, { "dterm_notch_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_hz) },
{ "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_cutoff) }, { "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_cutoff) },
{ "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, vbatPidCompensation) }, { "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, vbatPidCompensation) },
@ -677,7 +678,7 @@ const clivalue_t valueTable[] = {
{ "iterm_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermLimit) }, { "iterm_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermLimit) },
{ "pidsum_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) }, { "pidsum_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) },
{ "pidsum_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) }, { "pidsum_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) },
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yaw_lpf_hz) }, { "yaw_lowpass_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yaw_lowpass_hz) },
{ "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].P) }, { "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].P) },
{ "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].I) }, { "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, pid[PID_PITCH].I) },