//
// Written by Curtis Olson, started January 2004.
//
-// Copyright (C) 2004 Curtis L. Olson - curt@flightgear.org
+// Copyright (C) 2004 Curtis L. Olson - http://www.flightgear.org/~curt
//
// This program is free software; you can redistribute it and/or
// modify it under the terms of the GNU General Public License as
#include <simgear/structure/exception.hxx>
#include <simgear/misc/sg_path.hxx>
+#include <simgear/sg_inlines.h>
#include <Main/fg_props.hxx>
#include <Main/globals.hxx>
+#include <Main/util.hxx>
#include "xmlauto.hxx"
-FGPIDController::FGPIDController( SGPropertyNode *node, bool old ):
- proportional( false ),
- factor( 0.0 ),
- offset_prop( NULL ),
- offset_value( 0.0 ),
- integral( false ),
- gain( 0.0 ),
- int_sum( 0.0 ),
- one_eighty( false ),
- clamp( false ),
+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 ),
ep_n_1( 0.0 ),
edf_n_1( 0.0 ),
edf_n_2( 0.0 ),
- u_n_1( 0.0 )
+ u_n_1( 0.0 ),
+ desiredTs( 0.0 )
{
int i;
for ( i = 0; i < node->nChildren(); ++i ) {
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 ( val != NULL ) {
enable_value = val->getStringValue();
}
- } else if ( cname == "debug" ) {
- debug = child->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 ) {
} else {
prop = child->getChild( "value" );
if ( prop != NULL ) {
- r_n_value = prop->getDoubleValue();
+ r_n = 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;
output_list.push_back( tmp );
i++;
}
- prop = child->getChild( "clamp" );
- if ( prop != NULL ) {
- clamp = true;
+ } else if ( cname == "config" ) {
+ SGPropertyNode *prop;
- SGPropertyNode *tmp;
+ prop = child->getChild( "Ts" );
+ if ( prop != NULL ) {
+ desiredTs = prop->getDoubleValue();
+ }
+
+ prop = child->getChild( "Kp" );
+ if ( prop != NULL ) {
+ Kp = prop->getDoubleValue();
+ }
- tmp = prop->getChild( "min" );
- if ( tmp != NULL ) {
- u_min = tmp->getDoubleValue();
- // cout << "min = " << u_min << endl;
- }
+ prop = child->getChild( "beta" );
+ if ( prop != NULL ) {
+ beta = prop->getDoubleValue();
+ }
- tmp = prop->getChild( "max" );
- if ( tmp != NULL ) {
- u_max = tmp->getDoubleValue();
- // cout << "max = " << u_max << endl;
- }
+ prop = child->getChild( "alpha" );
+ if ( prop != NULL ) {
+ alpha = prop->getDoubleValue();
}
- } else if ( cname == "proportional" ) {
- proportional = true;
- SGPropertyNode *prop;
+ prop = child->getChild( "gamma" );
+ if ( prop != NULL ) {
+ gamma = prop->getDoubleValue();
+ }
- prop = child->getChild( "pre" );
+ prop = child->getChild( "Ti" );
if ( prop != NULL ) {
- prop = prop->getChild( "one-eighty" );
- if ( prop != NULL && prop->getBoolValue() ) {
- one_eighty = true;
- }
+ Ti = prop->getDoubleValue();
}
- prop = child->getChild( "factor" );
+ prop = child->getChild( "Td" );
if ( prop != NULL ) {
- factor = prop->getDoubleValue();
+ Td = prop->getDoubleValue();
}
- prop = child->getChild( "offset" );
+ prop = child->getChild( "u_min" );
if ( prop != NULL ) {
- SGPropertyNode *sub = prop->getChild( "prop" );
- if ( sub != NULL ) {
- offset_prop = fgGetNode( sub->getStringValue(), true );
- // cout << "offset prop = " << sub->getStringValue() << endl;
- } else {
- sub = prop->getChild( "value" );
- if ( sub != NULL ) {
- offset_value = sub->getDoubleValue();
- // cout << "offset value = " << offset_value << endl;
- }
- }
+ u_min = prop->getDoubleValue();
}
- } else if ( cname == "integral" ) {
- integral = true;
- SGPropertyNode *prop;
- prop = child->getChild( "gain" );
+ prop = child->getChild( "u_max" );
if ( prop != NULL ) {
- gain = prop->getDoubleValue();
+ u_max = prop->getDoubleValue();
}
} else {
SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
+ if ( name.length() ) {
+ SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
+ }
}
}
}
-FGPIDController::FGPIDController( SGPropertyNode *node ):
+/*
+ * Roy Vegard Ovesen:
+ *
+ * Ok! Here is the PID controller algorithm that I would like to see
+ * implemented:
+ *
+ * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
+ * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
+ *
+ * u_n = u_n-1 + delta_u_n
+ *
+ * where:
+ *
+ * delta_u : The incremental output
+ * Kp : Proportional gain
+ * ep : Proportional error with reference weighing
+ * ep = beta * r - y
+ * where:
+ * beta : Weighing factor
+ * r : Reference (setpoint)
+ * y : Process value, measured
+ * e : Error
+ * e = r - y
+ * Ts : Sampling interval
+ * Ti : Integrator time
+ * Td : Derivator time
+ * edf : Derivate error with reference weighing and filtering
+ * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
+ * where:
+ * Tf : Filter time
+ * Tf = alpha * Td , where alpha usually is set to 0.1
+ * ed : Unfiltered derivate error with reference weighing
+ * ed = gamma * r - y
+ * where:
+ * gamma : Weighing factor
+ *
+ * u : absolute output
+ *
+ * Index n means the n'th value.
+ *
+ *
+ * Inputs:
+ * enabled ,
+ * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
+ * Kp , Ti , Td , Ts (is the sampling time available?)
+ * u_min , u_max
+ *
+ * Output:
+ * u_n
+ */
+
+void FGPIDController::update( double dt ) {
+ double ep_n; // proportional error with reference weighing
+ double e_n; // error
+ double ed_n; // derivative error
+ double edf_n; // derivative error filter
+ double Tf; // filter time
+ double delta_u_n = 0.0; // incremental output
+ double u_n = 0.0; // absolute output
+ double Ts; // sampling interval (sec)
+
+ elapsedTime += dt;
+ if ( elapsedTime <= desiredTs ) {
+ // do nothing if time step is not positive (i.e. no time has
+ // elapsed)
+ return;
+ }
+ Ts = elapsedTime;
+ elapsedTime = 0.0;
+
+ if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
+ 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_1 = u_n;
+ }
+ enabled = true;
+ } else {
+ enabled = false;
+ }
+
+ if ( enabled && Ts > 0.0) {
+ if ( debug ) cout << "Updating " << 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;
+ }
+
+ if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
+
+ // Calculates proportional error:
+ ep_n = beta * r_n - y_n;
+ if ( debug ) cout << " ep_n = " << ep_n;
+ if ( debug ) cout << " ep_n_1 = " << ep_n_1;
+
+ // Calculates error:
+ e_n = r_n - y_n;
+ if ( debug ) cout << " e_n = " << e_n;
+
+ // Calculates derivate error:
+ ed_n = gamma * r_n - y_n;
+ if ( debug ) cout << " ed_n = " << ed_n;
+
+ if ( Td > 0.0 ) {
+ // Calculates filter time:
+ Tf = alpha * Td;
+ if ( debug ) cout << " Tf = " << Tf;
+
+ // Filters the derivate error:
+ edf_n = edf_n_1 / (Ts/Tf + 1)
+ + ed_n * (Ts/Tf) / (Ts/Tf + 1);
+ if ( debug ) cout << " edf_n = " << edf_n;
+ } else {
+ edf_n = ed_n;
+ }
+
+ // Calculates the incremental output:
+ if ( Ti > 0.0 ) {
+ delta_u_n = Kp * ( (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))
+ << endl;
+ }
+
+ // Integrator anti-windup logic:
+ if ( delta_u_n > (u_max - u_n_1) ) {
+ delta_u_n = u_max - u_n_1;
+ if ( debug ) cout << " max saturation " << endl;
+ } else if ( delta_u_n < (u_min - u_n_1) ) {
+ delta_u_n = u_min - u_n_1;
+ if ( debug ) cout << " min saturation " << endl;
+ }
+
+ // Calculates absolute output:
+ u_n = u_n_1 + delta_u_n;
+ if ( debug ) cout << " output = " << u_n << endl;
+
+ // Updates indexed values;
+ u_n_1 = u_n;
+ ep_n_1 = ep_n;
+ edf_n_2 = edf_n_1;
+ edf_n_1 = edf_n;
+
+ unsigned int i;
+ for ( i = 0; i < output_list.size(); ++i ) {
+ output_list[i]->setDoubleValue( u_n );
+ }
+ } else if ( !enabled ) {
+ ep_n = 0.0;
+ edf_n = 0.0;
+ // Updates indexed values;
+ u_n_1 = u_n;
+ ep_n_1 = ep_n;
+ edf_n_2 = edf_n_1;
+ edf_n_1 = edf_n;
+ }
+}
+
+
+FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
proportional( false ),
- factor( 0.0 ),
+ Kp( 0.0 ),
offset_prop( NULL ),
offset_value( 0.0 ),
integral( false ),
- gain( 0.0 ),
+ Ki( 0.0 ),
int_sum( 0.0 ),
- one_eighty( false ),
clamp( false ),
debug( false ),
y_n( 0.0 ),
r_n( 0.0 ),
- Kp( 0.0 ),
- alpha( 0.1 ),
- beta( 1.0 ),
- gamma( 0.0 ),
- Ti( 0.0 ),
- Td( 0.0 ),
+ y_scale( 1.0 ),
+ r_scale ( 1.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 )
+ u_max( 0.0 )
{
int i;
for ( i = 0; i < node->nChildren(); ++i ) {
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->getDoubleValue();
}
}
+ prop = child->getChild( "scale" );
+ if ( prop != NULL ) {
+ r_scale = prop->getDoubleValue();
+ }
} else if ( cname == "output" ) {
int i = 0;
SGPropertyNode *prop;
prop = child->getChild( "Kp" );
if ( prop != NULL ) {
Kp = prop->getDoubleValue();
+ proportional = true;
}
- prop = child->getChild( "beta" );
- if ( prop != NULL ) {
- beta = prop->getDoubleValue();
- }
-
- prop = child->getChild( "alpha" );
- if ( prop != NULL ) {
- alpha = prop->getDoubleValue();
- }
-
- prop = child->getChild( "gamma" );
- if ( prop != NULL ) {
- gamma = prop->getDoubleValue();
- }
-
- prop = child->getChild( "Ti" );
+ prop = child->getChild( "Ki" );
if ( prop != NULL ) {
- Ti = prop->getDoubleValue();
- }
-
- prop = child->getChild( "Td" );
- if ( prop != NULL ) {
- Td = prop->getDoubleValue();
+ Ki = prop->getDoubleValue();
+ integral = true;
}
prop = child->getChild( "u_min" );
if ( prop != NULL ) {
u_min = prop->getDoubleValue();
+ clamp = true;
}
prop = child->getChild( "u_max" );
if ( prop != NULL ) {
u_max = prop->getDoubleValue();
+ clamp = true;
}
} else {
SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
}
-void FGPIDController::update_old( double dt ) {
+void FGPISimpleController::update( double dt ) {
if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
if ( !enabled ) {
// we have just been enabled, zero out int_sum
if ( debug ) cout << "Updating " << name << endl;
double input = 0.0;
if ( input_prop != NULL ) {
- input = input_prop->getDoubleValue();
+ input = input_prop->getDoubleValue() * y_scale;
}
double r_n = 0.0;
if ( r_n_prop != NULL ) {
- r_n = r_n_prop->getDoubleValue();
+ r_n = r_n_prop->getDoubleValue() * r_scale;
} else {
r_n = r_n_value;
}
double error = r_n - input;
- if ( one_eighty ) {
- while ( error < -180.0 ) { error += 360.0; }
- while ( error > 180.0 ) { error -= 360.0; }
- }
if ( debug ) cout << "input = " << input
<< " reference = " << r_n
<< " error = " << error
}
if ( proportional ) {
- prop_comp = error * factor + offset;
+ prop_comp = error * Kp + offset;
}
if ( integral ) {
- int_sum += error * gain * dt;
+ int_sum += error * Ki * dt;
} else {
int_sum = 0.0;
}
}
-/*
- * Roy Vegard Ovesen:
- *
- * Ok! Here is the PID controller algorithm that I would like to see
- * implemented:
- *
- * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
- * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
- *
- * u_n = u_n-1 + delta_u_n
- *
- * where:
- *
- * delta_u : The incremental output
- * Kp : Proportional gain
- * ep : Proportional error with reference weighing
- * ep = beta * r - y
- * where:
- * beta : Weighing factor
- * r : Reference (setpoint)
- * y : Process value, measured
- * e : Error
- * e = r - y
- * Ts : Sampling interval
- * Ti : Integrator time
- * Td : Derivator time
- * edf : Derivate error with reference weighing and filtering
- * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
- * where:
- * Tf : Filter time
- * Tf = alpha * Td , where alpha usually is set to 0.1
- * ed : Unfiltered derivate error with reference weighing
- * ed = gamma * r - y
- * where:
- * gamma : Weighing factor
- *
- * u : absolute output
- *
- * Index n means the n'th value.
- *
- *
- * Inputs:
- * enabled ,
- * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
- * Kp , Ti , Td , Ts (is the sampling time available?)
- * u_min , u_max
- *
- * Output:
- * u_n
- */
+FGPredictor::FGPredictor ( SGPropertyNode *node ):
+ last_value ( 999999999.9 ),
+ average ( 0.0 ),
+ seconds( 0.0 ),
+ filter_gain( 0.0 ),
+ debug( false ),
+ ivalue( 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 );
+ }
+ }
+}
-void FGPIDController::update( double dt ) {
- double ep_n; // proportional error with reference weighing
- double e_n; // error
- double ed_n; // derivative error
- double edf_n; // derivative error filter
- double Tf; // filter time
- double delta_u_n; // incremental output
- double u_n; // absolute output
- double Ts = dt; // Sampling interval (sec)
-
- if ( Ts <= 0.0 ) {
- // do nothing if time step is not positive (i.e. no time has
- // elapsed)
- return;
- }
+void FGPredictor::update( double dt ) {
+ /*
+ Simple moving average filter converts input value to predicted value "seconds".
- if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
+ Smoothing as described by Curt Olson:
+ gain would be valid in the range of 0 - 1.0
+ 1.0 would mean no filtering.
+ 0.0 would mean no input.
+ 0.5 would mean (1 part past value + 1 part current value) / 2
+ 0.1 would mean (9 parts past value + 1 part current value) / 10
+ 0.25 would mean (3 parts past value + 1 part current value) / 4
+
+ */
+
+ if ( input_prop != NULL ) {
+ ivalue = input_prop->getDoubleValue();
+ // no sense if there isn't an input :-)
enabled = true;
} else {
enabled = false;
}
if ( enabled ) {
- if ( debug ) cout << "Updating " << name << endl;
- double y_n = 0.0;
- if ( input_prop != NULL ) {
- y_n = input_prop->getDoubleValue();
+ // first time initialize average
+ if (last_value >= 999999999.0) {
+ last_value = ivalue;
}
- double r_n = 0.0;
- if ( r_n_prop != NULL ) {
- r_n = r_n_prop->getDoubleValue();
- } else {
- r_n = r_n_value;
- }
-
- if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
+ 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;
+ }
- // Calculates proportional error:
- ep_n = beta * r_n - y_n;
- if ( debug ) cout << " ep_n = " << ep_n;
- if ( debug ) cout << " ep_n_1 = " << ep_n_1;
+ // calculate output with filter gain adjustment
+ double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
- // Calculates error:
- e_n = r_n - y_n;
- if ( debug ) cout << " e_n = " << e_n;
+ unsigned int i;
+ for ( i = 0; i < output_list.size(); ++i ) {
+ output_list[i]->setDoubleValue( output );
+ }
+ }
+ last_value = ivalue;
+ }
+}
- // Calculates derivate error:
- ed_n = gamma * r_n - y_n;
- if ( debug ) cout << " ed_n = " << ed_n;
- // Calculates filter time:
- Tf = alpha * Td;
- if ( debug ) cout << " Tf = " << Tf;
+FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node)
+{
+ samples = 1;
- // Filters the derivate error:
- edf_n = edf_n_1 / (Ts/Tf + 1)
- + ed_n * (Ts/Tf) / (Ts/Tf + 1);
- if ( debug ) cout << " edf_n = " << edf_n;
+ 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 == "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 ( 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 == "output" ) {
+ SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
+ output_list.push_back( tmp );
+ }
+ }
- // Calculates the incremental output:
- delta_u_n = Kp * ( (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;
+ output.resize(2, 0.0);
+ input.resize(samples + 1, 0.0);
+}
- // Integrator anti-windup logic:
- if ( delta_u_n > (u_max - u_n_1) ) {
- delta_u_n = 0;
- } else if ( delta_u_n < (u_min - u_n_1) ) {
- delta_u_n = 0;
- }
+void FGDigitalFilter::update(double dt)
+{
+ if ( input_prop != NULL ) {
+ input.push_front(input_prop->getDoubleValue());
+ input.resize(samples + 1, 0.0);
+ // no sense if there isn't an input :-)
+ enabled = true;
+ } else {
+ enabled = false;
+ }
- // Calculates absolute output:
- u_n = u_n_1 + delta_u_n;
- if ( debug ) cout << " output = " << u_n << endl;
+ if ( enabled && dt > 0.0 ) {
+ /*
+ * Exponential filter
+ *
+ * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
+ *
+ */
+
+ if (filterType == exponential)
+ {
+ double alpha = 1 / ((Tf/dt) + 1);
+ output.push_front(alpha * input[0] +
+ (1 - alpha) * output[0]);
+ unsigned int i;
+ for ( i = 0; i < output_list.size(); ++i ) {
+ output_list[i]->setDoubleValue( output[0] );
+ }
+ output.resize(1);
+ }
+ else if (filterType == doubleExponential)
+ {
+ double alpha = 1 / ((Tf/dt) + 1);
+ output.push_front(alpha * alpha * input[0] +
+ 2 * (1 - alpha) * output[0] -
+ (1 - alpha) * (1 - alpha) * output[1]);
+ unsigned int i;
+ for ( i = 0; i < output_list.size(); ++i ) {
+ output_list[i]->setDoubleValue( output[0] );
+ }
+ output.resize(2);
+ }
+ else if (filterType == movingAverage)
+ {
+ output.push_front(output[0] +
+ (input[0] - input.back()) / samples);
+ unsigned int i;
+ for ( i = 0; i < output_list.size(); ++i ) {
+ output_list[i]->setDoubleValue( output[0] );
+ }
+ output.resize(1);
+ }
+ else if (filterType == noiseSpike)
+ {
+ double maxChange = rateOfChange * dt;
- // Updates indexed values;
- u_n_1 = u_n;
- ep_n_1 = ep_n;
- edf_n_2 = edf_n_1;
- edf_n_1 = edf_n;
+ if ((output[0] - input[0]) > maxChange)
+ {
+ output.push_front(output[0] - maxChange);
+ }
+ else if ((output[0] - input[0]) < -maxChange)
+ {
+ output.push_front(output[0] + maxChange);
+ }
+ else if (fabs(input[0] - output[0]) <= maxChange)
+ {
+ output.push_front(input[0]);
+ }
- unsigned int i;
- for ( i = 0; i < output_list.size(); ++i ) {
- output_list[i]->setDoubleValue( u_n );
+ unsigned int i;
+ for ( i = 0; i < output_list.size(); ++i ) {
+ output_list[i]->setDoubleValue( output[0] );
+ }
+ output.resize(1);
+ }
+ if (debug)
+ {
+ cout << "input:" << input[0]
+ << "\toutput:" << output[0] << endl;
}
- } else if ( !enabled ) {
- u_n = 0.0;
- ep_n = 0.0;
- edf_n = 0.0;
- // Updates indexed values;
- u_n_1 = u_n;
- ep_n_1 = ep_n;
- edf_n_2 = edf_n_1;
- edf_n_1 = edf_n;
}
}
void FGXMLAutopilot::reinit() {
components.clear();
+ init();
build();
}
if ( name == "pid-controller" ) {
FGXMLAutoComponent *c = new FGPIDController( node );
components.push_back( c );
+ } else if ( name == "pi-simple-controller" ) {
+ FGXMLAutoComponent *c = new FGPISimpleController( node );
+ components.push_back( c );
+ } else if ( name == "predict-simple" ) {
+ FGXMLAutoComponent *c = new FGPredictor( node );
+ components.push_back( c );
+ } else if ( name == "filter" ) {
+ FGXMLAutoComponent *c = new FGDigitalFilter( node );
+ components.push_back( c );
} else {
SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
<< name );
v_last = v;
}
- // Calculate heading bug error normalized to +/- 180.0
+ // Calculate heading bug error normalized to +/- 180.0 (based on
+ // DG indicated heading)
static SGPropertyNode *bug
= fgGetNode( "/autopilot/settings/heading-bug-deg", true );
static SGPropertyNode *ind_hdg
= fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
true );
- static SGPropertyNode *bug_error
+ static SGPropertyNode *ind_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; }
- bug_error->setDoubleValue( diff );
+ ind_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
+ = 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
= fgGetNode( "/autopilot/settings/true-heading-deg", true );
static SGPropertyNode *true_hdg
= fgGetNode( "/orientation/heading-deg", true );
+ static SGPropertyNode *true_track
+ = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
static SGPropertyNode *true_error
= fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
// Calculate nav1 target heading error normalized to +/- 180.0
static SGPropertyNode *target_nav1
- = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
+ = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
static SGPropertyNode *true_nav1
= fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
+ static SGPropertyNode *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; }
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; }
+ true_track_nav1->setDoubleValue( diff );
+
+ // Calculate nav1 selected course error normalized to +/- 180.0
+ // (based on DG indicated heading)
+ static SGPropertyNode *nav1_course_error
+ = fgGetNode( "/autopilot/internal/nav1-course-error", true );
+ static SGPropertyNode *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; }
+ SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
+ nav1_course_error->setDoubleValue( diff );
+
+ // Calculate vertical speed in fpm
+ static SGPropertyNode *vs_fps
+ = fgGetNode( "/velocities/vertical-speed-fps", true );
+ static SGPropertyNode *vs_fpm
+ = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
+
+ vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
+
+
+ // 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 double last_static_pressure = 0.0;
+
+ if ( dt > 0.0 ) {
+ double current_static_pressure = static_pressure->getDoubleValue();
+
+ double current_pressure_rate =
+ ( current_static_pressure - last_static_pressure ) / dt;
+
+ pressure_rate->setDoubleValue(current_pressure_rate);
+
+ last_static_pressure = current_static_pressure;
+ }
+
}