From 42887891be58686cd7be422d45a5f76da15bae26 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 16 Nov 2020 17:37:46 +0000 Subject: [PATCH] Plane: tailsitter: make sure alt target is abover current alt --- ArduPlane/quadplane.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index b8e144684d..4b01aec5e6 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -952,6 +952,10 @@ void QuadPlane::run_z_controller(void) } else { // tailsitters gain lots of vertical speed in transisison, set target to the stopping point pos_control->set_target_to_stopping_point_z(); + // make sure stopping point is above current alt + if (pos_control->get_alt_target() < inertial_nav.get_altitude()) { + set_alt_target_current(); + } } gcs().send_text(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)pos_control->get_alt_target() * 0.01f); pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());