From 674bedd867de37dbcd1d468d6a32c51b6aefbb50 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 18 Nov 2015 21:47:07 +0900 Subject: [PATCH] Copter: acro sets alt target to zero for reporting --- ArduCopter/control_acro.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/control_acro.cpp b/ArduCopter/control_acro.cpp index 52a565bdc7..6e6a51cac7 100644 --- a/ArduCopter/control_acro.cpp +++ b/ArduCopter/control_acro.cpp @@ -13,6 +13,9 @@ bool Copter::acro_init(bool ignore_checks) if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (g.rc_3.control_in > get_non_takeoff_throttle())) { return false; } + // set target altitude to zero for reporting + pos_control.set_alt_target(0); + return true; }