SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
pid.cpp
Go to the documentation of this file.
1#include "pid.h"
2
3PIDController::PIDController(float P, float I, float D, float ramp, float limit, float sampling_time)
4 : P(P)
5 , I(I)
6 , D(D)
7 , output_ramp(ramp) // output derivative limit [ex. volts/second]
8 , limit(limit) // output supply limit [ex. volts]
9 , Ts(sampling_time) // sampling time [S]
10 , error_prev(0.0f)
11 , output_prev(0.0f)
12 , integral_prev(0.0f)
13{
15}
16
17// PID controller function
18float PIDController::operator() (float error){
19 // initalise the elapsed time with the fixed sampling tims Ts
20 float dt = Ts;
21 // if Ts is not set, use adaptive sampling time
22 // calculate the ellapsed time dt
23 if(!_isset(dt)){
24 unsigned long timestamp_now = _micros();
25 dt = (timestamp_now - timestamp_prev) * 1e-6f;
26 // quick fix for strange cases (micros overflow)
27 if(dt <= 0 || dt > 0.5f) dt = 1e-3f;
29 }
30
31 // u(s) = (P + I/s + Ds)e(s)
32 // Discrete implementations
33 // proportional part
34 // u_p = P *e(k)
35 float proportional = P * error;
36 // Tustin transform of the integral part
37 // u_ik = u_ik_1 + I*Ts/2*(ek + ek_1)
38 float integral = integral_prev + I*dt*0.5f*(error + error_prev);
39 // antiwindup - limit the output
41 // Discrete derivation
42 // u_dk = D(ek - ek_1)/Ts
43 float derivative = D*(error - error_prev)/dt;
44
45 // sum all the components
47 // antiwindup - limit the output variable
49
50 // if output ramp defined
51 if(_isset(output_ramp) && output_ramp > 0){
52 // limit the acceleration by ramping the output
53 float output_rate = (output - output_prev)/dt;
56 else if (output_rate < -output_ramp)
58 }
59 // saving for the next pass
63 return output;
64}
65
67 integral_prev = 0.0f;
68 output_prev = 0.0f;
69 error_prev = 0.0f;
70}
float operator()(float error)
Definition pid.cpp:18
PIDController(float P, float I, float D, float ramp=NOT_SET, float limit=NOT_SET, float sampling_time=NOT_SET)
Definition pid.cpp:3
float output_prev
last pid output value
Definition pid.h:43
unsigned long timestamp_prev
Last execution timestamp.
Definition pid.h:45
float output_ramp
Maximum speed of change of the output value.
Definition pid.h:37
float limit
Maximum output value.
Definition pid.h:38
float error_prev
last tracking error value
Definition pid.h:42
float D
Derivative gain.
Definition pid.h:36
float integral_prev
last integral component value
Definition pid.h:44
float Ts
Fixed sampling time (optional default NOT_SET)
Definition pid.h:39
float P
Proportional gain.
Definition pid.h:34
void reset()
Definition pid.cpp:66
float I
Integral gain.
Definition pid.h:35
#define _isset(a)
Definition foc_utils.h:13
#define _constrain(amt, low, high)
Definition foc_utils.h:11
unsigned long _micros()