]> git.mxchange.org Git - flightgear.git/blobdiff - src/Autopilot/xmlauto.cxx
Autopilot: clean up the helpers code (which drives the various /internal/) properties...
[flightgear.git] / src / Autopilot / xmlauto.cxx
index 7cc108ce2c899cb5a5598144c2473ba6af7cdeec..ff149a99c0c04daba89b25662ae54088bee08f9d 100644 (file)
 #  include <config.h>
 #endif
 
+#include <iostream>
+
 #include <simgear/structure/exception.hxx>
 #include <simgear/misc/sg_path.hxx>
 #include <simgear/sg_inlines.h>
+#include <simgear/props/props_io.hxx>
 
 #include <Main/fg_props.hxx>
 #include <Main/globals.hxx>
 
 #include "xmlauto.hxx"
 
+using std::cout;
+using std::endl;
 
-FGPIDController::FGPIDController( SGPropertyNode *node ):
-    debug( false ),
-    y_n( 0.0 ),
-    r_n( 0.0 ),
-    y_scale( 1.0 ),
-    r_scale( 1.0 ),
-    y_offset( 0.0 ),
-    r_offset( 0.0 ),
-    Kp( 0.0 ),
-    alpha( 0.1 ),
-    beta( 1.0 ),
-    gamma( 0.0 ),
-    Ti( 0.0 ),
-    Td( 0.0 ),
-    u_min( 0.0 ),
-    u_max( 0.0 ),
-    ep_n_1( 0.0 ),
-    edf_n_1( 0.0 ),
-    edf_n_2( 0.0 ),
-    u_n_1( 0.0 ),
-    desiredTs( 0.0 ),
-    elapsedTime( 0.0 )
+FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
 {
-    int i;
-    for ( i = 0; i < node->nChildren(); ++i ) {
-        SGPropertyNode *child = node->getChild(i);
-        string cname = child->getName();
-        string cval = child->getStringValue();
-        if ( cname == "name" ) {
-            name = cval;
-        } else if ( cname == "debug" ) {
-            debug = child->getBoolValue();
-        } else if ( cname == "enable" ) {
-            // cout << "parsing enable" << endl;
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                // cout << "prop = " << prop->getStringValue() << endl;
-                enable_prop = fgGetNode( prop->getStringValue(), true );
-            } else {
-                // cout << "no prop child" << endl;
-            }
-            SGPropertyNode *val = child->getChild( "value" );
-            if ( val != NULL ) {
-                enable_value = val->getStringValue();
-            }
-            SGPropertyNode *pass = child->getChild( "honor-passive" );
-            if ( pass != NULL ) {
-                honor_passive = pass->getBoolValue();
-            }
-        } else if ( cname == "input" ) {
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                input_prop = fgGetNode( prop->getStringValue(), true );
-            }
-            prop = child->getChild( "scale" );
-            if ( prop != NULL ) {
-                y_scale = prop->getDoubleValue();
-            }
-            prop = child->getChild( "offset" );
-            if ( prop != NULL ) {
-                y_offset = prop->getDoubleValue();
-            }
-        } else if ( cname == "reference" ) {
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                r_n_prop = fgGetNode( prop->getStringValue(), true );
-            } else {
-                prop = child->getChild( "value" );
-                if ( prop != NULL ) {
-                    r_n_value = prop->getDoubleValue();
-                }
-            }
-            prop = child->getChild( "scale" );
-            if ( prop != NULL ) {
-                r_scale = prop->getDoubleValue();
-            }
-            prop = child->getChild( "offset" );
-            if ( prop != NULL ) {
-                r_offset = prop->getDoubleValue();
-            }
-        } else if ( cname == "output" ) {
-            int i = 0;
-            SGPropertyNode *prop;
-            while ( (prop = child->getChild("prop", i)) != NULL ) {
-                SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
-                output_list.push_back( tmp );
-                i++;
-            }
-        } else if ( cname == "config" ) {
-            SGPropertyNode *config;
+  SGPropertyNode_ptr minNode = root->getChild( "min" );
+  SGPropertyNode_ptr maxNode = root->getChild( "max" );
+  if( minNode == NULL || maxNode == NULL ) {
+    SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
+  } else {
+    minPeriod = new FGXMLAutoInput( minNode );
+    maxPeriod = new FGXMLAutoInput( maxNode );
+  }
+}
 
