pid.limit != 0 fix

This commit is contained in:
Anton Babushkin 2013-09-01 20:17:24 +02:00
parent 56293c8068
commit e553087d10
1 changed files with 4 additions and 2 deletions

View File

@ -51,6 +51,8 @@
#include "pid.h"
#include <math.h>
#define SIGMA 0.000001f
__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax,
float limit, uint8_t mode, float dt_min)
{
@ -168,7 +170,7 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
// Calculate the error integral and check for saturation
i = pid->integral + (error * dt);
if ((pid->limit != 0.0f && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) ||
if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) ||
fabsf(i) > pid->intmax) {
i = pid->integral; // If saturated then do not update integral value
pid->saturated = 1;
@ -186,7 +188,7 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
float output = (error * pid->kp) + (i * pid->ki) + (d * pid->kd);
if (isfinite(output)) {
if (pid->limit != 0.0f) {
if (pid->limit > SIGMA) {
if (output > pid->limit) {
output = pid->limit;