aboutsummaryrefslogtreecommitdiff
path: root/src/modules/systemlib/pid
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-09-01 20:17:24 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-09-01 20:17:24 +0200
commite553087d10e7187c12e5e0f28937585a732a46da (patch)
tree2f185a2b173399e91a119b142171fe521a3bd703 /src/modules/systemlib/pid
parent56293c8068381d8c0cb2bf1a19c2924b2e3eca4f (diff)
downloadpx4-firmware-e553087d10e7187c12e5e0f28937585a732a46da.tar.gz
px4-firmware-e553087d10e7187c12e5e0f28937585a732a46da.tar.bz2
px4-firmware-e553087d10e7187c12e5e0f28937585a732a46da.zip
pid.limit != 0 fix
Diffstat (limited to 'src/modules/systemlib/pid')
-rw-r--r--src/modules/systemlib/pid/pid.c6
1 files changed, 4 insertions, 2 deletions
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 562f3ac04..739503ed4 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -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;