mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
92822dbd6b
commit
1dcd7a358e
|
@ -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++;
|
||||
|
|
Loading…
Reference in New Issue