]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/pidcontroller.cxx
Autopilot: add interface properties and property-root.
[flightgear.git] / src / Autopilot / pidcontroller.cxx
1 // pidcontroller.cxx - implementation of PID controller
2 //
3 // Written by Torsten Dreyer
4 // Based heavily on work created by Curtis Olson, started January 2004.
5 //
6 // Copyright (C) 2004  Curtis L. Olson  - http://www.flightgear.org/~curt
7 // Copyright (C) 2010  Torsten Dreyer - Torsten (at) t3r (dot) de
8 //
9 // This program is free software; you can redistribute it and/or
10 // modify it under the terms of the GNU General Public License as
11 // published by the Free Software Foundation; either version 2 of the
12 // License, or (at your option) any later version.
13 //
14 // This program is distributed in the hope that it will be useful, but
15 // WITHOUT ANY WARRANTY; without even the implied warranty of
16 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
17 // General Public License for more details.
18 //
19 // You should have received a copy of the GNU General Public License
20 // along with this program; if not, write to the Free Software
21 // Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.
22 //
23
24 #include "pidcontroller.hxx"
25
26 using namespace FGXMLAutopilot;
27
28 using std::endl;
29 using std::cout;
30
31 PIDController::PIDController():
32     AnalogComponent(),
33     alpha( 0.1 ),
34     beta( 1.0 ),
35     gamma( 0.0 ),
36     ep_n_1( 0.0 ),
37     edf_n_1( 0.0 ),
38     edf_n_2( 0.0 ),
39     u_n_1( 0.0 ),
40     desiredTs( 0.0 ),
41     elapsedTime( 0.0 )
42 {
43 }
44
45 /*
46  * Roy Vegard Ovesen:
47  *
48  * Ok! Here is the PID controller algorithm that I would like to see
49  * implemented:
50  *
51  *   delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
52  *               + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
53  *
54  *   u_n = u_n-1 + delta_u_n
55  *
56  * where:
57  *
58  * delta_u : The incremental output
59  * Kp      : Proportional gain
60  * ep      : Proportional error with reference weighing
61  *           ep = beta * r - y
62  *           where:
63  *           beta : Weighing factor
64  *           r    : Reference (setpoint)
65  *           y    : Process value, measured
66  * e       : Error
67  *           e = r - y
68  * Ts      : Sampling interval
69  * Ti      : Integrator time
70  * Td      : Derivator time
71  * edf     : Derivate error with reference weighing and filtering
72  *           edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
73  *           where:
74  *           Tf : Filter time
75  *           Tf = alpha * Td , where alpha usually is set to 0.1
76  *           ed : Unfiltered derivate error with reference weighing
77  *             ed = gamma * r - y
78  *             where:
79  *             gamma : Weighing factor
80  * 
81  * u       : absolute output
82  * 
83  * Index n means the n'th value.
84  * 
85  * 
86  * Inputs:
87  * enabled ,
88  * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
89  * Kp , Ti , Td , Ts (is the sampling time available?)
90  * u_min , u_max
91  * 
92  * Output:
93  * u_n
94  */
95
96 void PIDController::update( bool firstTime, double dt ) 
97 {
98     if( firstTime ) {
99       ep_n_1 = 0.0;
100       edf_n_2 = edf_n_1 = 0.0;
101
102       // first time being enabled, seed with current property tree value
103       u_n_1 = get_output_value();
104     }
105
106     double u_min = _minInput.get_value();
107     double u_max = _maxInput.get_value();
108
109     elapsedTime += dt;
110     if( elapsedTime <= desiredTs ) {
111         // do nothing if time step is not positive (i.e. no time has
112         // elapsed)
113         return;
114     }
115     double Ts = elapsedTime; // sampling interval (sec)
116     elapsedTime = 0.0;
117
118     if( Ts > SGLimitsd::min()) {
119         if( _debug ) cout <<  "Updating " << get_name()
120                           << " Ts " << Ts << endl;
121
122         double y_n = _valueInput.get_value();
123         double r_n = _referenceInput.get_value();
124                       
125         if ( _debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
126
127         // Calculates proportional error:
128         double ep_n = beta * r_n - y_n;
129         if ( _debug ) cout << "  ep_n = " << ep_n;
130         if ( _debug ) cout << "  ep_n_1 = " << ep_n_1;
131
132         // Calculates error:
133         double e_n = r_n - y_n;
134         if ( _debug ) cout << " e_n = " << e_n;
135
136         double edf_n = 0.0;
137         double td = Td.get_value();
138         if ( td > 0.0 ) { // do we need to calcluate derivative error?
139
140           // Calculates derivate error:
141             double ed_n = gamma * r_n - y_n;
142             if ( _debug ) cout << " ed_n = " << ed_n;
143
144             // Calculates filter time:
145             double Tf = alpha * td;
146             if ( _debug ) cout << " Tf = " << Tf;
147
148             // Filters the derivate error:
149             edf_n = edf_n_1 / (Ts/Tf + 1)
150                 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
151             if ( _debug ) cout << " edf_n = " << edf_n;
152         } else {
153             edf_n_2 = edf_n_1 = edf_n = 0.0;
154         }
155
156         // Calculates the incremental output:
157         double ti = Ti.get_value();
158         double delta_u_n = 0.0; // incremental output
159         if ( ti > 0.0 ) {
160             delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
161                                + ((Ts/ti) * e_n)
162                                + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
163
164           if ( _debug ) {
165               cout << " delta_u_n = " << delta_u_n << endl;
166               cout << "P:" << Kp.get_value() * (ep_n - ep_n_1)
167                    << " I:" << Kp.get_value() * ((Ts/ti) * e_n)
168                    << " D:" << Kp.get_value() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
169                    << endl;
170         }
171         }
172
173         // Integrator anti-windup logic:
174         if ( delta_u_n > (u_max - u_n_1) ) {
175             delta_u_n = u_max - u_n_1;
176             if ( _debug ) cout << " max saturation " << endl;
177         } else if ( delta_u_n < (u_min - u_n_1) ) {
178             delta_u_n = u_min - u_n_1;
179             if ( _debug ) cout << " min saturation " << endl;
180         }
181
182         // Calculates absolute output:
183         double u_n = u_n_1 + delta_u_n;
184         if ( _debug ) cout << "  output = " << u_n << endl;
185
186         // Updates indexed values;
187         u_n_1   = u_n;
188         ep_n_1  = ep_n;
189         edf_n_2 = edf_n_1;
190         edf_n_1 = edf_n;
191
192         set_output_value( u_n );
193     }
194 }
195
196 //------------------------------------------------------------------------------
197 bool PIDController::configure( SGPropertyNode& cfg_node,
198                                const std::string& cfg_name,
199                                SGPropertyNode& prop_root )
200 {
201   SG_LOG(SG_AUTOPILOT, SG_BULK, "PIDController::configure(" << cfg_name << ")");
202
203   if( AnalogComponent::configure(cfg_node, cfg_name, prop_root) )
204     return true;
205
206   if( cfg_name == "config" ) {
207     Component::configure(prop_root, cfg_node);
208     return true;
209   }
210
211   if (cfg_name == "Ts") {
212     desiredTs = cfg_node.getDoubleValue();
213     return true;
214   } 
215
216   if (cfg_name == "Kp") {
217     Kp.push_back( new InputValue(prop_root, cfg_node) );
218     return true;
219   } 
220
221   if (cfg_name == "Ti") {
222     Ti.push_back( new InputValue(prop_root, cfg_node) );
223     return true;
224   } 
225
226   if (cfg_name == "Td") {
227     Td.push_back( new InputValue(prop_root, cfg_node) );
228     return true;
229   } 
230
231   if (cfg_name == "beta") {
232     beta = cfg_node.getDoubleValue();
233     return true;
234   } 
235
236   if (cfg_name == "alpha") {
237     alpha = cfg_node.getDoubleValue();
238     return true;
239   } 
240
241   if (cfg_name == "gamma") {
242     gamma = cfg_node.getDoubleValue();
243     return true;
244   } 
245
246   SG_LOG
247   (
248     SG_AUTOPILOT,
249     SG_BULK,
250     "PIDController::configure(" << cfg_name << ") [unhandled]"
251   );
252   return false;
253 }
254