]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/xmlauto.cxx
Add RS, JK, D and T flip flops as components
[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/misc/strutils.hxx>
30 #include <simgear/structure/exception.hxx>
31 #include <simgear/misc/sg_path.hxx>
32 #include <simgear/sg_inlines.h>
33 #include <simgear/props/props_io.hxx>
34
35 #include <Main/fg_props.hxx>
36 #include <Main/globals.hxx>
37 #include <Main/util.hxx>
38
39 #include "xmlauto.hxx"
40
41 using std::cout;
42 using std::endl;
43
44 using simgear::PropertyList;
45
46 FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
47 {
48   SGPropertyNode_ptr minNode = root->getChild( "min" );
49   SGPropertyNode_ptr maxNode = root->getChild( "max" );
50   if( minNode == NULL || maxNode == NULL ) {
51     SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
52   } else {
53     minPeriod = new FGXMLAutoInput( minNode );
54     maxPeriod = new FGXMLAutoInput( maxNode );
55   }
56 }
57
58 double FGPeriodicalValue::normalize( double value )
59 {
60   if( !(minPeriod && maxPeriod )) return value;
61
62   double p1 = minPeriod->get_value();
63   double p2 = maxPeriod->get_value();
64
65   double min = std::min<double>(p1,p2);
66   double max = std::max<double>(p1,p2);
67   double phase = fabs(max - min);
68
69   if( phase > SGLimitsd::min() ) {
70     while( value < min )  value += phase;
71     while( value >= max ) value -= phase;
72   } else {
73     value = min; // phase is zero
74   }
75
76   return value;
77 }
78
79 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
80   value(0.0),
81   abs(false),
82   _condition(NULL) 
83 {
84   parse( node, value, offset, scale );
85 }
86
87
88 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
89 {
90     value = aValue;
91     property = NULL; 
92     offset = NULL;
93     scale = NULL;
94     min = NULL;
95     max = NULL;
96     periodical = NULL;
97
98     if( node == NULL )
99         return;
100
101     SGPropertyNode * n;
102
103     if( (n = node->getChild("condition")) != NULL ) {
104         _condition = sgReadCondition(fgGetNode("/"), n);
105     }
106
107     if( (n = node->getChild( "scale" )) != NULL ) {
108         scale = new FGXMLAutoInput( n, aScale );
109     }
110
111     if( (n = node->getChild( "offset" )) != NULL ) {
112         offset = new FGXMLAutoInput( n, aOffset );
113     }
114
115     if( (n = node->getChild( "max" )) != NULL ) {
116         max = new FGXMLAutoInput( n );
117     }
118
119     if( (n = node->getChild( "min" )) != NULL ) {
120         min = new FGXMLAutoInput( n );
121     }
122
123     if( (n = node->getChild( "abs" )) != NULL ) {
124       abs = n->getBoolValue();
125     }
126
127     if( (n = node->getChild( "period" )) != NULL ) {
128       periodical = new FGPeriodicalValue( n );
129     }
130
131     SGPropertyNode *valueNode = node->getChild( "value" );
132     if ( valueNode != NULL ) {
133         value = valueNode->getDoubleValue();
134     }
135
136     n = node->getChild( "property" );
137     // if no <property> element, check for <prop> element for backwards
138     // compatibility
139     if(  n == NULL )
140         n = node->getChild( "prop" );
141
142     if (  n != NULL ) {
143         property = fgGetNode(  n->getStringValue(), true );
144         if ( valueNode != NULL ) {
145             // initialize property with given value 
146             // if both <prop> and <value> exist
147             double s = get_scale();
148             if( s != 0 )
149               property->setDoubleValue( (value - get_offset())/s );
150             else
151               property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
152         }
153     }
154
155     if ( n == NULL && valueNode == NULL ) {
156         // no <value> element and no <prop> element, use text node 
157         const char * textnode = node->getStringValue();
158         char * endp = NULL;
159         // try to convert to a double value. If the textnode does not start with a number
160         // endp will point to the beginning of the string. We assume this should be
161         // a property name
162         value = strtod( textnode, &endp );
163         if( endp == textnode ) {
164           property = fgGetNode( textnode, true );
165         }
166     }
167 }
168
169 void FGXMLAutoInput::set_value( double aValue ) 
170 {
171     double s = get_scale();
172     if( s != 0 )
173         property->setDoubleValue( (aValue - get_offset())/s );
174     else
175         property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
176 }
177
178 double FGXMLAutoInput::get_value() 
179 {
180     if( property != NULL ) 
181         value = property->getDoubleValue();
182
183     if( scale ) 
184         value *= scale->get_value();
185
186     if( offset ) 
187         value += offset->get_value();
188
189     if( min ) {
190         double m = min->get_value();
191         if( value < m )
192             value = m;
193     }
194
195     if( max ) {
196         double m = max->get_value();
197         if( value > m )
198             value = m;
199     }
200
201     if( periodical ) {
202       value = periodical->normalize( value );
203     }
204     
205     return abs ? fabs(value) : value;
206 }
207
208 FGXMLAutoComponent::FGXMLAutoComponent() :
209       _condition( NULL ),
210       enable_prop( NULL ),
211       enable_value( NULL ),
212       passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
213       honor_passive( false ),
214       name(""),
215       feedback_if_disabled( false ),
216       debug(false),
217       enabled( false )
218 {
219 }
220
221 FGXMLAutoComponent::~FGXMLAutoComponent() 
222 {
223     delete enable_value;
224 }
225
226 void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
227 {
228   SGPropertyNode *prop; 
229   for (int i = 0; i < aNode->nChildren(); ++i ) {
230     SGPropertyNode *child = aNode->getChild(i);
231     string cname(child->getName());
232     
233     if (parseNodeHook(cname, child)) {
234       // derived class handled it, fine
235     } else if ( cname == "name" ) {
236       name = child->getStringValue();
237     } else if ( cname == "feedback-if-disabled" ) {
238       feedback_if_disabled = child->getBoolValue();
239     } else if ( cname == "debug" ) {
240       debug = child->getBoolValue();
241     } else if ( cname == "enable" ) {
242       if( (prop = child->getChild("condition")) != NULL ) {
243         _condition = sgReadCondition(fgGetNode("/"), prop);
244       } else {
245          if ( (prop = child->getChild( "prop" )) != NULL ) {
246              enable_prop = fgGetNode( prop->getStringValue(), true );
247          }
248
249          if ( (prop = child->getChild( "value" )) != NULL ) {
250              delete enable_value;
251              enable_value = new string(prop->getStringValue());
252          }
253       }
254       if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
255           honor_passive = prop->getBoolValue();
256       }
257     } else if ( cname == "input" ) {
258       valueInput.push_back( new FGXMLAutoInput( child ) );
259     } else if ( cname == "reference" ) {
260       referenceInput.push_back( new FGXMLAutoInput( child ) );
261     } else if ( cname == "output" ) {
262       // grab all <prop> and <property> childs
263       int found = 0;
264       // backwards compatibility: allow <prop> elements
265       for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) { 
266           SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
267           output_list.push_back( tmp );
268           found++;
269       }
270       for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) { 
271           SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
272           output_list.push_back( tmp );
273           found++;
274       }
275
276       // no <prop> elements, text node of <output> is property name
277       if( found == 0 )
278           output_list.push_back( fgGetNode(child->getStringValue(), true ) );
279     } else if ( cname == "config" ) {
280       parseConfig(child);
281     } else if ( cname == "min" ) {
282         uminInput.push_back( new FGXMLAutoInput( child ) );
283     } else if ( cname == "u_min" ) {
284         uminInput.push_back( new FGXMLAutoInput( child ) );
285     } else if ( cname == "max" ) {
286         umaxInput.push_back( new FGXMLAutoInput( child ) );
287     } else if ( cname == "u_max" ) {
288         umaxInput.push_back( new FGXMLAutoInput( child ) );
289     } else if ( cname == "period" ) {
290       periodical = new FGPeriodicalValue( child );
291     } else {
292       SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:" 
293         << cname << " in section " << name);
294       throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
295     }
296   } // of top-level iteration
297 }
298
299 void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
300 {
301   for (int i = 0; i < aConfig->nChildren(); ++i ) {
302     SGPropertyNode *child = aConfig->getChild(i);
303     string cname(child->getName());
304     
305     if (parseConfigHook(cname, child)) {
306       // derived class handled it, fine
307     } else if ( cname == "min" ) {
308         uminInput.push_back( new FGXMLAutoInput( child ) );
309     } else if ( cname == "u_min" ) {
310         uminInput.push_back( new FGXMLAutoInput( child ) );
311     } else if ( cname == "max" ) {
312         umaxInput.push_back( new FGXMLAutoInput( child ) );
313     } else if ( cname == "u_max" ) {
314         umaxInput.push_back( new FGXMLAutoInput( child ) );
315     } else {
316       SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:" 
317         << cname << " in section " << name);
318       throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
319     }
320   } // of config iteration
321 }
322
323 bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
324 {
325   return false;
326 }
327
328 bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
329 {
330   return false;
331 }
332
333 bool FGXMLAutoComponent::isPropertyEnabled()
334 {
335     if( _condition )
336         return _condition->test();
337
338     if( enable_prop ) {
339         if( enable_value ) {
340             return *enable_value == enable_prop->getStringValue();
341         } else {
342             return enable_prop->getBoolValue();
343         }
344     }
345     return true;
346 }
347
348 void FGXMLAutoComponent::do_feedback_if_disabled()
349 {
350     if( output_list.size() > 0 ) {    
351         FGXMLAutoInput * input = valueInput.get_active();
352         if( input != NULL )
353             input->set_value( output_list[0]->getDoubleValue() );
354     }
355 }
356
357 double FGXMLAutoComponent::clamp( double value )
358 {
359     //If this is a periodical value, normalize it into our domain 
360     // before clamping
361     if( periodical )
362       value = periodical->normalize( value );
363
364     // clamp, if either min or max is defined
365     if( uminInput.size() + umaxInput.size() > 0 ) {
366         double d = umaxInput.get_value( 0.0 );
367         if( value > d ) value = d;
368         d = uminInput.get_value( 0.0 );
369         if( value < d ) value = d;
370     }
371     return value;
372 }
373
374 FGPIDController::FGPIDController( SGPropertyNode *node ):
375     FGXMLAutoComponent(),
376     alpha( 0.1 ),
377     beta( 1.0 ),
378     gamma( 0.0 ),
379     ep_n_1( 0.0 ),
380     edf_n_1( 0.0 ),
381     edf_n_2( 0.0 ),
382     u_n_1( 0.0 ),
383     desiredTs( 0.0 ),
384     elapsedTime( 0.0 )
385 {
386   parseNode(node);
387 }
388
389 bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
390 {
391   if (aName == "Ts") {
392     desiredTs = aNode->getDoubleValue();
393   } else if (aName == "Kp") {
394     Kp.push_back( new FGXMLAutoInput(aNode) );
395   } else if (aName == "Ti") {
396     Ti.push_back( new FGXMLAutoInput(aNode) );
397   } else if (aName == "Td") {
398     Td.push_back( new FGXMLAutoInput(aNode) );
399   } else if (aName == "beta") {
400     beta = aNode->getDoubleValue();
401   } else if (aName == "alpha") {
402     alpha = aNode->getDoubleValue();
403   } else if (aName == "gamma") {
404     gamma = aNode->getDoubleValue();
405   } else {
406     // unhandled by us, let the base class try it
407     return false;
408   }
409
410   return true;
411 }
412
413 /*
414  * Roy Vegard Ovesen:
415  *
416  * Ok! Here is the PID controller algorithm that I would like to see
417  * implemented:
418  *
419  *   delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
420  *               + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
421  *
422  *   u_n = u_n-1 + delta_u_n
423  *
424  * where:
425  *
426  * delta_u : The incremental output
427  * Kp      : Proportional gain
428  * ep      : Proportional error with reference weighing
429  *           ep = beta * r - y
430  *           where:
431  *           beta : Weighing factor
432  *           r    : Reference (setpoint)
433  *           y    : Process value, measured
434  * e       : Error
435  *           e = r - y
436  * Ts      : Sampling interval
437  * Ti      : Integrator time
438  * Td      : Derivator time
439  * edf     : Derivate error with reference weighing and filtering
440  *           edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
441  *           where:
442  *           Tf : Filter time
443  *           Tf = alpha * Td , where alpha usually is set to 0.1
444  *           ed : Unfiltered derivate error with reference weighing
445  *             ed = gamma * r - y
446  *             where:
447  *             gamma : Weighing factor
448  * 
449  * u       : absolute output
450  * 
451  * Index n means the n'th value.
452  * 
453  * 
454  * Inputs:
455  * enabled ,
456  * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
457  * Kp , Ti , Td , Ts (is the sampling time available?)
458  * u_min , u_max
459  * 
460  * Output:
461  * u_n
462  */
463
464 void FGPIDController::update( double dt ) {
465     double e_n;             // error
466     double edf_n;
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         double 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         double td = Td.get_value();
515         if ( td > 0.0 ) { // do we need to calcluate derivative error?
516
517           // Calculates derivate error:
518             double ed_n = gamma * r_n - y_n;
519             if ( debug ) cout << " ed_n = " << ed_n;
520
521             // Calculates filter time:
522             double Tf = alpha * td;
523             if ( debug ) cout << " Tf = " << Tf;
524
525             // Filters the derivate error:
526             edf_n = edf_n_1 / (Ts/Tf + 1)
527                 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
528             if ( debug ) cout << " edf_n = " << edf_n;
529         } else {
530             edf_n_2 = edf_n_1 = edf_n = 0.0;
531         }
532
533         // Calculates the incremental output:
534         double ti = Ti.get_value();
535         if ( ti > 0.0 ) {
536             delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
537                                + ((Ts/ti) * e_n)
538                                + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
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
549         // Integrator anti-windup logic:
550         if ( delta_u_n > (u_max - u_n_1) ) {
551             delta_u_n = u_max - u_n_1;
552             if ( debug ) cout << " max saturation " << endl;
553         } else if ( delta_u_n < (u_min - u_n_1) ) {
554             delta_u_n = u_min - u_n_1;
555             if ( debug ) cout << " min saturation " << endl;
556         }
557
558         // Calculates absolute output:
559         u_n = u_n_1 + delta_u_n;
560         if ( debug ) cout << "  output = " << u_n << endl;
561
562         // Updates indexed values;
563         u_n_1   = u_n;
564         ep_n_1  = ep_n;
565         edf_n_2 = edf_n_1;
566         edf_n_1 = edf_n;
567
568         set_output_value( u_n );
569     } else if ( !enabled ) {
570         ep_n_1 = 0.0;
571         edf_n_2 = edf_n_1 = edf_n = 0.0;
572     }
573 }
574
575
576 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
577     FGXMLAutoComponent(),
578     int_sum( 0.0 )
579 {
580   parseNode(node);
581 }
582
583 bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
584 {
585   if (aName == "Kp") {
586     Kp.push_back( new FGXMLAutoInput(aNode) );
587   } else if (aName == "Ki") {
588     Ki.push_back( new FGXMLAutoInput(aNode) );
589   } else {
590     // unhandled by us, let the base class try it
591     return false;
592   }
593
594   return true;
595 }
596
597 void FGPISimpleController::update( double dt ) {
598
599     if ( isPropertyEnabled() ) {
600         if ( !enabled ) {
601             // we have just been enabled, zero out int_sum
602             int_sum = 0.0;
603         }
604         enabled = true;
605     } else {
606         enabled = false;
607         do_feedback();
608     }
609
610     if ( enabled ) {
611         if ( debug ) cout << "Updating " << get_name() << endl;
612         double y_n = valueInput.get_value();
613         double r_n = referenceInput.get_value();
614                       
615         double error = r_n - y_n;
616         if ( debug ) cout << "input = " << y_n
617                           << " reference = " << r_n
618                           << " error = " << error
619                           << endl;
620
621         double prop_comp = clamp(error * Kp.get_value());
622         int_sum += error * Ki.get_value() * dt;
623
624
625         double output = prop_comp + int_sum;
626         double clamped_output = clamp( output );
627         if( output != clamped_output ) // anti-windup
628           int_sum = clamped_output - prop_comp;
629
630         if ( debug ) cout << "prop_comp = " << prop_comp
631                           << " int_sum = " << int_sum << endl;
632
633         set_output_value( clamped_output );
634         if ( debug ) cout << "output = " << clamped_output << endl;
635     }
636 }
637
638
639 FGPredictor::FGPredictor ( SGPropertyNode *node ):
640     FGXMLAutoComponent(),
641     average(0.0)
642 {
643   parseNode(node);
644 }
645
646 bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
647 {
648   if (aName == "seconds") {
649     seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
650   } else if (aName == "filter-gain") {
651     filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
652   } else {
653     return false;
654   }
655   
656   return true;
657 }
658
659 void FGPredictor::update( double dt ) {
660     /*
661        Simple moving average filter converts input value to predicted value "seconds".
662
663        Smoothing as described by Curt Olson:
664          gain would be valid in the range of 0 - 1.0
665          1.0 would mean no filtering.
666          0.0 would mean no input.
667          0.5 would mean (1 part past value + 1 part current value) / 2
668          0.1 would mean (9 parts past value + 1 part current value) / 10
669          0.25 would mean (3 parts past value + 1 part current value) / 4
670
671     */
672
673     double ivalue = valueInput.get_value();
674
675     if ( isPropertyEnabled() ) {
676         if ( !enabled ) {
677             // first time being enabled
678             last_value = ivalue;
679         }
680         enabled = true;
681     } else {
682         enabled = false;
683         do_feedback();
684     }
685
686     if ( enabled ) {
687
688         if ( dt > 0.0 ) {
689             double current = (ivalue - last_value)/dt; // calculate current error change (per second)
690             average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
691
692             // calculate output with filter gain adjustment
693             double output = ivalue + 
694                (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) + 
695                        filter_gain.get_value() * (current * seconds.get_value());
696             output = clamp( output );
697             set_output_value( output );
698         }
699         last_value = ivalue;
700     }
701 }
702
703
704 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
705     FGXMLAutoComponent(),
706     filterType(none)
707 {
708     parseNode(node);
709
710     output.resize(2, 0.0);
711     input.resize(samplesInput.get_value() + 1, 0.0);
712 }
713
714
715 bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
716 {
717   if (aName == "type" ) {
718     string val(aNode->getStringValue());
719     if ( val == "exponential" ) {
720       filterType = exponential;
721     } else if (val == "double-exponential") {
722       filterType = doubleExponential;
723     } else if (val == "moving-average") {
724       filterType = movingAverage;
725     } else if (val == "noise-spike") {
726       filterType = noiseSpike;
727     } else if (val == "gain") {
728       filterType = gain;
729     } else if (val == "reciprocal") {
730       filterType = reciprocal;
731     } else if (val == "differential") {
732       filterType = differential;
733       // use a constant of two samples for current and previous input value
734       samplesInput.push_back( new FGXMLAutoInput(NULL, 2.0 ) ); 
735     }
736   } else if (aName == "filter-time" ) {
737     TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
738     if( filterType == none ) filterType = exponential;
739   } else if (aName == "samples" ) {
740     samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
741     if( filterType == none ) filterType = movingAverage;
742   } else if (aName == "max-rate-of-change" ) {
743     rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
744     if( filterType == none ) filterType = noiseSpike;
745   } else if (aName == "gain" ) {
746     gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
747     if( filterType == none ) filterType = gain;
748   } else {
749     return false; // not handled by us, let the base class try
750   }
751   
752   return true;
753 }
754
755 void FGDigitalFilter::update(double dt)
756 {
757     if ( isPropertyEnabled() ) {
758
759         input.push_front(valueInput.get_value()-referenceInput.get_value());
760         input.resize(samplesInput.get_value() + 1, 0.0);
761
762         if ( !enabled ) {
763             // first time being enabled, initialize output to the
764             // value of the output property to avoid bumping.
765             output.push_front(get_output_value());
766         }
767
768         enabled = true;
769     } else {
770         enabled = false;
771         do_feedback();
772     }
773
774     if ( !enabled || dt < SGLimitsd::min() ) 
775         return;
776
777     /*
778      * Exponential filter
779      *
780      * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
781      *
782      */
783      if( debug ) cout << "Updating " << get_name()
784                       << " dt " << dt << endl;
785
786     if (filterType == exponential)
787     {
788         double alpha = 1 / ((TfInput.get_value()/dt) + 1);
789         output.push_front(alpha * input[0] + 
790                           (1 - alpha) * output[0]);
791     } 
792     else if (filterType == doubleExponential)
793     {
794         double alpha = 1 / ((TfInput.get_value()/dt) + 1);
795         output.push_front(alpha * alpha * input[0] + 
796                           2 * (1 - alpha) * output[0] -
797                           (1 - alpha) * (1 - alpha) * output[1]);
798     }
799     else if (filterType == movingAverage)
800     {
801         output.push_front(output[0] + 
802                           (input[0] - input.back()) / samplesInput.get_value());
803     }
804     else if (filterType == noiseSpike)
805     {
806         double maxChange = rateOfChangeInput.get_value() * dt;
807
808         if ((output[0] - input[0]) > maxChange)
809         {
810             output.push_front(output[0] - maxChange);
811         }
812         else if ((output[0] - input[0]) < -maxChange)
813         {
814             output.push_front(output[0] + maxChange);
815         }
816         else if (fabs(input[0] - output[0]) <= maxChange)
817         {
818             output.push_front(input[0]);
819         }
820     }
821     else if (filterType == gain)
822     {
823         output[0] = gainInput.get_value() * input[0];
824     }
825     else if (filterType == reciprocal)
826     {
827         if (input[0] != 0.0) {
828             output[0] = gainInput.get_value() / input[0];
829         }
830     }
831     else if (filterType == differential)
832     {
833         if( dt > SGLimitsd::min() ) {
834             output[0] = (input[0]-input[1]) * TfInput.get_value() / dt;
835         }
836     }
837
838     output[0] = clamp(output[0]) ;
839     set_output_value( output[0] );
840
841     output.resize(2);
842
843     if (debug)
844     {
845         cout << "input:" << input[0] 
846              << "\toutput:" << output[0] << endl;
847     }
848 }
849
850 FGXMLAutoLogic::FGXMLAutoLogic(SGPropertyNode * node ) :
851     FGXMLAutoComponent(),
852     inverted(false)
853 {
854     parseNode(node);
855 }
856
857 bool FGXMLAutoLogic::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
858 {
859     if (aName == "input") {
860         input = sgReadCondition( fgGetNode("/"), aNode );
861     } else if (aName == "inverted") {
862         inverted = aNode->getBoolValue();
863     } else {
864         return false;
865     }
866   
867     return true;
868 }
869
870 void FGXMLAutoLogic::update(double dt)
871 {
872     if ( isPropertyEnabled() ) {
873         if ( !enabled ) {
874             // we have just been enabled
875         }
876         enabled = true;
877     } else {
878         enabled = false;
879         do_feedback();
880     }
881
882     if ( !enabled || dt < SGLimitsd::min() ) 
883         return;
884
885     if( input == NULL ) {
886         if ( debug ) cout << "No input for " << get_name() << endl;
887         return;
888     }
889
890     bool i = input->test();
891
892     if ( debug ) cout << "Updating " << get_name() << ": " << (inverted ? !i : i) << endl;
893
894     set_output_value( i );
895 }
896
897 class FGXMLAutoRSFlipFlop : public FGXMLAutoFlipFlop {
898 public:
899   FGXMLAutoRSFlipFlop( SGPropertyNode * node ) :
900     FGXMLAutoFlipFlop( node ) {}
901
902   void updateState( double dt ) {
903
904     if( sInput == NULL ) {
905         if ( debug ) cout << "No set (S) input for " << get_name() << endl;
906         return;
907     }
908
909     if( rInput == NULL ) {
910         if ( debug ) cout << "No reset (R) input for " << get_name() << endl;
911         return;
912     }
913
914     bool s = sInput->test();
915     bool r = rInput->test();
916
917     // s == false && q == false: no change, keep state
918     if( s || r ) {
919       bool q = false;
920       if( s ) q = true; // set
921       if( r ) q = false; // reset
922       // s && q: race condition. we let r win
923       if( inverted ) q = !q;
924
925       if ( debug ) cout << "Updating " << get_name() << ":" 
926         << " s=" << s
927         << ",r=" << r
928         << ",q=" << q << endl;
929       set_output_value( q );
930     } else {
931       if ( debug ) cout << "Updating " << get_name() << ":" 
932         << " s=" << s
933         << ",r=" << r
934         << ",q=unchanged" << endl;
935     }
936   }
937 };
938
939 class FGXMLAutoJKFlipFlop : public FGXMLAutoFlipFlop {
940 private: 
941   bool clock;
942 public:
943   FGXMLAutoJKFlipFlop( SGPropertyNode * node ) :
944     FGXMLAutoFlipFlop( node ), 
945     clock(false) {}
946
947   void updateState( double dt ) {
948
949     if( jInput == NULL ) {
950         if ( debug ) cout << "No set (j) input for " << get_name() << endl;
951         return;
952     }
953
954     if( kInput == NULL ) {
955         if ( debug ) cout << "No reset (k) input for " << get_name() << endl;
956         return;
957     }
958
959     bool j = jInput->test();
960     bool k = kInput->test();
961     /*
962       if the user provided a clock input, use it. 
963       Otherwise use framerate as clock
964       This JK operates on the raising edge. 
965     */
966     bool c = clockInput ? clockInput->test() : false;
967     bool raisingEdge = clockInput ? (c && !clock) : true;
968     clock = c;
969
970     if( !raisingEdge ) return;
971     
972     bool q = get_bool_output_value();
973     // j == false && k == false: no change, keep state
974     if( (j || k) ) {
975       if( j && k ) {
976         q = !q; // toggle
977       } else {
978         if( j ) q = true; // set
979         if( k ) q = false; // reset
980       }
981       if( inverted ) q = !q;
982
983       if ( debug ) cout << "Updating " << get_name() << ":" 
984         << " j=" << j
985         << ",k=" << k
986         << ",q=" << q << endl;
987       set_output_value( q );
988     } else {
989       if ( debug ) cout << "Updating " << get_name() << ":" 
990         << " j=" << j
991         << ",k=" << k
992         << ",q=unchanged" << endl;
993     }
994   }
995 };
996
997 class FGXMLAutoDFlipFlop : public FGXMLAutoFlipFlop {
998 private: 
999   bool clock;
1000 public:
1001   FGXMLAutoDFlipFlop( SGPropertyNode * node ) :
1002     FGXMLAutoFlipFlop( node ), 
1003     clock(false) {}
1004
1005   void updateState( double dt ) {
1006
1007     if( clockInput == NULL ) {
1008         if ( debug ) cout << "No (clock) input for " << get_name() << endl;
1009         return;
1010     }
1011
1012     if( dInput == NULL ) {
1013         if ( debug ) cout << "No (D) input for " << get_name() << endl;
1014         return;
1015     }
1016
1017     bool d = dInput->test();
1018
1019     // check the clock - raising edge
1020     bool c = clockInput->test();
1021     bool raisingEdge = c && !clock;
1022     clock = c;
1023
1024     if( raisingEdge ) {
1025       bool q = d;
1026       if( inverted ) q = !q;
1027
1028       if ( debug ) cout << "Updating " << get_name() << ":" 
1029         << " d=" << d
1030         << ",q=" << q << endl;
1031       set_output_value( q );
1032     } else {
1033       if ( debug ) cout << "Updating " << get_name() << ":" 
1034         << " d=" << d
1035         << ",q=unchanged" << endl;
1036     }
1037   }
1038 };
1039
1040 class FGXMLAutoTFlipFlop : public FGXMLAutoFlipFlop {
1041 private: 
1042   bool clock;
1043 public:
1044   FGXMLAutoTFlipFlop( SGPropertyNode * node ) :
1045     FGXMLAutoFlipFlop( node ), 
1046     clock(false) {}
1047
1048   void updateState( double dt ) {
1049
1050     if( clockInput == NULL ) {
1051         if ( debug ) cout << "No (clock) input for " << get_name() << endl;
1052         return;
1053     }
1054
1055     // check the clock - raising edge
1056     bool c = clockInput->test();
1057     bool raisingEdge = c && !clock;
1058     clock = c;
1059
1060     if( raisingEdge ) {
1061       bool q = !get_bool_output_value(); // toggle
1062       if( inverted ) q = !q; // doesnt really make sense for a T-FF
1063
1064       if ( debug ) cout << "Updating " << get_name() << ":" 
1065         << ",q=" << q << endl;
1066       set_output_value( q );
1067     } else {
1068       if ( debug ) cout << "Updating " << get_name() << ":" 
1069         << ",q=unchanged" << endl;
1070     }
1071   }
1072 };
1073
1074 FGXMLAutoFlipFlop::FGXMLAutoFlipFlop(SGPropertyNode * node ) :
1075     FGXMLAutoComponent(),
1076     inverted(false)
1077 {
1078     parseNode(node);
1079 }
1080
1081 bool FGXMLAutoFlipFlop::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
1082 {
1083     if (aName == "set"||aName == "S") {
1084         sInput = sgReadCondition( fgGetNode("/"), aNode );
1085     } else if (aName == "reset" || aName == "R" ) {
1086         rInput = sgReadCondition( fgGetNode("/"), aNode );
1087     } else if (aName == "J") {
1088         jInput = sgReadCondition( fgGetNode("/"), aNode );
1089     } else if (aName == "K") {
1090         kInput = sgReadCondition( fgGetNode("/"), aNode );
1091     } else if (aName == "T") {
1092         tInput = sgReadCondition( fgGetNode("/"), aNode );
1093     } else if (aName == "D") {
1094         dInput = sgReadCondition( fgGetNode("/"), aNode );
1095     } else if (aName == "clock") {
1096         clockInput = sgReadCondition( fgGetNode("/"), aNode );
1097     } else if (aName == "inverted") {
1098         inverted = aNode->getBoolValue();
1099     } else if (aName == "type") {
1100         // ignore element type, evaluated by loader
1101     } else {
1102         return false;
1103     }
1104   
1105     return true;
1106 }
1107
1108 void FGXMLAutoFlipFlop::update(double dt)
1109 {
1110     if ( isPropertyEnabled() ) {
1111         if ( !enabled ) {
1112             // we have just been enabled
1113             // initialize to a bool property
1114             set_output_value( get_bool_output_value() );
1115         }
1116         enabled = true;
1117     } else {
1118         enabled = false;
1119         do_feedback();
1120     }
1121
1122     if ( !enabled || dt < SGLimitsd::min() ) 
1123         return;
1124
1125     updateState( dt );
1126 }
1127
1128
1129 FGXMLAutopilotGroup::FGXMLAutopilotGroup() :
1130   SGSubsystemGroup()
1131 #ifdef XMLAUTO_USEHELPER
1132   ,average(0.0), // average/filtered prediction
1133   v_last(0.0),  // last velocity
1134   last_static_pressure(0.0),
1135   vel(fgGetNode( "/velocities/airspeed-kt", true )),
1136   // Estimate speed in 5,10 seconds
1137   lookahead5(fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true )),
1138   lookahead10(fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true )),
1139   bug(fgGetNode( "/autopilot/settings/heading-bug-deg", true )),
1140   mag_hdg(fgGetNode( "/orientation/heading-magnetic-deg", true )),
1141   bug_error(fgGetNode( "/autopilot/internal/heading-bug-error-deg", true )),
1142   fdm_bug_error(fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true )),
1143   target_true(fgGetNode( "/autopilot/settings/true-heading-deg", true )),
1144   true_hdg(fgGetNode( "/orientation/heading-deg", true )),
1145   true_error(fgGetNode( "/autopilot/internal/true-heading-error-deg", true )),
1146   target_nav1(fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true )),
1147   true_nav1(fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true )),
1148   true_track_nav1(fgGetNode( "/autopilot/internal/nav1-track-error-deg", true )),
1149   nav1_course_error(fgGetNode( "/autopilot/internal/nav1-course-error", true )),
1150   nav1_selected_course(fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true )),
1151   vs_fps(fgGetNode( "/velocities/vertical-speed-fps", true )),
1152   vs_fpm(fgGetNode( "/autopilot/internal/vert-speed-fpm", true )),
1153   static_pressure(fgGetNode( "/systems/static[0]/pressure-inhg", true )),
1154   pressure_rate(fgGetNode( "/autopilot/internal/pressure-rate", true )),
1155   track(fgGetNode( "/orientation/track-deg", true ))
1156 #endif
1157 {
1158 }
1159
1160 void FGXMLAutopilotGroup::update( double dt )
1161 {
1162     // update all configured autopilots
1163     SGSubsystemGroup::update( dt );
1164 #ifdef XMLAUTO_USEHELPER
1165     // update helper values
1166     double v = vel->getDoubleValue();
1167     double a = 0.0;
1168     if ( dt > 0.0 ) {
1169         a = (v - v_last) / dt;
1170
1171         if ( dt < 1.0 ) {
1172             average = (1.0 - dt) * average + dt * a;
1173         } else {
1174             average = a;
1175         }
1176
1177         lookahead5->setDoubleValue( v + average * 5.0 );
1178         lookahead10->setDoubleValue( v + average * 10.0 );
1179         v_last = v;
1180     }
1181
1182     // Calculate heading bug error normalized to +/- 180.0
1183     double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
1184     SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1185     bug_error->setDoubleValue( diff );
1186
1187     fdm_bug_error->setDoubleValue( diff );
1188
1189     // Calculate true heading error normalized to +/- 180.0
1190     diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
1191     SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1192     true_error->setDoubleValue( diff );
1193
1194     // Calculate nav1 target heading error normalized to +/- 180.0
1195     diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
1196     SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1197     true_nav1->setDoubleValue( diff );
1198
1199     // Calculate true groundtrack
1200     diff = target_nav1->getDoubleValue() - track->getDoubleValue();
1201     SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1202     true_track_nav1->setDoubleValue( diff );
1203
1204     // Calculate nav1 selected course error normalized to +/- 180.0
1205     diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
1206     SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
1207     nav1_course_error->setDoubleValue( diff );
1208
1209     // Calculate vertical speed in fpm
1210     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
1211
1212
1213     // Calculate static port pressure rate in [inhg/s].
1214     // Used to determine vertical speed.
1215     if ( dt > 0.0 ) {
1216         double current_static_pressure = static_pressure->getDoubleValue();
1217         double current_pressure_rate = 
1218             ( current_static_pressure - last_static_pressure ) / dt;
1219
1220         pressure_rate->setDoubleValue(current_pressure_rate);
1221         last_static_pressure = current_static_pressure;
1222     }
1223 #endif
1224 }
1225
1226 void FGXMLAutopilotGroup::reinit()
1227 {
1228     for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
1229       FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
1230       if( ap == NULL ) continue; // ?
1231       remove_subsystem( _autopilotNames[i] );
1232       delete ap;
1233     }
1234     _autopilotNames.clear();
1235     init();
1236 }
1237
1238 void FGXMLAutopilotGroup::init()
1239 {
1240     PropertyList autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
1241     if( autopilotNodes.size() == 0 ) {
1242         SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
1243         return;
1244     }
1245
1246     for( PropertyList::size_type i = 0; i < autopilotNodes.size(); i++ ) {
1247         SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
1248         if( pathNode == NULL ) {
1249             SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
1250             continue;
1251         }
1252
1253         string apName;
1254         SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
1255         if( nameNode != NULL ) {
1256             apName = nameNode->getStringValue();
1257         } else {
1258           std::ostringstream buf;
1259           buf <<  "unnamed_autopilot_" << i;
1260           apName = buf.str();
1261         }
1262
1263         if( get_subsystem( apName.c_str() ) != NULL ) {
1264             SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
1265             continue;
1266         }
1267
1268         SGPath config( globals->get_fg_root() );
1269         config.append( pathNode->getStringValue() );
1270
1271         SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
1272         // FGXMLAutopilot
1273         FGXMLAutopilot * ap = new FGXMLAutopilot;
1274         try {
1275             SGPropertyNode_ptr root = new SGPropertyNode();
1276             readProperties( config.str(), root );
1277
1278
1279             if ( ! ap->build( root ) ) {
1280                 SG_LOG( SG_ALL, SG_ALERT,
1281                   "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
1282                 delete ap;
1283                 continue;
1284             }        
1285         } catch (const sg_exception& e) {
1286             SG_LOG( SG_AUTOPILOT, SG_ALERT, "Failed to load autopilot configuration: "
1287                     << config.str() << ":" << e.getMessage() );
1288             delete ap;
1289             continue;
1290         }
1291
1292         SG_LOG( SG_AUTOPILOT, SG_INFO, "adding  autopilot subsystem " << apName );
1293         set_subsystem( apName, ap );
1294         _autopilotNames.push_back( apName );
1295     }
1296
1297     SGSubsystemGroup::init();
1298 }
1299
1300 FGXMLAutopilot::FGXMLAutopilot() {
1301 }
1302
1303
1304 FGXMLAutopilot::~FGXMLAutopilot() {
1305 }
1306
1307  
1308 /* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
1309  * and configure/add the digital filters specified in that file
1310  */
1311 void FGXMLAutopilot::init() 
1312 {
1313 }
1314
1315
1316 void FGXMLAutopilot::reinit() {
1317     components.clear();
1318     init();
1319 }
1320
1321
1322 void FGXMLAutopilot::bind() {
1323 }
1324
1325 void FGXMLAutopilot::unbind() {
1326 }
1327
1328 bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
1329     SGPropertyNode *node;
1330     int i;
1331
1332     int count = config_props->nChildren();
1333     for ( i = 0; i < count; ++i ) {
1334         node = config_props->getChild(i);
1335         string name = node->getName();
1336         // cout << name << endl;
1337         SG_LOG( SG_AUTOPILOT, SG_BULK, "adding  autopilot component " << name );
1338         if ( name == "pid-controller" ) {
1339             components.push_back( new FGPIDController( node ) );
1340         } else if ( name == "pi-simple-controller" ) {
1341             components.push_back( new FGPISimpleController( node ) );
1342         } else if ( name == "predict-simple" ) {
1343             components.push_back( new FGPredictor( node ) );
1344         } else if ( name == "filter" ) {
1345             components.push_back( new FGDigitalFilter( node ) );
1346         } else if ( name == "logic" ) {
1347             components.push_back( new FGXMLAutoLogic( node ) );
1348         } else if ( name == "flipflop" ) {
1349             FGXMLAutoFlipFlop * flipFlop = NULL;
1350             SGPropertyNode_ptr typeNode = node->getNode( "type" );            
1351             string val;
1352             if( typeNode != NULL ) val = typeNode->getStringValue();
1353             val = simgear::strutils::strip(val);
1354             if( val == "RS" || val =="SR" ) flipFlop      = new FGXMLAutoRSFlipFlop( node );
1355             else if( val == "JK" ) flipFlop = new FGXMLAutoJKFlipFlop( node );
1356             else if( val == "T" ) flipFlop  = new FGXMLAutoTFlipFlop( node );
1357             else if( val == "D" ) flipFlop  = new FGXMLAutoDFlipFlop( node );
1358             if( flipFlop == NULL ) {
1359               SG_LOG(SG_AUTOPILOT, SG_ALERT, "can't create flipflop of type: " << val);
1360               return false;
1361             }
1362             components.push_back( flipFlop );
1363         } else {
1364             SG_LOG( SG_AUTOPILOT, SG_WARN, "Unknown top level autopilot section: " << name );
1365 //            return false;
1366         }
1367     }
1368
1369     return true;
1370 }
1371
1372 /*
1373  * Update the list of autopilot components
1374  */
1375
1376 void FGXMLAutopilot::update( double dt ) 
1377 {
1378     unsigned int i;
1379     for ( i = 0; i < components.size(); ++i ) {
1380         components[i]->update( dt );
1381     }
1382 }
1383