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