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