From 87c684b5eee1f1d803fbaf623863518a9397f54b Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 15 Dec 2022 22:14:14 +1030 Subject: [PATCH] Plane: Vtol: use land_at_climb_rate_cm for vertical rate control --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 64dad68cf0..342c9937cd 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1005,7 +1005,7 @@ void QuadPlane::check_yaw_reset(void) void QuadPlane::set_climb_rate_cms(float target_climb_rate_cms, bool force_descend) { - pos_control->input_vel_accel_z(target_climb_rate_cms, 0, force_descend); + pos_control->land_at_climb_rate_cm(target_climb_rate_cms, force_descend); } /*