From 429c21b8878a007233341729b2ca148063aa2070 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 6 Mar 2020 10:50:51 +1100 Subject: [PATCH] AC_Autorotation: convert to new get_rpm() API --- libraries/AC_Autorotation/AC_Autorotation.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 7cacb4d633..dcdbcd9477 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -219,10 +219,9 @@ float AC_Autorotation::get_rpm(bool update_counter) //Get RPM value uint8_t instance = _param_rpm_instance; - current_rpm = rpm->get_rpm(instance); //Check RPM sesnor is returning a healthy status - if (current_rpm <= -1) { + if (!rpm->get_rpm(instance, current_rpm) || current_rpm <= -1) { //unhealthy, rpm unreliable _flags.bad_rpm = true; }