From aeecc46f7bbe10d1c9b298c0e39f0e7a76667409 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Wed, 14 Jan 2015 16:23:26 +0900
Subject: [PATCH] AC_PosControl: remove unnecessary set of desired_accel

The desired_accel is set again 11 lines lower so this line did nothing.
---
 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 74b520955..28d8fd56b 100644
--- a/libraries/AC_AttitudeControl/AC_PosControl.cpp
+++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp
@@ -325,7 +325,6 @@ void AC_PosControl::rate_to_accel_z()
         // Reset Filter
         _vel_error.z = 0;
         _vel_error_filter.reset(0);
-        desired_accel = 0;
         _flags.reset_rate_to_accel_z = false;
     } else {
         // calculate rate error and filter with cut off frequency of 2 Hz
-- 
GitLab