SimpleFOClibrary  2.1
pid.cpp
Go to the documentation of this file.
1 #include "pid.h"
2 
3 PIDController::PIDController(float P, float I, float D, float ramp, float limit)
4  : P(P)
5  , I(I)
6  , D(D)
7  , output_ramp(ramp) // output derivative limit [volts/second]
8  , limit(limit) // output supply limit [volts]
9  , integral_prev(0.0)
10  , error_prev(0.0)
11  , output_prev(0.0)
12 {
14 }
15 
16 // PID controller function
17 float PIDController::operator() (float error){
18  // calculate the time from the last call
19  unsigned long timestamp_now = _micros();
20  float Ts = (timestamp_now - timestamp_prev) * 1e-6;
21  // quick fix for strange cases (micros overflow)
22  if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
23 
24  // u(s) = (P + I/s + Ds)e(s)
25  // Discrete implementations
26  // proportional part
27  // u_p = P *e(k)
28  float proportional = P * error;
29  // Tustin transform of the integral part
30  // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1)
31  float integral = integral_prev + I*Ts*0.5*(error + error_prev);
32  // antiwindup - limit the output
33  integral = _constrain(integral, -limit, limit);
34  // Discrete derivation
35  // u_dk = D(ek - ek_1)/Ts
36  float derivative = D*(error - error_prev)/Ts;
37 
38  // sum all the components
39  float output = proportional + integral + derivative;
40  // antiwindup - limit the output variable
41  output = _constrain(output, -limit, limit);
42 
43  // limit the acceleration by ramping the output
44  float output_rate = (output - output_prev)/Ts;
45  if (output_rate > output_ramp)
46  output = output_prev + output_ramp*Ts;
47  else if (output_rate < -output_ramp)
48  output = output_prev - output_ramp*Ts;
49 
50  // saving for the next pass
51  integral_prev = integral;
52  output_prev = output;
53  error_prev = error;
54  timestamp_prev = timestamp_now;
55  return output;
56 }
57 
PIDController::error_prev
float error_prev
last tracking error value
Definition: pid.h:35
PIDController::I
float I
Integral gain.
Definition: pid.h:28
PIDController::operator()
float operator()(float error)
Definition: pid.cpp:17
_constrain
#define _constrain(amt, low, high)
Definition: foc_utils.h:9
PIDController::timestamp_prev
unsigned long timestamp_prev
Last execution timestamp.
Definition: pid.h:36
PIDController::output_prev
float output_prev
last pid output value
Definition: pid.h:37
PIDController::limit
float limit
Maximum output value.
Definition: pid.h:31
PIDController::PIDController
PIDController(float P, float I, float D, float ramp, float limit)
Definition: pid.cpp:3
PIDController::output_ramp
float output_ramp
Maximum speed of change of the output value.
Definition: pid.h:30
PIDController::P
float P
Proportional gain.
Definition: pid.h:27
pid.h
_micros
unsigned long _micros()
Definition: time_utils.cpp:21
PIDController::D
float D
Derivative gain.
Definition: pid.h:29
PIDController::integral_prev
float integral_prev
last integral component value
Definition: pid.h:34