]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/xmlauto.cxx
ignore resets for now because every z/Z key press would trigger a call to NOAA. We...
[flightgear.git] / src / Autopilot / xmlauto.cxx
1 // xmlauto.cxx - a more flexible, generic way to build autopilots
2 //
3 // Written by Curtis Olson, started January 2004.
4 //
5 // Copyright (C) 2004  Curtis L. Olson  - curt@flightgear.org
6 //
7 // This program is free software; you can redistribute it and/or
8 // modify it under the terms of the GNU General Public License as
9 // published by the Free Software Foundation; either version 2 of the
10 // License, or (at your option) any later version.
11 //
12 // This program is distributed in the hope that it will be useful, but
13 // WITHOUT ANY WARRANTY; without even the implied warranty of
14 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
15 // General Public License for more details.
16 //
17 // You should have received a copy of the GNU General Public License
18 // along with this program; if not, write to the Free Software
19 // Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
20 //
21 // $Id$
22
23
24 #include <simgear/structure/exception.hxx>
25 #include <simgear/misc/sg_path.hxx>
26
27 #include <Main/fg_props.hxx>
28 #include <Main/globals.hxx>
29
30 #include "xmlauto.hxx"
31
32
33 FGPIDController::FGPIDController( SGPropertyNode *node ):
34     debug( false ),
35     y_n( 0.0 ),
36     r_n( 0.0 ),
37     Kp( 0.0 ),
38     alpha( 0.1 ),
39     beta( 1.0 ),
40     gamma( 0.0 ),
41     Ti( 0.0 ),
42     Td( 0.0 ),
43     u_min( 0.0 ),
44     u_max( 0.0 ),
45     ep_n_1( 0.0 ),
46     edf_n_1( 0.0 ),
47     edf_n_2( 0.0 ),
48     u_n_1( 0.0 )
49 {
50     int i;
51     for ( i = 0; i < node->nChildren(); ++i ) {
52         SGPropertyNode *child = node->getChild(i);
53         string cname = child->getName();
54         string cval = child->getStringValue();
55         if ( cname == "name" ) {
56             name = cval;
57         } else if ( cname == "debug" ) {
58             debug = child->getBoolValue();
59         } else if ( cname == "enable" ) {
60             // cout << "parsing enable" << endl;
61             SGPropertyNode *prop = child->getChild( "prop" );
62             if ( prop != NULL ) {
63                 // cout << "prop = " << prop->getStringValue() << endl;
64                 enable_prop = fgGetNode( prop->getStringValue(), true );
65             } else {
66                 // cout << "no prop child" << endl;
67             }
68             SGPropertyNode *val = child->getChild( "value" );
69             if ( val != NULL ) {
70                 enable_value = val->getStringValue();
71             }
72         } else if ( cname == "input" ) {
73             SGPropertyNode *prop = child->getChild( "prop" );
74             if ( prop != NULL ) {
75                 input_prop = fgGetNode( prop->getStringValue(), true );
76             }
77         } else if ( cname == "reference" ) {
78             SGPropertyNode *prop = child->getChild( "prop" );
79             if ( prop != NULL ) {
80                 r_n_prop = fgGetNode( prop->getStringValue(), true );
81             } else {
82                 prop = child->getChild( "value" );
83                 if ( prop != NULL ) {
84                     r_n = prop->getDoubleValue();
85                 }
86             }
87         } else if ( cname == "output" ) {
88             int i = 0;
89             SGPropertyNode *prop;
90             while ( (prop = child->getChild("prop", i)) != NULL ) {
91                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
92                 output_list.push_back( tmp );
93                 i++;
94             }
95         } else if ( cname == "config" ) {
96             SGPropertyNode *prop;
97
98             prop = child->getChild( "Kp" );
99             if ( prop != NULL ) {
100                 Kp = prop->getDoubleValue();
101             }
102
103             prop = child->getChild( "beta" );
104             if ( prop != NULL ) {
105                 beta = prop->getDoubleValue();
106             }
107
108             prop = child->getChild( "alpha" );
109             if ( prop != NULL ) {
110                 alpha = prop->getDoubleValue();
111             }
112
113             prop = child->getChild( "gamma" );
114             if ( prop != NULL ) {
115                 gamma = prop->getDoubleValue();
116             }
117
118             prop = child->getChild( "Ti" );
119             if ( prop != NULL ) {
120                 Ti = prop->getDoubleValue();
121             }
122
123             prop = child->getChild( "Td" );
124             if ( prop != NULL ) {
125                 Td = prop->getDoubleValue();
126             }
127
128             prop = child->getChild( "u_min" );
129             if ( prop != NULL ) {
130                 u_min = prop->getDoubleValue();
131             }
132
133             prop = child->getChild( "u_max" );
134             if ( prop != NULL ) {
135                 u_max = prop->getDoubleValue();
136             }
137         } else {
138             SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
139             if ( name.length() ) {
140                 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
141             }
142         }
143     }   
144 }
145
146
147 /*
148  * Roy Vegard Ovesen:
149  *
150  * Ok! Here is the PID controller algorithm that I would like to see
151  * implemented:
152  *
153  *   delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
154  *               + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
155  *
156  *   u_n = u_n-1 + delta_u_n
157  *
158  * where:
159  *
160  * delta_u : The incremental output
161  * Kp      : Proportional gain
162  * ep      : Proportional error with reference weighing
163  *           ep = beta * r - y
164  *           where:
165  *           beta : Weighing factor
166  *           r    : Reference (setpoint)
167  *           y    : Process value, measured
168  * e       : Error
169  *           e = r - y
170  * Ts      : Sampling interval
171  * Ti      : Integrator time
172  * Td      : Derivator time
173  * edf     : Derivate error with reference weighing and filtering
174  *           edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
175  *           where:
176  *           Tf : Filter time
177  *           Tf = alpha * Td , where alpha usually is set to 0.1
178  *           ed : Unfiltered derivate error with reference weighing
179  *             ed = gamma * r - y
180  *             where:
181  *             gamma : Weighing factor
182  * 
183  * u       : absolute output
184  * 
185  * Index n means the n'th value.
186  * 
187  * 
188  * Inputs:
189  * enabled ,
190  * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
191  * Kp , Ti , Td , Ts (is the sampling time available?)
192  * u_min , u_max
193  * 
194  * Output:
195  * u_n
196  */
197
198 void FGPIDController::update( double dt ) {
199     double ep_n;         // proportional error with reference weighing
200     double e_n;          // error
201     double ed_n;         // derivative error
202     double edf_n;        // derivative error filter
203     double Tf;           // filter time
204     double delta_u_n;    // incremental output
205     double u_n;          // absolute output
206     double Ts = dt;      // Sampling interval (sec)
207
208     if ( Ts <= 0.0 ) {
209         // do nothing if time step is not positive (i.e. no time has
210         // elapsed)
211         return;
212     }
213
214     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
215         if ( !enabled ) {
216             // first time being enabled, seed u_n with current
217             // property tree value
218             u_n = output_list[0]->getDoubleValue();
219             // and clip
220             if ( u_n < u_min ) { u_n = u_min; }
221             if ( u_n > u_max ) { u_n = u_max; }
222             u_n_1 = u_n;
223         }
224         enabled = true;
225     } else {
226         enabled = false;
227     }
228
229     if ( enabled ) {
230         if ( debug ) cout << "Updating " << name << endl;
231
232         double y_n = 0.0;
233         if ( input_prop != NULL ) {
234             y_n = input_prop->getDoubleValue();
235         }
236
237         double r_n = 0.0;
238         if ( r_n_prop != NULL ) {
239             r_n = r_n_prop->getDoubleValue();
240         } else {
241             r_n = r_n_value;
242         }
243                       
244         if ( debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
245
246         // Calculates proportional error:
247         ep_n = beta * r_n - y_n;
248         if ( debug ) cout << "  ep_n = " << ep_n;
249         if ( debug ) cout << "  ep_n_1 = " << ep_n_1;
250
251         // Calculates error:
252         e_n = r_n - y_n;
253         if ( debug ) cout << " e_n = " << e_n;
254
255         // Calculates derivate error:
256         ed_n = gamma * r_n - y_n;
257         if ( debug ) cout << " ed_n = " << ed_n;
258
259         // Calculates filter time:
260         Tf = alpha * Td;
261         if ( debug ) cout << " Tf = " << Tf;
262
263         // Filters the derivate error:
264         edf_n = edf_n_1 / (Ts/Tf + 1)
265             + ed_n * (Ts/Tf) / (Ts/Tf + 1);
266         if ( debug ) cout << " edf_n = " << edf_n;
267
268         // Calculates the incremental output:
269         delta_u_n = Kp * ( (ep_n - ep_n_1)
270                            + ((Ts/Ti) * e_n)
271                            + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
272         if ( debug ) cout << " delta_u_n = " << delta_u_n << endl;
273
274         // Integrator anti-windup logic:
275         if ( delta_u_n > (u_max - u_n_1) ) {
276             delta_u_n = 0;
277         } else if ( delta_u_n < (u_min - u_n_1) ) {
278             delta_u_n = 0;
279         }
280
281         // Calculates absolute output:
282         u_n = u_n_1 + delta_u_n;
283         if ( debug ) cout << "  output = " << u_n << endl;
284
285         // Updates indexed values;
286         u_n_1   = u_n;
287         ep_n_1  = ep_n;
288         edf_n_2 = edf_n_1;
289         edf_n_1 = edf_n;
290
291         unsigned int i;
292         for ( i = 0; i < output_list.size(); ++i ) {
293             output_list[i]->setDoubleValue( u_n );
294         }
295     } else if ( !enabled ) {
296         u_n   = 0.0;
297         ep_n  = 0.0;
298         edf_n = 0.0;
299         // Updates indexed values;
300         u_n_1   = u_n;
301         ep_n_1  = ep_n;
302         edf_n_2 = edf_n_1;
303         edf_n_1 = edf_n;
304     }
305 }
306
307
308 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
309     proportional( false ),
310     Kp( 0.0 ),
311     offset_prop( NULL ),
312     offset_value( 0.0 ),
313     integral( false ),
314     Ki( 0.0 ),
315     int_sum( 0.0 ),
316     clamp( false ),
317     debug( false ),
318     y_n( 0.0 ),
319     r_n( 0.0 ),
320     u_min( 0.0 ),
321     u_max( 0.0 )
322 {
323     int i;
324     for ( i = 0; i < node->nChildren(); ++i ) {
325         SGPropertyNode *child = node->getChild(i);
326         string cname = child->getName();
327         string cval = child->getStringValue();
328         if ( cname == "name" ) {
329             name = cval;
330         } else if ( cname == "debug" ) {
331             debug = child->getBoolValue();
332         } else if ( cname == "enable" ) {
333             // cout << "parsing enable" << endl;
334             SGPropertyNode *prop = child->getChild( "prop" );
335             if ( prop != NULL ) {
336                 // cout << "prop = " << prop->getStringValue() << endl;
337                 enable_prop = fgGetNode( prop->getStringValue(), true );
338             } else {
339                 // cout << "no prop child" << endl;
340             }
341             SGPropertyNode *val = child->getChild( "value" );
342             if ( val != NULL ) {
343                 enable_value = val->getStringValue();
344             }
345         } else if ( cname == "input" ) {
346             SGPropertyNode *prop = child->getChild( "prop" );
347             if ( prop != NULL ) {
348                 input_prop = fgGetNode( prop->getStringValue(), true );
349             }
350         } else if ( cname == "reference" ) {
351             SGPropertyNode *prop = child->getChild( "prop" );
352             if ( prop != NULL ) {
353                 r_n_prop = fgGetNode( prop->getStringValue(), true );
354             } else {
355                 prop = child->getChild( "value" );
356                 if ( prop != NULL ) {
357                     r_n = prop->getDoubleValue();
358                 }
359             }
360         } else if ( cname == "output" ) {
361             int i = 0;
362             SGPropertyNode *prop;
363             while ( (prop = child->getChild("prop", i)) != NULL ) {
364                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
365                 output_list.push_back( tmp );
366                 i++;
367             }
368         } else if ( cname == "config" ) {
369             SGPropertyNode *prop;
370
371             prop = child->getChild( "Kp" );
372             if ( prop != NULL ) {
373                 Kp = prop->getDoubleValue();
374                 proportional = true;
375             }
376
377             prop = child->getChild( "Ki" );
378             if ( prop != NULL ) {
379                 Ki = prop->getDoubleValue();
380                 integral = true;
381             }
382
383             prop = child->getChild( "u_min" );
384             if ( prop != NULL ) {
385                 u_min = prop->getDoubleValue();
386                 clamp = true;
387             }
388
389             prop = child->getChild( "u_max" );
390             if ( prop != NULL ) {
391                 u_max = prop->getDoubleValue();
392                 clamp = true;
393             }
394         } else {
395             SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
396             if ( name.length() ) {
397                 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
398             }
399         }
400     }   
401 }
402
403
404 void FGPISimpleController::update( double dt ) {
405     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
406         if ( !enabled ) {
407             // we have just been enabled, zero out int_sum
408             int_sum = 0.0;
409         }
410         enabled = true;
411     } else {
412         enabled = false;
413     }
414
415     if ( enabled ) {
416         if ( debug ) cout << "Updating " << name << endl;
417         double input = 0.0;
418         if ( input_prop != NULL ) {
419             input = input_prop->getDoubleValue();
420         }
421
422         double r_n = 0.0;
423         if ( r_n_prop != NULL ) {
424             r_n = r_n_prop->getDoubleValue();
425         } else {
426             r_n = r_n_value;
427         }
428                       
429         double error = r_n - input;
430         if ( debug ) cout << "input = " << input
431                           << " reference = " << r_n
432                           << " error = " << error
433                           << endl;
434
435         double prop_comp = 0.0;
436         double offset = 0.0;
437         if ( offset_prop != NULL ) {
438             offset = offset_prop->getDoubleValue();
439             if ( debug ) cout << "offset = " << offset << endl;
440         } else {
441             offset = offset_value;
442         }
443
444         if ( proportional ) {
445             prop_comp = error * Kp + offset;
446         }
447
448         if ( integral ) {
449             int_sum += error * Ki * dt;
450         } else {
451             int_sum = 0.0;
452         }
453
454         if ( debug ) cout << "prop_comp = " << prop_comp
455                           << " int_sum = " << int_sum << endl;
456
457         double output = prop_comp + int_sum;
458
459         if ( clamp ) {
460             if ( output < u_min ) {
461                 output = u_min;
462             }
463             if ( output > u_max ) {
464                 output = u_max;
465             }
466         }
467         if ( debug ) cout << "output = " << output << endl;
468
469         unsigned int i;
470         for ( i = 0; i < output_list.size(); ++i ) {
471             output_list[i]->setDoubleValue( output );
472         }
473     }
474 }
475
476
477 FGXMLAutopilot::FGXMLAutopilot() {
478 }
479
480
481 FGXMLAutopilot::~FGXMLAutopilot() {
482 }
483
484  
485 void FGXMLAutopilot::init() {
486     config_props = fgGetNode( "/autopilot/new-config", true );
487
488     SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
489
490     if ( path_n ) {
491         SGPath config( globals->get_fg_root() );
492         config.append( path_n->getStringValue() );
493
494         SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
495                 << config.str() );
496         try {
497             readProperties( config.str(), config_props );
498
499             if ( ! build() ) {
500                 SG_LOG( SG_ALL, SG_ALERT,
501                         "Detected an internal inconsistancy in the autopilot");
502                 SG_LOG( SG_ALL, SG_ALERT,
503                         " configuration.  See earlier errors for" );
504                 SG_LOG( SG_ALL, SG_ALERT,
505                         " details.");
506                 exit(-1);
507             }        
508         } catch (const sg_exception& exc) {
509             SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
510                     << config.str() );
511         }
512
513     } else {
514         SG_LOG( SG_ALL, SG_WARN,
515                 "No autopilot configuration specified for this model!");
516     }
517 }
518
519
520 void FGXMLAutopilot::reinit() {
521     components.clear();
522     init();
523     build();
524 }
525
526
527 void FGXMLAutopilot::bind() {
528 }
529
530 void FGXMLAutopilot::unbind() {
531 }
532
533 bool FGXMLAutopilot::build() {
534     SGPropertyNode *node;
535     int i;
536
537     int count = config_props->nChildren();
538     for ( i = 0; i < count; ++i ) {
539         node = config_props->getChild(i);
540         string name = node->getName();
541         // cout << name << endl;
542         if ( name == "pid-controller" ) {
543             FGXMLAutoComponent *c = new FGPIDController( node );
544             components.push_back( c );
545         } else if ( name == "pi-simple-controller" ) {
546             FGXMLAutoComponent *c = new FGPISimpleController( node );
547             components.push_back( c );
548         } else {
549             SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
550                     << name );
551             return false;
552         }
553     }
554
555     return true;
556 }
557
558
559 /*
560  * Update helper values
561  */
562 static void update_helper( double dt ) {
563     // Estimate speed in 5,10 seconds
564     static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
565     static SGPropertyNode *lookahead5
566         = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
567     static SGPropertyNode *lookahead10
568         = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
569
570     static double average = 0.0; // average/filtered prediction
571     static double v_last = 0.0;  // last velocity
572
573     double v = vel->getDoubleValue();
574     double a = 0.0;
575     if ( dt > 0.0 ) {
576         a = (v - v_last) / dt;
577
578         if ( dt < 1.0 ) {
579             average = (1.0 - dt) * average + dt * a;
580         } else {
581             average = a;
582         }
583
584         lookahead5->setDoubleValue( v + average * 5.0 );
585         lookahead10->setDoubleValue( v + average * 10.0 );
586         v_last = v;
587     }
588
589     // Calculate heading bug error normalized to +/- 180.0 (based on
590     // DG indicated heading)
591     static SGPropertyNode *bug
592         = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
593     static SGPropertyNode *ind_hdg
594         = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
595                      true );
596     static SGPropertyNode *ind_bug_error
597         = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
598
599     double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
600     if ( diff < -180.0 ) { diff += 360.0; }
601     if ( diff > 180.0 ) { diff -= 360.0; }
602     ind_bug_error->setDoubleValue( diff );
603
604     // Calculate heading bug error normalized to +/- 180.0 (based on
605     // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
606     // compass.)
607     static SGPropertyNode *mag_hdg
608         = fgGetNode( "/orientation/heading-magnetic-deg", true );
609     static SGPropertyNode *fdm_bug_error
610         = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
611
612     diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
613     if ( diff < -180.0 ) { diff += 360.0; }
614     if ( diff > 180.0 ) { diff -= 360.0; }
615     fdm_bug_error->setDoubleValue( diff );
616
617     // Calculate true heading error normalized to +/- 180.0
618     static SGPropertyNode *target_true
619         = fgGetNode( "/autopilot/settings/true-heading-deg", true );
620     static SGPropertyNode *true_hdg
621         = fgGetNode( "/orientation/heading-deg", true );
622     static SGPropertyNode *true_error
623         = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
624
625     diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
626     if ( diff < -180.0 ) { diff += 360.0; }
627     if ( diff > 180.0 ) { diff -= 360.0; }
628     true_error->setDoubleValue( diff );
629
630     // Calculate nav1 target heading error normalized to +/- 180.0
631     static SGPropertyNode *target_nav1
632         = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
633     static SGPropertyNode *true_nav1
634         = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
635
636     diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
637     if ( diff < -180.0 ) { diff += 360.0; }
638     if ( diff > 180.0 ) { diff -= 360.0; }
639     true_nav1->setDoubleValue( diff );
640
641     // Calculate vertical speed in fpm
642     static SGPropertyNode *vs_fps
643         = fgGetNode( "/velocities/vertical-speed-fps", true );
644     static SGPropertyNode *vs_fpm
645         = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
646
647     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );  
648 }
649
650
651 /*
652  * Update the list of autopilot components
653  */
654
655 void FGXMLAutopilot::update( double dt ) {
656     update_helper( dt );
657
658     unsigned int i;
659     for ( i = 0; i < components.size(); ++i ) {
660         components[i]->update( dt );
661     }
662 }