]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/xmlauto.cxx
replace depreciated plib symbols with their new forms
[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  - http://www.flightgear.org/~curt
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 #include <simgear/sg_inlines.h>
27
28 #include <Main/fg_props.hxx>
29 #include <Main/globals.hxx>
30 #include <Main/util.hxx>
31
32 #include "xmlauto.hxx"
33
34
35 FGPIDController::FGPIDController( SGPropertyNode *node ):
36     debug( false ),
37     y_n( 0.0 ),
38     r_n( 0.0 ),
39     y_scale( 1.0 ),
40     r_scale( 1.0 ),
41     y_offset( 0.0 ),
42     r_offset( 0.0 ),
43     Kp( 0.0 ),
44     alpha( 0.1 ),
45     beta( 1.0 ),
46     gamma( 0.0 ),
47     Ti( 0.0 ),
48     Td( 0.0 ),
49     u_min( 0.0 ),
50     u_max( 0.0 ),
51     ep_n_1( 0.0 ),
52     edf_n_1( 0.0 ),
53     edf_n_2( 0.0 ),
54     u_n_1( 0.0 ),
55     desiredTs( 0.0 )
56 {
57     int i;
58     for ( i = 0; i < node->nChildren(); ++i ) {
59         SGPropertyNode *child = node->getChild(i);
60         string cname = child->getName();
61         string cval = child->getStringValue();
62         if ( cname == "name" ) {
63             name = cval;
64         } else if ( cname == "debug" ) {
65             debug = child->getBoolValue();
66         } else if ( cname == "enable" ) {
67             // cout << "parsing enable" << endl;
68             SGPropertyNode *prop = child->getChild( "prop" );
69             if ( prop != NULL ) {
70                 // cout << "prop = " << prop->getStringValue() << endl;
71                 enable_prop = fgGetNode( prop->getStringValue(), true );
72             } else {
73                 // cout << "no prop child" << endl;
74             }
75             SGPropertyNode *val = child->getChild( "value" );
76             if ( val != NULL ) {
77                 enable_value = val->getStringValue();
78             }
79         } else if ( cname == "input" ) {
80             SGPropertyNode *prop = child->getChild( "prop" );
81             if ( prop != NULL ) {
82                 input_prop = fgGetNode( prop->getStringValue(), true );
83             }
84             prop = child->getChild( "scale" );
85             if ( prop != NULL ) {
86                 y_scale = prop->getDoubleValue();
87             }
88             prop = child->getChild( "offset" );
89             if ( prop != NULL ) {
90                 y_offset = prop->getDoubleValue();
91             }
92         } else if ( cname == "reference" ) {
93             SGPropertyNode *prop = child->getChild( "prop" );
94             if ( prop != NULL ) {
95                 r_n_prop = fgGetNode( prop->getStringValue(), true );
96             } else {
97                 prop = child->getChild( "value" );
98                 if ( prop != NULL ) {
99                     r_n = prop->getDoubleValue();
100                 }
101             }
102             prop = child->getChild( "scale" );
103             if ( prop != NULL ) {
104                 r_scale = prop->getDoubleValue();
105             }
106             prop = child->getChild( "offset" );
107             if ( prop != NULL ) {
108                 r_offset = prop->getDoubleValue();
109             }
110         } else if ( cname == "output" ) {
111             int i = 0;
112             SGPropertyNode *prop;
113             while ( (prop = child->getChild("prop", i)) != NULL ) {
114                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
115                 output_list.push_back( tmp );
116                 i++;
117             }
118         } else if ( cname == "config" ) {
119             SGPropertyNode *prop;
120
121             prop = child->getChild( "Ts" );
122             if ( prop != NULL ) {
123                 desiredTs = prop->getDoubleValue();
124             }
125             
126             prop = child->getChild( "Kp" );
127             if ( prop != NULL ) {
128                 Kp = prop->getDoubleValue();
129             }
130
131             prop = child->getChild( "beta" );
132             if ( prop != NULL ) {
133                 beta = prop->getDoubleValue();
134             }
135
136             prop = child->getChild( "alpha" );
137             if ( prop != NULL ) {
138                 alpha = prop->getDoubleValue();
139             }
140
141             prop = child->getChild( "gamma" );
142             if ( prop != NULL ) {
143                 gamma = prop->getDoubleValue();
144             }
145
146             prop = child->getChild( "Ti" );
147             if ( prop != NULL ) {
148                 Ti = prop->getDoubleValue();
149             }
150
151             prop = child->getChild( "Td" );
152             if ( prop != NULL ) {
153                 Td = prop->getDoubleValue();
154             }
155
156             prop = child->getChild( "u_min" );
157             if ( prop != NULL ) {
158                 u_min = prop->getDoubleValue();
159             }
160
161             prop = child->getChild( "u_max" );
162             if ( prop != NULL ) {
163                 u_max = prop->getDoubleValue();
164             }
165         } else {
166             SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
167             if ( name.length() ) {
168                 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
169             }
170         }
171     }   
172 }
173
174
175 /*
176  * Roy Vegard Ovesen:
177  *
178  * Ok! Here is the PID controller algorithm that I would like to see
179  * implemented:
180  *
181  *   delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
182  *               + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
183  *
184  *   u_n = u_n-1 + delta_u_n
185  *
186  * where:
187  *
188  * delta_u : The incremental output
189  * Kp      : Proportional gain
190  * ep      : Proportional error with reference weighing
191  *           ep = beta * r - y
192  *           where:
193  *           beta : Weighing factor
194  *           r    : Reference (setpoint)
195  *           y    : Process value, measured
196  * e       : Error
197  *           e = r - y
198  * Ts      : Sampling interval
199  * Ti      : Integrator time
200  * Td      : Derivator time
201  * edf     : Derivate error with reference weighing and filtering
202  *           edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
203  *           where:
204  *           Tf : Filter time
205  *           Tf = alpha * Td , where alpha usually is set to 0.1
206  *           ed : Unfiltered derivate error with reference weighing
207  *             ed = gamma * r - y
208  *             where:
209  *             gamma : Weighing factor
210  * 
211  * u       : absolute output
212  * 
213  * Index n means the n'th value.
214  * 
215  * 
216  * Inputs:
217  * enabled ,
218  * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
219  * Kp , Ti , Td , Ts (is the sampling time available?)
220  * u_min , u_max
221  * 
222  * Output:
223  * u_n
224  */
225
226 void FGPIDController::update( double dt ) {
227     double ep_n;            // proportional error with reference weighing
228     double e_n;             // error
229     double ed_n;            // derivative error
230     double edf_n;           // derivative error filter
231     double Tf;              // filter time
232     double delta_u_n = 0.0; // incremental output
233     double u_n = 0.0;       // absolute output
234     double Ts;              // sampling interval (sec)
235     
236     elapsedTime += dt;
237     if ( elapsedTime <= desiredTs ) {
238         // do nothing if time step is not positive (i.e. no time has
239         // elapsed)
240         return;
241     }
242     Ts = elapsedTime;
243     elapsedTime = 0.0;
244
245     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
246         if ( !enabled ) {
247             // first time being enabled, seed u_n with current
248             // property tree value
249             u_n = output_list[0]->getDoubleValue();
250             // and clip
251             if ( u_n < u_min ) { u_n = u_min; }
252             if ( u_n > u_max ) { u_n = u_max; }
253             u_n_1 = u_n;
254         }
255         enabled = true;
256     } else {
257         enabled = false;
258     }
259
260     if ( enabled && Ts > 0.0) {
261         if ( debug ) cout << "Updating " << name
262                           << " Ts " << Ts << endl;
263
264         double y_n = 0.0;
265         if ( input_prop != NULL ) {
266             y_n = input_prop->getDoubleValue() * y_scale + y_offset;
267         }
268
269         double r_n = 0.0;
270         if ( r_n_prop != NULL ) {
271             r_n = r_n_prop->getDoubleValue() * r_scale + r_offset;
272         } else {
273             r_n = r_n_value;
274         }
275                       
276         if ( debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
277
278         // Calculates proportional error:
279         ep_n = beta * r_n - y_n;
280         if ( debug ) cout << "  ep_n = " << ep_n;
281         if ( debug ) cout << "  ep_n_1 = " << ep_n_1;
282
283         // Calculates error:
284         e_n = r_n - y_n;
285         if ( debug ) cout << " e_n = " << e_n;
286
287         // Calculates derivate error:
288         ed_n = gamma * r_n - y_n;
289         if ( debug ) cout << " ed_n = " << ed_n;
290
291         if ( Td > 0.0 ) {
292             // Calculates filter time:
293             Tf = alpha * Td;
294             if ( debug ) cout << " Tf = " << Tf;
295
296             // Filters the derivate error:
297             edf_n = edf_n_1 / (Ts/Tf + 1)
298                 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
299             if ( debug ) cout << " edf_n = " << edf_n;
300         } else {
301             edf_n = ed_n;
302         }
303
304         // Calculates the incremental output:
305         if ( Ti > 0.0 ) {
306             delta_u_n = Kp * ( (ep_n - ep_n_1)
307                                + ((Ts/Ti) * e_n)
308                                + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
309         }
310
311         if ( debug ) {
312             cout << " delta_u_n = " << delta_u_n << endl;
313             cout << "P:" << Kp * (ep_n - ep_n_1)
314                  << " I:" << Kp * ((Ts/Ti) * e_n)
315                  << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
316                  << endl;
317         }
318
319         // Integrator anti-windup logic:
320         if ( delta_u_n > (u_max - u_n_1) ) {
321             delta_u_n = u_max - u_n_1;
322             if ( debug ) cout << " max saturation " << endl;
323         } else if ( delta_u_n < (u_min - u_n_1) ) {
324             delta_u_n = u_min - u_n_1;
325             if ( debug ) cout << " min saturation " << endl;
326         }
327
328         // Calculates absolute output:
329         u_n = u_n_1 + delta_u_n;
330         if ( debug ) cout << "  output = " << u_n << endl;
331
332         // Updates indexed values;
333         u_n_1   = u_n;
334         ep_n_1  = ep_n;
335         edf_n_2 = edf_n_1;
336         edf_n_1 = edf_n;
337
338         unsigned int i;
339         for ( i = 0; i < output_list.size(); ++i ) {
340             output_list[i]->setDoubleValue( u_n );
341         }
342     } else if ( !enabled ) {
343         ep_n  = 0.0;
344         edf_n = 0.0;
345         // Updates indexed values;
346         u_n_1   = u_n;
347         ep_n_1  = ep_n;
348         edf_n_2 = edf_n_1;
349         edf_n_1 = edf_n;
350     }
351 }
352
353
354 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
355     proportional( false ),
356     Kp( 0.0 ),
357     offset_prop( NULL ),
358     offset_value( 0.0 ),
359     integral( false ),
360     Ki( 0.0 ),
361     int_sum( 0.0 ),
362     clamp( false ),
363     debug( false ),
364     y_n( 0.0 ),
365     r_n( 0.0 ),
366     y_scale( 1.0 ),
367     r_scale ( 1.0 ),
368     u_min( 0.0 ),
369     u_max( 0.0 )
370 {
371     int i;
372     for ( i = 0; i < node->nChildren(); ++i ) {
373         SGPropertyNode *child = node->getChild(i);
374         string cname = child->getName();
375         string cval = child->getStringValue();
376         if ( cname == "name" ) {
377             name = cval;
378         } else if ( cname == "debug" ) {
379             debug = child->getBoolValue();
380         } else if ( cname == "enable" ) {
381             // cout << "parsing enable" << endl;
382             SGPropertyNode *prop = child->getChild( "prop" );
383             if ( prop != NULL ) {
384                 // cout << "prop = " << prop->getStringValue() << endl;
385                 enable_prop = fgGetNode( prop->getStringValue(), true );
386             } else {
387                 // cout << "no prop child" << endl;
388             }
389             SGPropertyNode *val = child->getChild( "value" );
390             if ( val != NULL ) {
391                 enable_value = val->getStringValue();
392             }
393         } else if ( cname == "input" ) {
394             SGPropertyNode *prop = child->getChild( "prop" );
395             if ( prop != NULL ) {
396                 input_prop = fgGetNode( prop->getStringValue(), true );
397             }
398             prop = child->getChild( "scale" );
399             if ( prop != NULL ) {
400                 y_scale = prop->getDoubleValue();
401             }
402         } else if ( cname == "reference" ) {
403             SGPropertyNode *prop = child->getChild( "prop" );
404             if ( prop != NULL ) {
405                 r_n_prop = fgGetNode( prop->getStringValue(), true );
406             } else {
407                 prop = child->getChild( "value" );
408                 if ( prop != NULL ) {
409                     r_n = prop->getDoubleValue();
410                 }
411             }
412             prop = child->getChild( "scale" );
413             if ( prop != NULL ) {
414                 r_scale = prop->getDoubleValue();
415             }
416         } else if ( cname == "output" ) {
417             int i = 0;
418             SGPropertyNode *prop;
419             while ( (prop = child->getChild("prop", i)) != NULL ) {
420                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
421                 output_list.push_back( tmp );
422                 i++;
423             }
424         } else if ( cname == "config" ) {
425             SGPropertyNode *prop;
426
427             prop = child->getChild( "Kp" );
428             if ( prop != NULL ) {
429                 Kp = prop->getDoubleValue();
430                 proportional = true;
431             }
432
433             prop = child->getChild( "Ki" );
434             if ( prop != NULL ) {
435                 Ki = prop->getDoubleValue();
436                 integral = true;
437             }
438
439             prop = child->getChild( "u_min" );
440             if ( prop != NULL ) {
441                 u_min = prop->getDoubleValue();
442                 clamp = true;
443             }
444
445             prop = child->getChild( "u_max" );
446             if ( prop != NULL ) {
447                 u_max = prop->getDoubleValue();
448                 clamp = true;
449             }
450         } else {
451             SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
452             if ( name.length() ) {
453                 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
454             }
455         }
456     }   
457 }
458
459
460 void FGPISimpleController::update( double dt ) {
461     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
462         if ( !enabled ) {
463             // we have just been enabled, zero out int_sum
464             int_sum = 0.0;
465         }
466         enabled = true;
467     } else {
468         enabled = false;
469     }
470
471     if ( enabled ) {
472         if ( debug ) cout << "Updating " << name << endl;
473         double input = 0.0;
474         if ( input_prop != NULL ) {
475             input = input_prop->getDoubleValue() * y_scale;
476         }
477
478         double r_n = 0.0;
479         if ( r_n_prop != NULL ) {
480             r_n = r_n_prop->getDoubleValue() * r_scale;
481         } else {
482             r_n = r_n_value;
483         }
484                       
485         double error = r_n - input;
486         if ( debug ) cout << "input = " << input
487                           << " reference = " << r_n
488                           << " error = " << error
489                           << endl;
490
491         double prop_comp = 0.0;
492         double offset = 0.0;
493         if ( offset_prop != NULL ) {
494             offset = offset_prop->getDoubleValue();
495             if ( debug ) cout << "offset = " << offset << endl;
496         } else {
497             offset = offset_value;
498         }
499
500         if ( proportional ) {
501             prop_comp = error * Kp + offset;
502         }
503
504         if ( integral ) {
505             int_sum += error * Ki * dt;
506         } else {
507             int_sum = 0.0;
508         }
509
510         if ( debug ) cout << "prop_comp = " << prop_comp
511                           << " int_sum = " << int_sum << endl;
512
513         double output = prop_comp + int_sum;
514
515         if ( clamp ) {
516             if ( output < u_min ) {
517                 output = u_min;
518             }
519             if ( output > u_max ) {
520                 output = u_max;
521             }
522         }
523         if ( debug ) cout << "output = " << output << endl;
524
525         unsigned int i;
526         for ( i = 0; i < output_list.size(); ++i ) {
527             output_list[i]->setDoubleValue( output );
528         }
529     }
530 }
531
532
533 FGPredictor::FGPredictor ( SGPropertyNode *node ):
534     last_value ( 999999999.9 ),
535     average ( 0.0 ),
536     seconds( 0.0 ),
537     filter_gain( 0.0 ),
538     debug( false ),
539     ivalue( 0.0 )
540 {
541     int i;
542     for ( i = 0; i < node->nChildren(); ++i ) {
543         SGPropertyNode *child = node->getChild(i);
544         string cname = child->getName();
545         string cval = child->getStringValue();
546         if ( cname == "name" ) {
547             name = cval;
548         } else if ( cname == "debug" ) {
549             debug = child->getBoolValue();
550         } else if ( cname == "input" ) {
551             input_prop = fgGetNode( child->getStringValue(), true );
552         } else if ( cname == "seconds" ) {
553             seconds = child->getDoubleValue();
554         } else if ( cname == "filter-gain" ) {
555             filter_gain = child->getDoubleValue();
556         } else if ( cname == "output" ) {
557             SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
558             output_list.push_back( tmp );
559         }
560     }   
561 }
562
563 void FGPredictor::update( double dt ) {
564     /*
565        Simple moving average filter converts input value to predicted value "seconds".
566
567        Smoothing as described by Curt Olson:
568          gain would be valid in the range of 0 - 1.0
569          1.0 would mean no filtering.
570          0.0 would mean no input.
571          0.5 would mean (1 part past value + 1 part current value) / 2
572          0.1 would mean (9 parts past value + 1 part current value) / 10
573          0.25 would mean (3 parts past value + 1 part current value) / 4
574
575     */
576
577     if ( input_prop != NULL ) {
578         ivalue = input_prop->getDoubleValue();
579         // no sense if there isn't an input :-)
580         enabled = true;
581     } else {
582         enabled = false;
583     }
584
585     if ( enabled ) {
586
587         // first time initialize average
588         if (last_value >= 999999999.0) {
589            last_value = ivalue;
590         }
591
592         if ( dt > 0.0 ) {
593             double current = (ivalue - last_value)/dt; // calculate current error change (per second)
594             if ( dt < 1.0 ) {
595                 average = (1.0 - dt) * average + current * dt;
596             } else {
597                 average = current;
598             }
599
600             // calculate output with filter gain adjustment
601             double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
602
603             unsigned int i;
604             for ( i = 0; i < output_list.size(); ++i ) {
605                 output_list[i]->setDoubleValue( output );
606             }
607         }
608         last_value = ivalue;
609     }
610 }
611
612
613 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node)
614 {
615     samples = 1;
616
617     int i;
618     for ( i = 0; i < node->nChildren(); ++i ) {
619         SGPropertyNode *child = node->getChild(i);
620         string cname = child->getName();
621         string cval = child->getStringValue();
622         if ( cname == "name" ) {
623             name = cval;
624         } else if ( cname == "debug" ) {
625             debug = child->getBoolValue();
626         } else if ( cname == "type" ) {
627             if ( cval == "exponential" ) {
628                 filterType = exponential;
629             } else if (cval == "double-exponential") {
630                 filterType = doubleExponential;
631             } else if (cval == "moving-average") {
632                 filterType = movingAverage;
633             } else if (cval == "noise-spike") {
634                 filterType = noiseSpike;
635             }
636         } else if ( cname == "input" ) {
637             input_prop = fgGetNode( child->getStringValue(), true );
638         } else if ( cname == "filter-time" ) {
639             Tf = child->getDoubleValue();
640         } else if ( cname == "samples" ) {
641             samples = child->getIntValue();
642         } else if ( cname == "max-rate-of-change" ) {
643             rateOfChange = child->getDoubleValue();
644         } else if ( cname == "output" ) {
645             SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
646             output_list.push_back( tmp );
647         }
648     }
649
650     output.resize(2, 0.0);
651     input.resize(samples + 1, 0.0);
652 }
653
654 void FGDigitalFilter::update(double dt)
655 {
656     if ( input_prop != NULL ) {
657         input.push_front(input_prop->getDoubleValue());
658         input.resize(samples + 1, 0.0);
659         // no sense if there isn't an input :-)
660         enabled = true;
661     } else {
662         enabled = false;
663     }
664
665     if ( enabled && dt > 0.0 ) {
666         /*
667          * Exponential filter
668          *
669          * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
670          *
671          */
672
673         if (filterType == exponential)
674         {
675             double alpha = 1 / ((Tf/dt) + 1);
676             output.push_front(alpha * input[0] + 
677                               (1 - alpha) * output[0]);
678             unsigned int i;
679             for ( i = 0; i < output_list.size(); ++i ) {
680                 output_list[i]->setDoubleValue( output[0] );
681             }
682             output.resize(1);
683         } 
684         else if (filterType == doubleExponential)
685         {
686             double alpha = 1 / ((Tf/dt) + 1);
687             output.push_front(alpha * alpha * input[0] + 
688                               2 * (1 - alpha) * output[0] -
689                               (1 - alpha) * (1 - alpha) * output[1]);
690             unsigned int i;
691             for ( i = 0; i < output_list.size(); ++i ) {
692                 output_list[i]->setDoubleValue( output[0] );
693             }
694             output.resize(2);
695         }
696         else if (filterType == movingAverage)
697         {
698             output.push_front(output[0] + 
699                               (input[0] - input.back()) / samples);
700             unsigned int i;
701             for ( i = 0; i < output_list.size(); ++i ) {
702                 output_list[i]->setDoubleValue( output[0] );
703             }
704             output.resize(1);
705         }
706         else if (filterType == noiseSpike)
707         {
708             double maxChange = rateOfChange * dt;
709
710             if ((output[0] - input[0]) > maxChange)
711             {
712                 output.push_front(output[0] - maxChange);
713             }
714             else if ((output[0] - input[0]) < -maxChange)
715             {
716                 output.push_front(output[0] + maxChange);
717             }
718             else if (fabs(input[0] - output[0]) <= maxChange)
719             {
720                 output.push_front(input[0]);
721             }
722
723             unsigned int i;
724             for ( i = 0; i < output_list.size(); ++i ) {
725                 output_list[i]->setDoubleValue( output[0] );
726             }
727             output.resize(1);
728         }
729         if (debug)
730         {
731             cout << "input:" << input[0] 
732                  << "\toutput:" << output[0] << endl;
733         }
734     }
735 }
736
737
738 FGXMLAutopilot::FGXMLAutopilot() {
739 }
740
741
742 FGXMLAutopilot::~FGXMLAutopilot() {
743 }
744
745  
746 void FGXMLAutopilot::init() {
747     config_props = fgGetNode( "/autopilot/new-config", true );
748
749     SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
750
751     if ( path_n ) {
752         SGPath config( globals->get_fg_root() );
753         config.append( path_n->getStringValue() );
754
755         SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
756                 << config.str() );
757         try {
758             readProperties( config.str(), config_props );
759
760             if ( ! build() ) {
761                 SG_LOG( SG_ALL, SG_ALERT,
762                         "Detected an internal inconsistancy in the autopilot");
763                 SG_LOG( SG_ALL, SG_ALERT,
764                         " configuration.  See earlier errors for" );
765                 SG_LOG( SG_ALL, SG_ALERT,
766                         " details.");
767                 exit(-1);
768             }        
769         } catch (const sg_exception& exc) {
770             SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
771                     << config.str() );
772         }
773
774     } else {
775         SG_LOG( SG_ALL, SG_WARN,
776                 "No autopilot configuration specified for this model!");
777     }
778 }
779
780
781 void FGXMLAutopilot::reinit() {
782     components.clear();
783     init();
784     build();
785 }
786
787
788 void FGXMLAutopilot::bind() {
789 }
790
791 void FGXMLAutopilot::unbind() {
792 }
793
794 bool FGXMLAutopilot::build() {
795     SGPropertyNode *node;
796     int i;
797
798     int count = config_props->nChildren();
799     for ( i = 0; i < count; ++i ) {
800         node = config_props->getChild(i);
801         string name = node->getName();
802         // cout << name << endl;
803         if ( name == "pid-controller" ) {
804             FGXMLAutoComponent *c = new FGPIDController( node );
805             components.push_back( c );
806         } else if ( name == "pi-simple-controller" ) {
807             FGXMLAutoComponent *c = new FGPISimpleController( node );
808             components.push_back( c );
809         } else if ( name == "predict-simple" ) {
810             FGXMLAutoComponent *c = new FGPredictor( node );
811             components.push_back( c );
812         } else if ( name == "filter" ) {
813             FGXMLAutoComponent *c = new FGDigitalFilter( node );
814             components.push_back( c );
815         } else {
816             SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
817                     << name );
818             return false;
819         }
820     }
821
822     return true;
823 }
824
825
826 /*
827  * Update helper values
828  */
829 static void update_helper( double dt ) {
830     // Estimate speed in 5,10 seconds
831     static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
832     static SGPropertyNode *lookahead5
833         = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
834     static SGPropertyNode *lookahead10
835         = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
836
837     static double average = 0.0; // average/filtered prediction
838     static double v_last = 0.0;  // last velocity
839
840     double v = vel->getDoubleValue();
841     double a = 0.0;
842     if ( dt > 0.0 ) {
843         a = (v - v_last) / dt;
844
845         if ( dt < 1.0 ) {
846             average = (1.0 - dt) * average + dt * a;
847         } else {
848             average = a;
849         }
850
851         lookahead5->setDoubleValue( v + average * 5.0 );
852         lookahead10->setDoubleValue( v + average * 10.0 );
853         v_last = v;
854     }
855
856     // Calculate heading bug error normalized to +/- 180.0 (based on
857     // DG indicated heading)
858     static SGPropertyNode *bug
859         = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
860     static SGPropertyNode *ind_hdg
861         = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
862                      true );
863     static SGPropertyNode *ind_bug_error
864         = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
865
866     double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
867     if ( diff < -180.0 ) { diff += 360.0; }
868     if ( diff > 180.0 ) { diff -= 360.0; }
869     ind_bug_error->setDoubleValue( diff );
870
871     // Calculate heading bug error normalized to +/- 180.0 (based on
872     // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
873     // compass.)
874     static SGPropertyNode *mag_hdg
875         = fgGetNode( "/orientation/heading-magnetic-deg", true );
876     static SGPropertyNode *fdm_bug_error
877         = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
878
879     diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
880     if ( diff < -180.0 ) { diff += 360.0; }
881     if ( diff > 180.0 ) { diff -= 360.0; }
882     fdm_bug_error->setDoubleValue( diff );
883
884     // Calculate true heading error normalized to +/- 180.0
885     static SGPropertyNode *target_true
886         = fgGetNode( "/autopilot/settings/true-heading-deg", true );
887     static SGPropertyNode *true_hdg
888         = fgGetNode( "/orientation/heading-deg", true );
889     static SGPropertyNode *true_track
890         = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
891     static SGPropertyNode *true_error
892         = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
893
894     diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
895     if ( diff < -180.0 ) { diff += 360.0; }
896     if ( diff > 180.0 ) { diff -= 360.0; }
897     true_error->setDoubleValue( diff );
898
899     // Calculate nav1 target heading error normalized to +/- 180.0
900     static SGPropertyNode *target_nav1
901         = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
902     static SGPropertyNode *true_nav1
903         = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
904     static SGPropertyNode *true_track_nav1
905         = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
906
907     diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
908     if ( diff < -180.0 ) { diff += 360.0; }
909     if ( diff > 180.0 ) { diff -= 360.0; }
910     true_nav1->setDoubleValue( diff );
911
912     diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
913     if ( diff < -180.0 ) { diff += 360.0; }
914     if ( diff > 180.0 ) { diff -= 360.0; }
915     true_track_nav1->setDoubleValue( diff );
916
917     // Calculate nav1 selected course error normalized to +/- 180.0
918     // (based on DG indicated heading)
919     static SGPropertyNode *nav1_course_error
920         = fgGetNode( "/autopilot/internal/nav1-course-error", true );
921     static SGPropertyNode *nav1_selected_course
922         = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
923
924     diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
925 //    if ( diff < -180.0 ) { diff += 360.0; }
926 //    if ( diff > 180.0 ) { diff -= 360.0; }
927     SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
928     nav1_course_error->setDoubleValue( diff );
929
930     // Calculate vertical speed in fpm
931     static SGPropertyNode *vs_fps
932         = fgGetNode( "/velocities/vertical-speed-fps", true );
933     static SGPropertyNode *vs_fpm
934         = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
935
936     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
937
938
939     // Calculate static port pressure rate in [inhg/s].
940     // Used to determine vertical speed.
941     static SGPropertyNode *static_pressure
942         = fgGetNode( "/systems/static[0]/pressure-inhg", true );
943     static SGPropertyNode *pressure_rate
944         = fgGetNode( "/autopilot/internal/pressure-rate", true );
945
946     static double last_static_pressure = 0.0;
947
948     if ( dt > 0.0 ) {
949         double current_static_pressure = static_pressure->getDoubleValue();
950
951         double current_pressure_rate = 
952             ( current_static_pressure - last_static_pressure ) / dt;
953
954         pressure_rate->setDoubleValue(current_pressure_rate);
955
956         last_static_pressure = current_static_pressure;
957     }
958
959 }
960
961
962 /*
963  * Update the list of autopilot components
964  */
965
966 void FGXMLAutopilot::update( double dt ) {
967     update_helper( dt );
968
969     unsigned int i;
970     for ( i = 0; i < components.size(); ++i ) {
971         components[i]->update( dt );
972     }
973 }