From 22aa09d125ffaeaa784f3ff789827b01babe32d3 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 04:08:55 +0100 Subject: [PATCH] AC_PrecLand: params always use set method --- libraries/AC_PrecLand/AC_PrecLand.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index a60389909f..e51369f9ff 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -203,7 +203,7 @@ void AC_PrecLand::init(uint16_t update_rate_hz) // create inertial history buffer // constrain lag parameter to be within bounds - _lag = constrain_float(_lag, 0.02f, 0.25f); + _lag.set(constrain_float(_lag, 0.02f, 0.25f)); // 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);