From d423f483a6f971bc1ec88d7cc9bb22ca6a9b0e4c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 04:08:56 +0100 Subject: [PATCH] AP_AHRS: params always use set method --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 6f447fba80..1c006c0795 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -587,7 +587,7 @@ AP_AHRS_DCM::drift_correction_yaw(void) // sanity check _kp_yaw if (_kp_yaw < AP_AHRS_YAW_P_MIN) { - _kp_yaw = AP_AHRS_YAW_P_MIN; + _kp_yaw.set(AP_AHRS_YAW_P_MIN); } // update the proportional control to drag the @@ -927,7 +927,7 @@ AP_AHRS_DCM::drift_correction(float deltat) // sanity check _kp value if (_kp < AP_AHRS_RP_P_MIN) { - _kp = AP_AHRS_RP_P_MIN; + _kp.set(AP_AHRS_RP_P_MIN); } // we now want to calculate _omega_P and _omega_I. The