From 9ebd0e9960394ebf9230d8e470f11b329e68f8ce Mon Sep 17 00:00:00 2001
From: Jonathan Challinger <mr.challinger@gmail.com>
Date: Mon, 12 Jan 2015 13:58:43 -0800
Subject: [PATCH] AC_PosControl: reincarnate dead block of code

---
 libraries/AC_AttitudeControl/AC_PosControl.cpp | 1 -
 1 file changed, 1 deletion(-)

diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp
index 12f2b6173..74b520955 100644
--- a/libraries/AC_AttitudeControl/AC_PosControl.cpp
+++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp
@@ -303,7 +303,6 @@ void AC_PosControl::rate_to_accel_z()
     // reset last velocity target to current target
     if (_flags.reset_rate_to_accel_z) {
         _vel_last.z = _vel_target.z;
-        _flags.reset_rate_to_accel_z = false;
     }
 
     // feed forward desired acceleration calculation
-- 
GitLab