From 5c68a04c5d098e20682221190beee67b960b7933 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Sat, 13 Aug 2011 04:46:21 +0000 Subject: [PATCH] PID: fixed an uninitialised variable we did not initialise derivative to zero git-svn-id: https://arducopter.googlecode.com/svn/trunk@3082 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/PID/PID.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index fb6cb4c536..69132c8a02 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -18,7 +18,7 @@ PID::get_pid(int32_t error, uint16_t dt, float scaler) // Compute derivative component if time has elapsed if ((fabs(_kd) > 0) && (dt > 0)) { - float derivative; + float derivative = 0; // add in _filter[_filter_index] = (error - _last_error) / delta_time; _filter_index++;