From c404eec65cfe2afffbf94439bdb8ee6d490ebd9a Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 31 Aug 2021 13:48:40 +0930 Subject: [PATCH] AC_WPNav: Separate landing and terrain following. --- libraries/AC_WPNav/AC_Circle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 4c1beff7fe..f452924cc2 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -220,7 +220,7 @@ bool AC_Circle::update(float climb_rate_cms) float target_zf = target.z; _pos_control.input_pos_vel_accel_z(target_zf, zero2, 0); } else { - _pos_control.set_pos_target_z_from_climb_rate_cm(climb_rate_cms, false); + _pos_control.set_pos_target_z_from_climb_rate_cm(climb_rate_cms); } // update position controller