From 6209f31d309734cb3b17b40d528fde662327e348 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 20 Sep 2024 22:20:42 +1000 Subject: [PATCH] AC_PID: re-order initialiser lines so -Werror=reorder will work --- libraries/AC_PID/AC_PID.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 132523d759..eb06c4301e 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -106,12 +106,12 @@ AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ default_ki(initial_i), default_kd(initial_d), default_kff(initial_ff), + default_kdff(initial_dff), default_kimax(initial_imax), default_filt_T_hz(initial_filt_T_hz), default_filt_E_hz(initial_filt_E_hz), default_filt_D_hz(initial_filt_D_hz), - default_slew_rate_max(initial_srmax), - default_kdff(initial_dff) + default_slew_rate_max(initial_srmax) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info);