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