-            config = child->getChild( "Ts" );
-            if ( config != NULL ) {
-                desiredTs = config->getDoubleValue();
-            }
-            
-            config = child->getChild( "Kp" );
-            if ( config != NULL ) {
-                SGPropertyNode *val = config->getChild( "value" );
-                if ( val != NULL ) {
-                    Kp = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop = config->getChild( "prop" );
-                if ( prop != NULL ) {
-                    Kp_prop = fgGetNode( prop->getStringValue(), true );
-                    if ( val != NULL ) {
-                        Kp_prop->setDoubleValue(Kp);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop == NULL) {
-                    Kp = config->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Kp config. Please use <prop> and/or <value> tags." );
-                    if ( name.length() ) {
-                        SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-                    }
-                }
-            }
+double FGPeriodicalValue::normalize( double value )
+{
+  if( !(minPeriod && maxPeriod )) return value;
 
-            config = child->getChild( "beta" );
-            if ( config != NULL ) {
-                beta = config->getDoubleValue();
-            }
+  double p1 = minPeriod->get_value();
+  double p2 = maxPeriod->get_value();
 
-            config = child->getChild( "alpha" );
-            if ( config != NULL ) {
-                alpha = config->getDoubleValue();
-            }
+  double min = std::min<double>(p1,p2);
+  double max = std::max<double>(p1,p2);
+  double phase = fabs(max - min);
 
-            config = child->getChild( "gamma" );
-            if ( config != NULL ) {
-                gamma = config->getDoubleValue();
-            }
+  if( phase > SGLimitsd::min() ) {
+    while( value < min ) value += phase;
+    while( value > max ) value -= phase;
+  } else {
+    value = min; // phase is zero
+  }
 
-            config = child->getChild( "Ti" );
-            if ( config != NULL ) {
-                SGPropertyNode *val = config->getChild( "value" );
-                if ( val != NULL ) {
-                    Ti = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop = config->getChild( "prop" );
-                if ( prop != NULL ) {
-                    Ti_prop = fgGetNode( prop->getStringValue(), true );
-                    if ( val != NULL ) {
-                        Ti_prop->setDoubleValue(Kp);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop == NULL) {
-                Ti = config->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Ti config. Please use <prop> and/or <value> tags." );
-                    if ( name.length() ) {
-                        SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-                    }
-                }
-            }
+  return value;
+}
 
-            config = child->getChild( "Td" );
-            if ( config != NULL ) {
-                SGPropertyNode *val = config->getChild( "value" );
-                if ( val != NULL ) {
-                    Td = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop = config->getChild( "prop" );
-                if ( prop != NULL ) {
-                    Td_prop = fgGetNode( prop->getStringValue(), true );
-                    if ( val != NULL ) {
-                        Td_prop->setDoubleValue(Kp);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop == NULL) {
-                Td = config->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Td config. Please use <prop> and/or <value> tags." );
-                    if ( name.length() ) {
-                        SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-                    }
-                }
-            }
+FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
+  value(0.0),
+  abs(false),
+  _condition(NULL) 
+{
+  parse( node, value, offset, scale );
+}
 
-            config = child->getChild( "u_min" );
-            if ( config != NULL ) {
-                SGPropertyNode *val = config->getChild( "value" );
-                if ( val != NULL ) {
-                    u_min = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop = config->getChild( "prop" );
-                if ( prop != NULL ) {
-                    umin_prop = fgGetNode( prop->getStringValue(), true );
-                    if ( val != NULL ) {
-                        umin_prop->setDoubleValue(u_min);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop == NULL) {
-                u_min = config->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_min config. Please use <prop> and/or <value> tags." );
-                    if ( name.length() ) {
-                        SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-                    }
-                }
-            }
 
-            config = child->getChild( "u_max" );
-            if ( config != NULL ) {
-                SGPropertyNode *val = config->getChild( "value" );
-                if ( val != NULL ) {
-                    u_max = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop = config->getChild( "prop" );
-                if ( prop != NULL ) {
-                    umax_prop = fgGetNode( prop->getStringValue(), true );
-                    if ( val != NULL ) {
-                        umax_prop->setDoubleValue(u_max);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop == NULL) {
-                u_max = config->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_max config. Please use <prop> and/or <value> tags." );
-                    if ( name.length() ) {
-                        SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-                    }
-                }
-            }
+void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
+{
+    value = aValue;
+    property = NULL; 
+    offset = NULL;
+    scale = NULL;
+    min = NULL;
+    max = NULL;
+    periodical = NULL;
+
+    if( node == NULL )
+        return;
+
+    SGPropertyNode * n;
+
+    if( (n = node->getChild("condition")) != NULL ) {
+        _condition = sgReadCondition(fgGetNode("/"), n);
+    }
+
+    if( (n = node->getChild( "scale" )) != NULL ) {
+        scale = new FGXMLAutoInput( n, aScale );
+    }
+
+    if( (n = node->getChild( "offset" )) != NULL ) {
+        offset = new FGXMLAutoInput( n, aOffset );
+    }
+
+    if( (n = node->getChild( "max" )) != NULL ) {
+        max = new FGXMLAutoInput( n );
+    }
+
+    if( (n = node->getChild( "min" )) != NULL ) {
+        min = new FGXMLAutoInput( n );
+    }
+
+    if( (n = node->getChild( "abs" )) != NULL ) {
+      abs = n->getBoolValue();
+    }
+
+    if( (n = node->getChild( "period" )) != NULL ) {
+      periodical = new FGPeriodicalValue( n );
+    }
+
+    SGPropertyNode *valueNode = node->getChild( "value" );
+    if ( valueNode != NULL ) {
+        value = valueNode->getDoubleValue();
+    }
+
+    n = node->getChild( "property" );
+    // if no <property> element, check for <prop> element for backwards
+    // compatibility
+    if(  n == NULL )
+        n = node->getChild( "prop" );
+
+    if (  n != NULL ) {
+        property = fgGetNode(  n->getStringValue(), true );
+        if ( valueNode != NULL ) {
+            // initialize property with given value 
+            // if both <prop> and <value> exist
+            double s = get_scale();
+            if( s != 0 )
+              property->setDoubleValue( (value - get_offset())/s );
+            else
+              property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
+        }
+    }
+
+    if ( n == NULL && valueNode == NULL ) {
+        // no <value> element and no <prop> element, use text node 
+        const char * textnode = node->getStringValue();
+        char * endp = NULL;
+        // try to convert to a double value. If the textnode does not start with a number
+        // endp will point to the beginning of the string. We assume this should be
+        // a property name
+        value = strtod( textnode, &endp );
+        if( endp == textnode ) {
+          property = fgGetNode( textnode, true );
+        }
+    }
+}
+
+void FGXMLAutoInput::set_value( double aValue ) 
+{
+    double s = get_scale();
+    if( s != 0 )
+        property->setDoubleValue( (aValue - get_offset())/s );
+    else
+        property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
+}
+
+double FGXMLAutoInput::get_value() 
+{
+    if( property != NULL ) 
+        value = property->getDoubleValue();
+
+    if( scale ) 
+        value *= scale->get_value();
+
+    if( offset ) 
+        value += offset->get_value();
+
+    if( min ) {
+        double m = min->get_value();
+        if( value < m )
+            value = m;
+    }
+
+    if( max ) {
+        double m = max->get_value();
+        if( value > m )
+            value = m;
+    }
+
+    if( periodical ) {
+      value = periodical->normalize( value );
+    }
+    
+    return abs ? fabs(value) : value;
+}
+
+FGXMLAutoComponent::FGXMLAutoComponent() :
+      _condition( NULL ),
+      enable_prop( NULL ),
+      enable_value( NULL ),
+      passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
+      honor_passive( false ),
+      name(""),
+      feedback_if_disabled( false ),
+      debug(false),
+      enabled( false )
+{
+}
+
+FGXMLAutoComponent::~FGXMLAutoComponent() 
+{
+    delete enable_value;
+}
+
+void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
+{
+  SGPropertyNode *prop; 
+  for (int i = 0; i < aNode->nChildren(); ++i ) {
+    SGPropertyNode *child = aNode->getChild(i);
+    string cname(child->getName());
+    
+    if (parseNodeHook(cname, child)) {
+      // derived class handled it, fine
+    } else if ( cname == "name" ) {
+      name = child->getStringValue();
+    } else if ( cname == "feedback-if-disabled" ) {
+      feedback_if_disabled = child->getBoolValue();
+    } else if ( cname == "debug" ) {
+      debug = child->getBoolValue();
+    } else if ( cname == "enable" ) {
+      if( (prop = child->getChild("condition")) != NULL ) {
+        _condition = sgReadCondition(fgGetNode("/"), prop);
+      } else {
+         if ( (prop = child->getChild( "prop" )) != NULL ) {
+             enable_prop = fgGetNode( prop->getStringValue(), true );
+         }
+
+         if ( (prop = child->getChild( "value" )) != NULL ) {
+             delete enable_value;
+             enable_value = new string(prop->getStringValue());
+         }
+      }
+      if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
+          honor_passive = prop->getBoolValue();
+      }
+    } else if ( cname == "input" ) {
+      valueInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "reference" ) {
+      referenceInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "output" ) {
+      // grab all <prop> and <property> childs
+      int found = 0;
+      // backwards compatibility: allow <prop> elements
+      for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) { 
+          SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
+          output_list.push_back( tmp );
+          found++;
+      }
+      for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) { 
+          SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
+          output_list.push_back( tmp );
+          found++;
+      }
+
+      // no <prop> elements, text node of <output> is property name
+      if( found == 0 )
+          output_list.push_back( fgGetNode(child->getStringValue(), true ) );
+    } else if ( cname == "config" ) {
+      parseConfig(child);
+    } else if ( cname == "min" ) {
+        uminInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "u_min" ) {
+        uminInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "max" ) {
+        umaxInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "u_max" ) {
+        umaxInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "period" ) {
+      periodical = new FGPeriodicalValue( child );
+    } else {
+      SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:" 
+        << cname << " in section " << name);
+      throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
+    }
+  } // of top-level iteration
+}
+
+void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
+{
+  for (int i = 0; i < aConfig->nChildren(); ++i ) {
+    SGPropertyNode *child = aConfig->getChild(i);
+    string cname(child->getName());
+    
+    if (parseConfigHook(cname, child)) {
+      // derived class handled it, fine
+    } else if ( cname == "min" ) {
+        uminInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "u_min" ) {
+        uminInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "max" ) {
+        umaxInput.push_back( new FGXMLAutoInput( child ) );
+    } else if ( cname == "u_max" ) {
+        umaxInput.push_back( new FGXMLAutoInput( child ) );
+    } else {
+      SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:" 
+        << cname << " in section " << name);
+      throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
+    }
+  } // of config iteration
+}
+
+bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
+{
+  return false;
+}
+
+bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
+{
+  return false;
+}
+
+bool FGXMLAutoComponent::isPropertyEnabled()
+{
+    if( _condition )
+        return _condition->test();
+
+    if( enable_prop ) {
+        if( enable_value ) {
+            return *enable_value == enable_prop->getStringValue();
         } else {
-            SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
-            if ( name.length() ) {
-                SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-            }
+            return enable_prop->getBoolValue();
         }
-    }   
+    }
+    return true;
+}
+
+void FGXMLAutoComponent::do_feedback_if_disabled()
+{
+    if( output_list.size() > 0 ) {    
+        FGXMLAutoInput * input = valueInput.get_active();
+        if( input != NULL )
+            input->set_value( output_list[0]->getDoubleValue() );
+    }
+}
+
+double FGXMLAutoComponent::clamp( double value )
+{
+    //If this is a periodical value, normalize it into our domain 
+    // before clamping
+    if( periodical )
+      value = periodical->normalize( value );
+
+    // clamp, if either min or max is defined
+    if( uminInput.size() + umaxInput.size() > 0 ) {
+        double d = umaxInput.get_value( 0.0 );
+        if( value > d ) value = d;
+        d = uminInput.get_value( 0.0 );
+        if( value < d ) value = d;
+    }
+    return value;
+}
+
+FGPIDController::FGPIDController( SGPropertyNode *node ):
+    FGXMLAutoComponent(),
+    alpha( 0.1 ),
+    beta( 1.0 ),
+    gamma( 0.0 ),
+    ep_n_1( 0.0 ),
+    edf_n_1( 0.0 ),
+    edf_n_2( 0.0 ),
+    u_n_1( 0.0 ),
+    desiredTs( 0.0 ),
+    elapsedTime( 0.0 )
+{
+  parseNode(node);
 }
 
+bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
+{
+  if (aName == "Ts") {
+    desiredTs = aNode->getDoubleValue();
+  } else if (aName == "Kp") {
+    Kp.push_back( new FGXMLAutoInput(aNode) );
+  } else if (aName == "Ti") {
+    Ti.push_back( new FGXMLAutoInput(aNode) );
+  } else if (aName == "Td") {
+    Td.push_back( new FGXMLAutoInput(aNode) );
+  } else if (aName == "beta") {
+    beta = aNode->getDoubleValue();
+  } else if (aName == "alpha") {
+    alpha = aNode->getDoubleValue();
+  } else if (aName == "gamma") {
+    gamma = aNode->getDoubleValue();
+  } else {
+    // unhandled by us, let the base class try it
+    return false;
+  }
+
+  return true;
+}
 
 /*
  * Roy Vegard Ovesen:
@@ -340,11 +467,10 @@ void FGPIDController::update( double dt ) {
     double delta_u_n = 0.0; // incremental output
     double u_n = 0.0;       // absolute output
     double Ts;              // sampling interval (sec)
-    if (umin_prop != NULL)u_min = umin_prop->getDoubleValue();
-    if (umax_prop != NULL)u_max = umax_prop->getDoubleValue();
-    if (Ti_prop != NULL)Ti = Ti_prop->getDoubleValue();
-    if (Td_prop != NULL)Td = Td_prop->getDoubleValue();
-    
+
+    double u_min = uminInput.get_value();
+    double u_max = umaxInput.get_value();
+
     elapsedTime += dt;
     if ( elapsedTime <= desiredTs ) {
         // do nothing if time step is not positive (i.e. no time has
@@ -354,36 +480,25 @@ void FGPIDController::update( double dt ) {
     Ts = elapsedTime;
     elapsedTime = 0.0;
 
-    if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
+    if ( isPropertyEnabled() ) {
         if ( !enabled ) {
             // first time being enabled, seed u_n with current
             // property tree value
-            u_n = output_list[0]->getDoubleValue();
-            // and clip
-            if ( u_n < u_min ) { u_n = u_min; }
-            if ( u_n > u_max ) { u_n = u_max; }
+            u_n = get_output_value();
             u_n_1 = u_n;
         }
         enabled = true;
     } else {
         enabled = false;
+        do_feedback();
     }
 
     if ( enabled && Ts > 0.0) {
-        if ( debug ) cout << "Updating " << name
+        if ( debug ) cout << "Updating " << get_name()
                           << " Ts " << Ts << endl;
 
-        double y_n = 0.0;
-        if ( input_prop != NULL ) {
-            y_n = input_prop->getDoubleValue() * y_scale + y_offset;
-        }
-
-        double r_n = 0.0;
-        if ( r_n_prop != NULL ) {
-            r_n = r_n_prop->getDoubleValue() * r_scale + r_offset;
-        } else {
-            r_n = r_n_value;
-        }
+        double y_n = valueInput.get_value();
+        double r_n = referenceInput.get_value();
                       
         if ( debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
 
@@ -400,9 +515,10 @@ void FGPIDController::update( double dt ) {
         ed_n = gamma * r_n - y_n;
         if ( debug ) cout << " ed_n = " << ed_n;
 
-        if ( Td > 0.0 ) {
+        double td = Td.get_value();
+        if ( td > 0.0 ) {
             // Calculates filter time:
-            Tf = alpha * Td;
+            Tf = alpha * td;
             if ( debug ) cout << " Tf = " << Tf;
 
             // Filters the derivate error:
@@ -414,20 +530,18 @@ void FGPIDController::update( double dt ) {
         }
 
         // Calculates the incremental output:
-        if ( Ti > 0.0 ) {
-            if (Kp_prop != NULL) {
-                Kp = Kp_prop->getDoubleValue();
-            }
-            delta_u_n = Kp * ( (ep_n - ep_n_1)
-                               + ((Ts/Ti) * e_n)
-                               + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
+        double ti = Ti.get_value();
+        if ( ti > 0.0 ) {
+            delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
+                               + ((Ts/ti) * e_n)
+                               + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
         }
 
         if ( debug ) {
             cout << " delta_u_n = " << delta_u_n << endl;
-            cout << "P:" << Kp * (ep_n - ep_n_1)
-                 << " I:" << Kp * ((Ts/Ti) * e_n)
-                 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
+            cout << "P:" << Kp.get_value() * (ep_n - ep_n_1)
+                 << " I:" << Kp.get_value() * ((Ts/ti) * e_n)
+                 << " D:" << Kp.get_value() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
                  << endl;
         }
 
@@ -450,19 +564,7 @@ void FGPIDController::update( double dt ) {
         edf_n_2 = edf_n_1;
         edf_n_1 = edf_n;
 
-        // passive_ignore == true means that we go through all the
-        // motions, but drive the outputs.  This is analogous to
-        // running the autopilot with the "servos" off.  This is
-        // helpful for things like flight directors which position
-        // their vbars from the autopilot computations.
-        if ( passive_mode->getBoolValue() && honor_passive ) {
-            // skip output step
-        } else {
-            unsigned int i;
-            for ( i = 0; i < output_list.size(); ++i ) {
-                output_list[i]->setDoubleValue( u_n );
-            }
-        }
+        set_output_value( u_n );
     } else if ( !enabled ) {
         ep_n  = 0.0;
         edf_n = 0.0;
@@ -476,168 +578,29 @@ void FGPIDController::update( double dt ) {
 
 
 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
-    proportional( false ),
-    Kp( 0.0 ),
-    offset_prop( NULL ),
-    offset_value( 0.0 ),
-    integral( false ),
-    Ki( 0.0 ),
-    int_sum( 0.0 ),
-    clamp( false ),
-    debug( false ),
-    y_n( 0.0 ),
-    r_n( 0.0 ),
-    y_scale( 1.0 ),
-    r_scale ( 1.0 ),
-    u_min( 0.0 ),
-    u_max( 0.0 )
+    FGXMLAutoComponent(),
+    int_sum( 0.0 )
 {
-    int i;
-    for ( i = 0; i < node->nChildren(); ++i ) {
-        SGPropertyNode *child = node->getChild(i);
-        string cname = child->getName();
-        string cval = child->getStringValue();
-        if ( cname == "name" ) {
-            name = cval;
-        } else if ( cname == "debug" ) {
-            debug = child->getBoolValue();
-        } else if ( cname == "enable" ) {
-            // cout << "parsing enable" << endl;
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                // cout << "prop = " << prop->getStringValue() << endl;
-                enable_prop = fgGetNode( prop->getStringValue(), true );
-            } else {
-                // cout << "no prop child" << endl;
-            }
-            SGPropertyNode *val = child->getChild( "value" );
-            if ( val != NULL ) {
-                enable_value = val->getStringValue();
-            }
-        } else if ( cname == "input" ) {
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                input_prop = fgGetNode( prop->getStringValue(), true );
-            }
-            prop = child->getChild( "scale" );
-            if ( prop != NULL ) {
-                y_scale = prop->getDoubleValue();
-            }
-        } else if ( cname == "reference" ) {
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                r_n_prop = fgGetNode( prop->getStringValue(), true );
-            } else {
-                prop = child->getChild( "value" );
-                if ( prop != NULL ) {
-                    r_n_value = prop->getDoubleValue();
-                }
-            }
-            prop = child->getChild( "scale" );
-            if ( prop != NULL ) {
-                r_scale = prop->getDoubleValue();
-            }
-        } else if ( cname == "output" ) {
-            int i = 0;
-            SGPropertyNode *prop;
-            while ( (prop = child->getChild("prop", i)) != NULL ) {
-                SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
-                output_list.push_back( tmp );
-                i++;
-            }
-        } else if ( cname == "config" ) {
-            SGPropertyNode *prop;
-
-            prop = child->getChild( "Kp" );
-            if ( prop != NULL ) {
-                SGPropertyNode *val = prop->getChild( "value" );
-                if ( val != NULL ) {
-                    Kp = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop1 = prop->getChild( "prop" );
-                if ( prop1 != NULL ) {
-                    Kp_prop = fgGetNode( prop1->getStringValue(), true );
-                    if ( val != NULL ) {
-                        Kp_prop->setDoubleValue(Kp);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop1 == NULL) {
-                Kp = prop->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Kp config. Please use <prop> and/or <value> tags." );
-                }
-                proportional = true;
-            }
-
-            prop = child->getChild( "Ki" );
-            if ( prop != NULL ) {
-                Ki = prop->getDoubleValue();
-                integral = true;
-            }
-
-            prop = child->getChild( "u_min" );
-            if ( prop != NULL ) {
-                SGPropertyNode *val = prop->getChild( "value" );
-                if ( val != NULL ) {
-                    u_min = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop1 = prop->getChild( "prop" );
-                if ( prop1 != NULL ) {
-                    umin_prop = fgGetNode( prop1->getStringValue(), true );
-                    if ( val != NULL ) {
-                        umin_prop->setDoubleValue(u_min);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop1 == NULL) {
-                u_min = prop->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_min config. Please use <prop> and/or <value> tags." );
-                }
-                clamp = true;
-            }
-
-            prop = child->getChild( "u_max" );
-            if ( prop != NULL ) {
-                SGPropertyNode *val = prop->getChild( "value" );
-                if ( val != NULL ) {
-                    u_max = val->getDoubleValue();
-                }
-
-                SGPropertyNode *prop1 = prop->getChild( "prop" );
-                if ( prop1 != NULL ) {
-                    umax_prop = fgGetNode( prop1->getStringValue(), true );
-                    if ( val != NULL ) {
-                        umax_prop->setDoubleValue(u_max);
-                    }
-                }
-
-                // output deprecated usage warning
-                if (val == NULL && prop1 == NULL) {
-                u_max = prop->getDoubleValue();
-                    SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_max config. Please use <prop> and/or <value> tags." );
-                }
-                clamp = true;
-            }
-        } else {
-            SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
-            if ( name.length() ) {
-                SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
-            }
-        }
-    }   
+  parseNode(node);
 }
 
+bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
+{
+  if (aName == "Kp") {
+    Kp.push_back( new FGXMLAutoInput(aNode) );
+  } else if (aName == "Ki") {
+    Ki.push_back( new FGXMLAutoInput(aNode) );
+  } else {
+    // unhandled by us, let the base class try it
+    return false;
+  }
+
+  return true;
+}
 
 void FGPISimpleController::update( double dt ) {
-    if (umin_prop != NULL)u_min = umin_prop->getDoubleValue();
-    if (umax_prop != NULL)u_max = umax_prop->getDoubleValue();
-    if (Kp_prop != NULL)Kp = Kp_prop->getDoubleValue();
 
-    if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
+    if ( isPropertyEnabled() ) {
         if ( !enabled ) {
             // we have just been enabled, zero out int_sum
             int_sum = 0.0;
@@ -645,98 +608,53 @@ void FGPISimpleController::update( double dt ) {
         enabled = true;
     } else {
         enabled = false;
+        do_feedback();
     }
 
     if ( enabled ) {
-        if ( debug ) cout << "Updating " << name << endl;
-        double input = 0.0;
-        if ( input_prop != NULL ) {
-            input = input_prop->getDoubleValue() * y_scale;
-        }
-
-        double r_n = 0.0;
-        if ( r_n_prop != NULL ) {
-            r_n = r_n_prop->getDoubleValue() * r_scale;
-        } else {
-            r_n = r_n_value;
-        }
+        if ( debug ) cout << "Updating " << get_name() << endl;
+        double y_n = valueInput.get_value();
+        double r_n = referenceInput.get_value();
                       
-        double error = r_n - input;
-        if ( debug ) cout << "input = " << input
+        double error = r_n - y_n;
+        if ( debug ) cout << "input = " << y_n
                           << " reference = " << r_n
                           << " error = " << error
                           << endl;
 
-        double prop_comp = 0.0;
-        double offset = 0.0;
-        if ( offset_prop != NULL ) {
-            offset = offset_prop->getDoubleValue();
-            if ( debug ) cout << "offset = " << offset << endl;
-        } else {
-            offset = offset_value;
-        }
-
-        if ( proportional ) {
-            prop_comp = error * Kp + offset;
-        }
+        double prop_comp = error * Kp.get_value();
+        int_sum += error * Ki.get_value() * dt;
 
-        if ( integral ) {
-            int_sum += error * Ki * dt;
-        } else {
-            int_sum = 0.0;
-        }
 
         if ( debug ) cout << "prop_comp = " << prop_comp
                           << " int_sum = " << int_sum << endl;
 
         double output = prop_comp + int_sum;
-
-        if ( clamp ) {
-            if ( output < u_min ) {
-                output = u_min;
-            }
-            if ( output > u_max ) {
-                output = u_max;
-            }
-        }
+        output = clamp( output );
+        set_output_value( output );
         if ( debug ) cout << "output = " << output << endl;
-
-        unsigned int i;
-        for ( i = 0; i < output_list.size(); ++i ) {
-            output_list[i]->setDoubleValue( output );
-        }
     }
 }
 
 
 FGPredictor::FGPredictor ( SGPropertyNode *node ):
-    last_value ( 999999999.9 ),
-    average ( 0.0 ),
-    seconds( 0.0 ),
-    filter_gain( 0.0 ),
-    debug( false ),
-    ivalue( 0.0 )
+    FGXMLAutoComponent(),
+    average(0.0)
 {
-    int i;
-    for ( i = 0; i < node->nChildren(); ++i ) {
-        SGPropertyNode *child = node->getChild(i);
-        string cname = child->getName();
-        string cval = child->getStringValue();
-        if ( cname == "name" ) {
-            name = cval;
-        } else if ( cname == "debug" ) {
-            debug = child->getBoolValue();
-        } else if ( cname == "input" ) {
-            input_prop = fgGetNode( child->getStringValue(), true );
-        } else if ( cname == "seconds" ) {
-            seconds = child->getDoubleValue();
-        } else if ( cname == "filter-gain" ) {
-            filter_gain = child->getDoubleValue();
-        } else if ( cname == "output" ) {
-            SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
-            output_list.push_back( tmp );
-        }
-    }   
+  parseNode(node);
+}
+
+bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
+{
+  if (aName == "seconds") {
+    seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
+  } else if (aName == "filter-gain") {
+    filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
+  } else {
+    return false;
+  }
+  
+  return true;
 }
 
 void FGPredictor::update( double dt ) {
@@ -753,36 +671,31 @@ void FGPredictor::update( double dt ) {
 
     */
 
-    if ( input_prop != NULL ) {
-        ivalue = input_prop->getDoubleValue();
-        // no sense if there isn't an input :-)
+    double ivalue = valueInput.get_value();
+
+    if ( isPropertyEnabled() ) {
+        if ( !enabled ) {
+            // first time being enabled
+            last_value = ivalue;
+        }
         enabled = true;
     } else {
         enabled = false;
+        do_feedback();
     }
 
     if ( enabled ) {
 
-        // first time initialize average
-        if (last_value >= 999999999.0) {
-           last_value = ivalue;
-        }
-
         if ( dt > 0.0 ) {
             double current = (ivalue - last_value)/dt; // calculate current error change (per second)
-            if ( dt < 1.0 ) {
-                average = (1.0 - dt) * average + current * dt;
-            } else {
-                average = current;
-            }
+            average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
 
             // calculate output with filter gain adjustment
-            double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
-
-            unsigned int i;
-            for ( i = 0; i < output_list.size(); ++i ) {
-                output_list[i]->setDoubleValue( output );
-            }
+            double output = ivalue + 
+               (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) + 
+                       filter_gain.get_value() * (current * seconds.get_value());
+            output = clamp( output );
+            set_output_value( output );
         }
         last_value = ivalue;
     }
@@ -790,102 +703,69 @@ void FGPredictor::update( double dt ) {
 
 
 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
-    Tf( 1.0 ),
-    samples( 1 ),
-    rateOfChange( 1.0 ),
-    gainFactor( 1.0 ),
-    gain_prop( NULL ),
-    output_min_clamp( -std::numeric_limits<double>::max() ),
-    output_max_clamp( std::numeric_limits<double>::max() )
+    FGXMLAutoComponent(),
+    filterType(none)
 {
-    int i;
-    for ( i = 0; i < node->nChildren(); ++i ) {
-        SGPropertyNode *child = node->getChild(i);
-        string cname = child->getName();
-        string cval = child->getStringValue();
-        if ( cname == "name" ) {
-            name = cval;
-        } else if ( cname == "debug" ) {
-            debug = child->getBoolValue();
-        } else if ( cname == "enable" ) {
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                enable_prop = fgGetNode( prop->getStringValue(), true );
-            }
-            SGPropertyNode *val = child->getChild( "value" );
-            if ( val != NULL ) {
-                enable_value = val->getStringValue();
-            }
-            SGPropertyNode *pass = child->getChild( "honor-passive" );
-            if ( pass != NULL ) {
-                honor_passive = pass->getBoolValue();
-            }
-        } else if ( cname == "type" ) {
-            if ( cval == "exponential" ) {
-                filterType = exponential;
-            } else if (cval == "double-exponential") {
-                filterType = doubleExponential;
-            } else if (cval == "moving-average") {
-                filterType = movingAverage;
-            } else if (cval == "noise-spike") {
-                filterType = noiseSpike;
-            } else if (cval == "gain") {
-                filterType = gain;
-            } else if (cval == "reciprocal") {
-                filterType = reciprocal;
-            }
-        } else if ( cname == "input" ) {
-            input_prop = fgGetNode( child->getStringValue(), true );
-        } else if ( cname == "filter-time" ) {
-            Tf = child->getDoubleValue();
-        } else if ( cname == "samples" ) {
-            samples = child->getIntValue();
-        } else if ( cname == "max-rate-of-change" ) {
-            rateOfChange = child->getDoubleValue();
-        } else if ( cname == "gain" ) {
-            SGPropertyNode *val = child->getChild( "value" );
-            if ( val != NULL ) {
-                gainFactor = val->getDoubleValue();
-            }
-            SGPropertyNode *prop = child->getChild( "prop" );
-            if ( prop != NULL ) {
-                gain_prop = fgGetNode( prop->getStringValue(), true );
-                gain_prop->setDoubleValue(gainFactor);
-            }
-        } else if ( cname == "u_min" ) {
-            output_min_clamp = child->getDoubleValue();
-        } else if ( cname == "u_max" ) {
-            output_max_clamp = child->getDoubleValue();
-        } else if ( cname == "output" ) {
-            SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
-            output_list.push_back( tmp );
-        }
-    }
+    parseNode(node);
 
     output.resize(2, 0.0);
-    input.resize(samples + 1, 0.0);
+    input.resize(samplesInput.get_value() + 1, 0.0);
+}
+
+
+bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
+{
+  if (aName == "type" ) {
+    string val(aNode->getStringValue());
+    if ( val == "exponential" ) {
+      filterType = exponential;
+    } else if (val == "double-exponential") {
+      filterType = doubleExponential;
+    } else if (val == "moving-average") {
+      filterType = movingAverage;
+    } else if (val == "noise-spike") {
+      filterType = noiseSpike;
+    } else if (val == "gain") {
+      filterType = gain;
+    } else if (val == "reciprocal") {
+      filterType = reciprocal;
+    }
+  } else if (aName == "filter-time" ) {
+    TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
+    if( filterType == none ) filterType = exponential;
+  } else if (aName == "samples" ) {
+    samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
+    if( filterType == none ) filterType = movingAverage;
+  } else if (aName == "max-rate-of-change" ) {
+    rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
+    if( filterType == none ) filterType = noiseSpike;
+  } else if (aName == "gain" ) {
+    gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
+    if( filterType == none ) filterType = gain;
+  } else {
+    return false; // not handled by us, let the base class try
+  }
+  
+  return true;
 }
 
 void FGDigitalFilter::update(double dt)
 {
-    if ( (input_prop != NULL && 
-          enable_prop != NULL && 
-          enable_prop->getStringValue() == enable_value) ||
-         (enable_prop == NULL &&
-          input_prop != NULL) ) {
+    if ( isPropertyEnabled() ) {
 
-        input.push_front(input_prop->getDoubleValue());
-        input.resize(samples + 1, 0.0);
+        input.push_front(valueInput.get_value());
+        input.resize(samplesInput.get_value() + 1, 0.0);
 
         if ( !enabled ) {
             // first time being enabled, initialize output to the
             // value of the output property to avoid bumping.
-            output.push_front(output_list[0]->getDoubleValue());
+            output.push_front(get_output_value());
         }
 
         enabled = true;
     } else {
         enabled = false;
+        do_feedback();
     }
 
     if ( enabled && dt > 0.0 ) {
@@ -895,16 +775,18 @@ void FGDigitalFilter::update(double dt)
          * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
          *
          */
+         if( debug ) cout << "Updating " << get_name()
+                          << " dt " << dt << endl;
 
         if (filterType == exponential)
         {
-            double alpha = 1 / ((Tf/dt) + 1);
+            double alpha = 1 / ((TfInput.get_value()/dt) + 1);
             output.push_front(alpha * input[0] + 
                               (1 - alpha) * output[0]);
         } 
         else if (filterType == doubleExponential)
         {
-            double alpha = 1 / ((Tf/dt) + 1);
+            double alpha = 1 / ((TfInput.get_value()/dt) + 1);
             output.push_front(alpha * alpha * input[0] + 
                               2 * (1 - alpha) * output[0] -
                               (1 - alpha) * (1 - alpha) * output[1]);
@@ -912,11 +794,11 @@ void FGDigitalFilter::update(double dt)
         else if (filterType == movingAverage)
         {
             output.push_front(output[0] + 
-                              (input[0] - input.back()) / samples);
+                              (input[0] - input.back()) / samplesInput.get_value());
         }
         else if (filterType == noiseSpike)
         {
-            double maxChange = rateOfChange * dt;
+            double maxChange = rateOfChangeInput.get_value() * dt;
 
             if ((output[0] - input[0]) > maxChange)
             {
@@ -933,32 +815,18 @@ void FGDigitalFilter::update(double dt)
         }
         else if (filterType == gain)
         {
-            if (gain_prop != NULL) {
-                gainFactor = gain_prop->getDoubleValue();
-            }
-            output[0] = gainFactor * input[0];
+            output[0] = gainInput.get_value() * input[0];
         }
         else if (filterType == reciprocal)
         {
-            if (gain_prop != NULL) {
-                gainFactor = gain_prop->getDoubleValue();
-            }
             if (input[0] != 0.0) {
-                output[0] = gainFactor / input[0];
+                output[0] = gainInput.get_value() / input[0];
             }
         }
 
-        if (output[0] < output_min_clamp) {
-            output[0] = output_min_clamp;
-        }
-        else if (output[0] > output_max_clamp) {
-            output[0] = output_max_clamp;
-        }
+        output[0] = clamp(output[0]) ;
+        set_output_value( output[0] );
 
-        unsigned int i;
-        for ( i = 0; i < output_list.size(); ++i ) {
-            output_list[i]->setDoubleValue( output[0] );
-        }
         output.resize(2);
 
         if (debug)
@@ -969,47 +837,99 @@ void FGDigitalFilter::update(double dt)
     }
 }
 
+FGXMLAutopilotGroup::FGXMLAutopilotGroup()
+{
+}
 
-FGXMLAutopilot::FGXMLAutopilot() {
+void FGXMLAutopilotGroup::reinit()
+{
+    for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
+      FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
+      if( ap == NULL ) continue; // ?
+      remove_subsystem( _autopilotNames[i] );
+      delete ap;
+    }
+    _autopilotNames.clear();
+    init();
 }
 
+void FGXMLAutopilotGroup::init()
+{
+    vector<SGPropertyNode_ptr> autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
+    if( autopilotNodes.size() == 0 ) {
+        SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
+        return;
+    }
 
-FGXMLAutopilot::~FGXMLAutopilot() {
-}
+    for( vector<SGPropertyNode_ptr>::size_type i = 0; i < autopilotNodes.size(); i++ ) {
+        SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
+        if( pathNode == NULL ) {
+            SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
+            continue;
+        }
 
-void FGXMLAutopilot::init() {
-    config_props = fgGetNode( "/autopilot/new-config", true );
+        string apName;
+        SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
+        if( nameNode != NULL ) {
+            apName = nameNode->getStringValue();
+        } else {
+          std::ostringstream buf;
+          buf <<  "unnamed_autopilot_" << i;
+          apName = buf.str();
+        }
 
-    SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
+        if( get_subsystem( apName.c_str() ) != NULL ) {
+            SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
+            continue;
+        }
 
-    if ( path_n ) {
         SGPath config( globals->get_fg_root() );
-        config.append( path_n->getStringValue() );
+        config.append( pathNode->getStringValue() );
 
-        SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
-                << config.str() );
+        SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
+        // FGXMLAutopilot
+        FGXMLAutopilot * ap = new FGXMLAutopilot;
         try {
-            readProperties( config.str(), config_props );
+            SGPropertyNode_ptr root = new SGPropertyNode();
+            readProperties( config.str(), root );
 
-            if ( ! build() ) {
-                SG_LOG( SG_ALL, SG_ALERT,
-                        "Detected an internal inconsistency in the autopilot");
-                SG_LOG( SG_ALL, SG_ALERT,
-                        " configuration.  See earlier errors for" );
+
+            if ( ! ap->build( root ) ) {
                 SG_LOG( SG_ALL, SG_ALERT,
-                        " details.");
-                exit(-1);
+                  "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
+                delete ap;
+                continue;
             }        
-        } catch (const sg_exception& exc) {
+        } catch (const sg_exception& e) {
             SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
-                    << config.str() );
+                    << config.str() << ":" << e.getMessage() );
+            delete ap;
+            continue;
         }
 
-    } else {
-        SG_LOG( SG_ALL, SG_WARN,
-                "No autopilot configuration specified for this model!");
+        SG_LOG( SG_ALL, SG_INFO, "adding  autopilot subsystem " << apName );
+        set_subsystem( apName, ap );
+        _autopilotNames.push_back( apName );
     }
+
+    SGSubsystemGroup::init();
+}
+
+FGXMLAutopilot::FGXMLAutopilot() {
+}
+
+
+FGXMLAutopilot::~FGXMLAutopilot() {
+}
+
+/* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
+ * and configure/add the digital filters specified in that file
+ */
+void FGXMLAutopilot::init() 
+{
+  latNode = fgGetNode("/position/latitude-deg");
+  lonNode = fgGetNode("/position/longitude-deg");
 }
 
 
@@ -1025,7 +945,7 @@ void FGXMLAutopilot::bind() {
 void FGXMLAutopilot::unbind() {
 }
 
-bool FGXMLAutopilot::build() {
+bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
     SGPropertyNode *node;
     int i;
 
@@ -1034,6 +954,7 @@ bool FGXMLAutopilot::build() {
         node = config_props->getChild(i);
         string name = node->getName();
         // cout << name << endl;
+        SG_LOG( SG_ALL, SG_INFO, "adding  autopilot component " << name );
         if ( name == "pid-controller" ) {
             components.push_back( new FGPIDController( node ) );
         } else if ( name == "pi-simple-controller" ) {
@@ -1042,10 +963,10 @@ bool FGXMLAutopilot::build() {
             components.push_back( new FGPredictor( node ) );
         } else if ( name == "filter" ) {
             components.push_back( new FGDigitalFilter( node ) );
-        } else {
-            SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
-                    << name );
-            return false;
+//        } else {
+//            SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
+//                    << name );
+//            return false;
         }
     }
 
@@ -1056,12 +977,12 @@ bool FGXMLAutopilot::build() {
 /*
  * Update helper values
  */
-static void update_helper( double dt ) {
+void FGXMLAutopilot::update_helper( double dt ) {
     // Estimate speed in 5,10 seconds
-    static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
-    static SGPropertyNode *lookahead5
+    static SGPropertyNode_ptr vel = fgGetNode( "/velocities/airspeed-kt", true );
+    static SGPropertyNode_ptr lookahead5
         = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
-    static SGPropertyNode *lookahead10
+    static SGPropertyNode_ptr lookahead10
         = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
 
     static double average = 0.0; // average/filtered prediction
@@ -1083,84 +1004,69 @@ static void update_helper( double dt ) {
         v_last = v;
     }
 
-    // Calculate heading bug error normalized to +/- 180.0 (based on
-    // DG indicated heading)
-    static SGPropertyNode *bug
+    // Calculate heading bug error normalized to +/- 180.0
+    static SGPropertyNode_ptr bug
         = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
-    static SGPropertyNode *ind_hdg
-        = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
-                     true );
-    static SGPropertyNode *ind_bug_error
+    static SGPropertyNode_ptr mag_hdg
+        = fgGetNode( "/orientation/heading-magnetic-deg", true );
+    static SGPropertyNode_ptr bug_error
         = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
 
-    double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
-    ind_bug_error->setDoubleValue( diff );
+    double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
+    bug_error->setDoubleValue( diff );
 
-    // Calculate heading bug error normalized to +/- 180.0 (based on
-    // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
-    // compass.)
-    static SGPropertyNode *mag_hdg
-        = fgGetNode( "/orientation/heading-magnetic-deg", true );
-    static SGPropertyNode *fdm_bug_error
+    static SGPropertyNode_ptr fdm_bug_error
         = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
-
-    diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
     fdm_bug_error->setDoubleValue( diff );
 
     // Calculate true heading error normalized to +/- 180.0
-    static SGPropertyNode *target_true
+    static SGPropertyNode_ptr target_true
         = fgGetNode( "/autopilot/settings/true-heading-deg", true );
-    static SGPropertyNode *true_hdg
+    static SGPropertyNode_ptr true_hdg
         = fgGetNode( "/orientation/heading-deg", true );
-    static SGPropertyNode *true_track
-        = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
-    static SGPropertyNode *true_error
+    static SGPropertyNode_ptr true_error
         = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
 
     diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
     true_error->setDoubleValue( diff );
 
     // Calculate nav1 target heading error normalized to +/- 180.0
-    static SGPropertyNode *target_nav1
+    static SGPropertyNode_ptr target_nav1
         = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
-    static SGPropertyNode *true_nav1
+    static SGPropertyNode_ptr true_nav1
         = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
-    static SGPropertyNode *true_track_nav1
+    static SGPropertyNode_ptr true_track_nav1
         = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
 
     diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
     true_nav1->setDoubleValue( diff );
 
-    diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
-    if ( diff < -180.0 ) { diff += 360.0; }
-    if ( diff > 180.0 ) { diff -= 360.0; }
+    // Calculate true groundtrack
+    SGGeod currentPosition(SGGeod::fromDeg(
+        lonNode->getDoubleValue(), latNode->getDoubleValue()));
+    double true_track = SGGeodesy::courseDeg(lastPosition, currentPosition);
+    lastPosition = currentPosition;
+    diff = target_nav1->getDoubleValue() - true_track;
+    SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
     true_track_nav1->setDoubleValue( diff );
 
     // Calculate nav1 selected course error normalized to +/- 180.0
-    // (based on DG indicated heading)
-    static SGPropertyNode *nav1_course_error
+    static SGPropertyNode_ptr nav1_course_error
         = fgGetNode( "/autopilot/internal/nav1-course-error", true );
-    static SGPropertyNode *nav1_selected_course
+    static SGPropertyNode_ptr nav1_selected_course
         = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
 
-    diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
-//    if ( diff < -180.0 ) { diff += 360.0; }
-//    if ( diff > 180.0 ) { diff -= 360.0; }
+    diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
     SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
     nav1_course_error->setDoubleValue( diff );
 
     // Calculate vertical speed in fpm
-    static SGPropertyNode *vs_fps
+    static SGPropertyNode_ptr vs_fps
         = fgGetNode( "/velocities/vertical-speed-fps", true );
-    static SGPropertyNode *vs_fpm
+    static SGPropertyNode_ptr vs_fpm
         = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
 
     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
@@ -1168,24 +1074,21 @@ static void update_helper( double dt ) {
 
     // Calculate static port pressure rate in [inhg/s].
     // Used to determine vertical speed.
-    static SGPropertyNode *static_pressure
-       = fgGetNode( "/systems/static[0]/pressure-inhg", true );
-    static SGPropertyNode *pressure_rate
-       = fgGetNode( "/autopilot/internal/pressure-rate", true );
+    static SGPropertyNode_ptr static_pressure
+        = fgGetNode( "/systems/static[0]/pressure-inhg", true );
+    static SGPropertyNode_ptr pressure_rate
+        = fgGetNode( "/autopilot/internal/pressure-rate", true );
 
     static double last_static_pressure = 0.0;
 
     if ( dt > 0.0 ) {
-       double current_static_pressure = static_pressure->getDoubleValue();
+        double current_static_pressure = static_pressure->getDoubleValue();
+        double current_pressure_rate = 
+            ( current_static_pressure - last_static_pressure ) / dt;
 
-       double current_pressure_rate = 
-           ( current_static_pressure - last_static_pressure ) / dt;
-
-       pressure_rate->setDoubleValue(current_pressure_rate);
-
-       last_static_pressure = current_static_pressure;
+        pressure_rate->setDoubleValue(current_pressure_rate);
+        last_static_pressure = current_static_pressure;
     }
-
 }