From a2d0f569c95096d81d9710e805fd4882822c51be Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 6 Jun 2021 16:47:24 +1000 Subject: [PATCH] AP_WheelEncoder: fixed PID constructor calls --- libraries/AP_WheelEncoder/AP_WheelRateControl.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.h b/libraries/AP_WheelEncoder/AP_WheelRateControl.h index 93dafd2960..1f72817845 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.h +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.h @@ -58,8 +58,8 @@ private: // parameters AP_Int8 _enabled; // top level enable/disable control AP_Float _rate_max; // wheel maximum rotation rate in rad/s - AC_PID _rate_pid0 = AC_PID(AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT); - AC_PID _rate_pid1 = AC_PID(AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT); + AC_PID _rate_pid0{AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT}; + AC_PID _rate_pid1{AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT}; // limit flags struct AP_MotorsUGV_limit {