From ee830355d2682b0b0c9811f9d9cbf1b88707748b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 22 Sep 2024 14:04:32 +1000 Subject: [PATCH] AC_PrecLand: remove assumption about how precland update method is called this method may not be being called from the scheduler table. Have the callers pass in a true value instead --- libraries/AC_PrecLand/AC_PrecLand.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 35c1d1af70..c97742a855 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -4,7 +4,6 @@ #include "AC_PrecLand.h" #include -#include #include #include "AC_PrecLand_Backend.h" @@ -226,7 +225,7 @@ void AC_PrecLand::init(uint16_t update_rate_hz) _lag.set(constrain_float(_lag, 0.02f, 0.25f)); // must match LAG parameter range at line 124 // calculate inertial buffer size from lag and minimum of main loop rate and update_rate_hz argument - const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag * MIN(update_rate_hz, AP::scheduler().get_loop_rate_hz())), 1); + const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag * update_rate_hz), 1); // instantiate ring buffer to hold inertial history, return on failure so no backends are created _inertial_history = NEW_NOTHROW ObjectArray(inertial_buffer_size);