Skip to content

Commit

Permalink
AC_AttitudeControl: ensure yaw gets a FLTD default
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and rmackay9 committed Feb 23, 2024
1 parent f0616b1 commit 5b2d760
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl {
.imax = AC_ATC_MULTI_RATE_YAW_IMAX,
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_E_hz = AC_ATC_MULTI_RATE_YAW_FILT_HZ,
.filt_D_hz = 0.0f,
.filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.srmax = 0,
.srtau = 1.0
}
Expand Down

0 comments on commit 5b2d760

Please sign in to comment.