From e3ab7ed234133bb31e81b2487fed6b3630a21438 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 04:08:55 +0100 Subject: [PATCH] AC_Autorotation: params always use set method --- libraries/AC_Autorotation/AC_Autorotation.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 0018a06be7..d6c7c8ea3c 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -143,7 +143,7 @@ void AC_Autorotation::init_hs_controller() _healthy_rpm_counter = 0; // Protect against divide by zero - _param_head_speed_set_point = MAX(_param_head_speed_set_point,500); + _param_head_speed_set_point.set(MAX(_param_head_speed_set_point,500)); } @@ -213,7 +213,7 @@ float AC_Autorotation::get_rpm(bool update_counter) if (rpm != nullptr) { //Check requested rpm instance to ensure either 0 or 1. Always defaults to 0. if ((_param_rpm_instance > 1) || (_param_rpm_instance < 0)) { - _param_rpm_instance = 0; + _param_rpm_instance.set(0); } //Get RPM value