1 // xmlauto.cxx - a more flexible, generic way to build autopilots
3 // Written by Curtis Olson, started January 2004.
5 // Copyright (C) 2004 Curtis L. Olson - http://www.flightgear.org/~curt
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.
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.
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.
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>
35 #include <Main/fg_props.hxx>
36 #include <Main/globals.hxx>
37 #include <Main/util.hxx>
39 #include "xmlauto.hxx"
44 using simgear::PropertyList;
46 FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
48 SGPropertyNode_ptr minNode = root->getChild( "min" );
49 SGPropertyNode_ptr maxNode = root->getChild( "max" );
50 if( minNode == NULL || maxNode == NULL ) {
51 SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
53 minPeriod = new FGXMLAutoInput( minNode );
54 maxPeriod = new FGXMLAutoInput( maxNode );
58 double FGPeriodicalValue::normalize( double value )
60 if( !(minPeriod && maxPeriod )) return value;
62 double p1 = minPeriod->get_value();
63 double p2 = maxPeriod->get_value();
65 double min = std::min<double>(p1,p2);
66 double max = std::max<double>(p1,p2);
67 double phase = fabs(max - min);
69 if( phase > SGLimitsd::min() ) {
70 while( value < min ) value += phase;
71 while( value >= max ) value -= phase;
73 value = min; // phase is zero
79 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
84 parse( node, value, offset, scale );
88 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
103 if( (n = node->getChild("condition")) != NULL ) {
104 _condition = sgReadCondition(fgGetNode("/"), n);
107 if( (n = node->getChild( "scale" )) != NULL ) {
108 scale = new FGXMLAutoInput( n, aScale );
111 if( (n = node->getChild( "offset" )) != NULL ) {
112 offset = new FGXMLAutoInput( n, aOffset );
115 if( (n = node->getChild( "max" )) != NULL ) {
116 max = new FGXMLAutoInput( n );
119 if( (n = node->getChild( "min" )) != NULL ) {
120 min = new FGXMLAutoInput( n );
123 if( (n = node->getChild( "abs" )) != NULL ) {
124 abs = n->getBoolValue();
127 if( (n = node->getChild( "period" )) != NULL ) {
128 periodical = new FGPeriodicalValue( n );
131 SGPropertyNode *valueNode = node->getChild( "value" );
132 if ( valueNode != NULL ) {
133 value = valueNode->getDoubleValue();
136 n = node->getChild( "property" );
137 // if no <property> element, check for <prop> element for backwards
140 n = node->getChild( "prop" );
143 property = fgGetNode( n->getStringValue(), true );
144 if ( valueNode != NULL ) {
145 // initialize property with given value
146 // if both <prop> and <value> exist
147 double s = get_scale();
149 property->setDoubleValue( (value - get_offset())/s );
151 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
155 if ( n == NULL && valueNode == NULL ) {
156 // no <value> element and no <prop> element, use text node
157 const char * textnode = node->getStringValue();
159 // try to convert to a double value. If the textnode does not start with a number
160 // endp will point to the beginning of the string. We assume this should be
162 value = strtod( textnode, &endp );
163 if( endp == textnode ) {
164 property = fgGetNode( textnode, true );
169 void FGXMLAutoInput::set_value( double aValue )
171 double s = get_scale();
173 property->setDoubleValue( (aValue - get_offset())/s );
175 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
178 double FGXMLAutoInput::get_value()
180 if( property != NULL )
181 value = property->getDoubleValue();
184 value *= scale->get_value();
187 value += offset->get_value();
190 double m = min->get_value();
196 double m = max->get_value();
202 value = periodical->normalize( value );
205 return abs ? fabs(value) : value;
208 FGXMLAutoComponent::FGXMLAutoComponent() :
211 enable_value( NULL ),
212 passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
213 honor_passive( false ),
215 feedback_if_disabled( false ),
221 FGXMLAutoComponent::~FGXMLAutoComponent()
226 void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
228 SGPropertyNode *prop;
229 for (int i = 0; i < aNode->nChildren(); ++i ) {
230 SGPropertyNode *child = aNode->getChild(i);
231 string cname(child->getName());
233 if (parseNodeHook(cname, child)) {
234 // derived class handled it, fine
235 } else if ( cname == "name" ) {
236 name = child->getStringValue();
237 } else if ( cname == "feedback-if-disabled" ) {
238 feedback_if_disabled = child->getBoolValue();
239 } else if ( cname == "debug" ) {
240 debug = child->getBoolValue();
241 } else if ( cname == "enable" ) {
242 if( (prop = child->getChild("condition")) != NULL ) {
243 _condition = sgReadCondition(fgGetNode("/"), prop);
245 if ( (prop = child->getChild( "prop" )) != NULL ) {
246 enable_prop = fgGetNode( prop->getStringValue(), true );
249 if ( (prop = child->getChild( "value" )) != NULL ) {
251 enable_value = new string(prop->getStringValue());
254 if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
255 honor_passive = prop->getBoolValue();
257 } else if ( cname == "input" ) {
258 valueInput.push_back( new FGXMLAutoInput( child ) );
259 } else if ( cname == "reference" ) {
260 referenceInput.push_back( new FGXMLAutoInput( child ) );
261 } else if ( cname == "output" ) {
262 // grab all <prop> and <property> childs
264 // backwards compatibility: allow <prop> elements
265 for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) {
266 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
267 output_list.push_back( tmp );
270 for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) {
271 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
272 output_list.push_back( tmp );
276 // no <prop> elements, text node of <output> is property name
278 output_list.push_back( fgGetNode(child->getStringValue(), true ) );
279 } else if ( cname == "config" ) {
281 } else if ( cname == "min" ) {
282 uminInput.push_back( new FGXMLAutoInput( child ) );
283 } else if ( cname == "u_min" ) {
284 uminInput.push_back( new FGXMLAutoInput( child ) );
285 } else if ( cname == "max" ) {
286 umaxInput.push_back( new FGXMLAutoInput( child ) );
287 } else if ( cname == "u_max" ) {
288 umaxInput.push_back( new FGXMLAutoInput( child ) );
289 } else if ( cname == "period" ) {
290 periodical = new FGPeriodicalValue( child );
292 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:"
293 << cname << " in section " << name);
294 throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
296 } // of top-level iteration
299 void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
301 for (int i = 0; i < aConfig->nChildren(); ++i ) {
302 SGPropertyNode *child = aConfig->getChild(i);
303 string cname(child->getName());
305 if (parseConfigHook(cname, child)) {
306 // derived class handled it, fine
307 } else if ( cname == "min" ) {
308 uminInput.push_back( new FGXMLAutoInput( child ) );
309 } else if ( cname == "u_min" ) {
310 uminInput.push_back( new FGXMLAutoInput( child ) );
311 } else if ( cname == "max" ) {
312 umaxInput.push_back( new FGXMLAutoInput( child ) );
313 } else if ( cname == "u_max" ) {
314 umaxInput.push_back( new FGXMLAutoInput( child ) );
316 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:"
317 << cname << " in section " << name);
318 throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
320 } // of config iteration
323 bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
328 bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
333 bool FGXMLAutoComponent::isPropertyEnabled()
336 return _condition->test();
340 return *enable_value == enable_prop->getStringValue();
342 return enable_prop->getBoolValue();
348 void FGXMLAutoComponent::do_feedback_if_disabled()
350 if( output_list.size() > 0 ) {
351 FGXMLAutoInput * input = valueInput.get_active();
353 input->set_value( output_list[0]->getDoubleValue() );
357 double FGXMLAutoComponent::clamp( double value )
359 //If this is a periodical value, normalize it into our domain
362 value = periodical->normalize( value );
364 // clamp, if either min or max is defined
365 if( uminInput.size() + umaxInput.size() > 0 ) {
366 double d = umaxInput.get_value( 0.0 );
367 if( value > d ) value = d;
368 d = uminInput.get_value( 0.0 );
369 if( value < d ) value = d;
374 FGPIDController::FGPIDController( SGPropertyNode *node ):
375 FGXMLAutoComponent(),
389 bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
392 desiredTs = aNode->getDoubleValue();
393 } else if (aName == "Kp") {
394 Kp.push_back( new FGXMLAutoInput(aNode) );
395 } else if (aName == "Ti") {
396 Ti.push_back( new FGXMLAutoInput(aNode) );
397 } else if (aName == "Td") {
398 Td.push_back( new FGXMLAutoInput(aNode) );
399 } else if (aName == "beta") {
400 beta = aNode->getDoubleValue();
401 } else if (aName == "alpha") {
402 alpha = aNode->getDoubleValue();
403 } else if (aName == "gamma") {
404 gamma = aNode->getDoubleValue();
406 // unhandled by us, let the base class try it
416 * Ok! Here is the PID controller algorithm that I would like to see
419 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
420 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
422 * u_n = u_n-1 + delta_u_n
426 * delta_u : The incremental output
427 * Kp : Proportional gain
428 * ep : Proportional error with reference weighing
431 * beta : Weighing factor
432 * r : Reference (setpoint)
433 * y : Process value, measured
436 * Ts : Sampling interval
437 * Ti : Integrator time
438 * Td : Derivator time
439 * edf : Derivate error with reference weighing and filtering
440 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
443 * Tf = alpha * Td , where alpha usually is set to 0.1
444 * ed : Unfiltered derivate error with reference weighing
447 * gamma : Weighing factor
449 * u : absolute output
451 * Index n means the n'th value.
456 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
457 * Kp , Ti , Td , Ts (is the sampling time available?)
464 void FGPIDController::update( double dt ) {
467 double delta_u_n = 0.0; // incremental output
468 double u_n = 0.0; // absolute output
469 double Ts; // sampling interval (sec)
471 double u_min = uminInput.get_value();
472 double u_max = umaxInput.get_value();
475 if ( elapsedTime <= desiredTs ) {
476 // do nothing if time step is not positive (i.e. no time has
483 if ( isPropertyEnabled() ) {
485 // first time being enabled, seed u_n with current
486 // property tree value
487 u_n = get_output_value();
496 if ( enabled && Ts > 0.0) {
497 if ( debug ) cout << "Updating " << get_name()
498 << " Ts " << Ts << endl;
500 double y_n = valueInput.get_value();
501 double r_n = referenceInput.get_value();
503 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
505 // Calculates proportional error:
506 double ep_n = beta * r_n - y_n;
507 if ( debug ) cout << " ep_n = " << ep_n;
508 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
512 if ( debug ) cout << " e_n = " << e_n;
514 double td = Td.get_value();
515 if ( td > 0.0 ) { // do we need to calcluate derivative error?
517 // Calculates derivate error:
518 double ed_n = gamma * r_n - y_n;
519 if ( debug ) cout << " ed_n = " << ed_n;
521 // Calculates filter time:
522 double Tf = alpha * td;
523 if ( debug ) cout << " Tf = " << Tf;
525 // Filters the derivate error:
526 edf_n = edf_n_1 / (Ts/Tf + 1)
527 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
528 if ( debug ) cout << " edf_n = " << edf_n;
530 edf_n_2 = edf_n_1 = edf_n = 0.0;
533 // Calculates the incremental output:
534 double ti = Ti.get_value();
536 delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
538 + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
541 cout << " delta_u_n = " << delta_u_n << endl;
542 cout << "P:" << Kp.get_value() * (ep_n - ep_n_1)
543 << " I:" << Kp.get_value() * ((Ts/ti) * e_n)
544 << " D:" << Kp.get_value() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
549 // Integrator anti-windup logic:
550 if ( delta_u_n > (u_max - u_n_1) ) {
551 delta_u_n = u_max - u_n_1;
552 if ( debug ) cout << " max saturation " << endl;
553 } else if ( delta_u_n < (u_min - u_n_1) ) {
554 delta_u_n = u_min - u_n_1;
555 if ( debug ) cout << " min saturation " << endl;
558 // Calculates absolute output:
559 u_n = u_n_1 + delta_u_n;
560 if ( debug ) cout << " output = " << u_n << endl;
562 // Updates indexed values;
568 set_output_value( u_n );
569 } else if ( !enabled ) {
571 edf_n_2 = edf_n_1 = edf_n = 0.0;
576 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
577 FGXMLAutoComponent(),
583 bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
586 Kp.push_back( new FGXMLAutoInput(aNode) );
587 } else if (aName == "Ki") {
588 Ki.push_back( new FGXMLAutoInput(aNode) );
590 // unhandled by us, let the base class try it
597 void FGPISimpleController::update( double dt ) {
599 if ( isPropertyEnabled() ) {
601 // we have just been enabled, zero out int_sum
611 if ( debug ) cout << "Updating " << get_name() << endl;
612 double y_n = valueInput.get_value();
613 double r_n = referenceInput.get_value();
615 double error = r_n - y_n;
616 if ( debug ) cout << "input = " << y_n
617 << " reference = " << r_n
618 << " error = " << error
621 double prop_comp = clamp(error * Kp.get_value());
622 int_sum += error * Ki.get_value() * dt;
625 double output = prop_comp + int_sum;
626 double clamped_output = clamp( output );
627 if( output != clamped_output ) // anti-windup
628 int_sum = clamped_output - prop_comp;
630 if ( debug ) cout << "prop_comp = " << prop_comp
631 << " int_sum = " << int_sum << endl;
633 set_output_value( clamped_output );
634 if ( debug ) cout << "output = " << clamped_output << endl;
639 FGPredictor::FGPredictor ( SGPropertyNode *node ):
640 FGXMLAutoComponent(),
646 bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
648 if (aName == "seconds") {
649 seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
650 } else if (aName == "filter-gain") {
651 filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
659 void FGPredictor::update( double dt ) {
661 Simple moving average filter converts input value to predicted value "seconds".
663 Smoothing as described by Curt Olson:
664 gain would be valid in the range of 0 - 1.0
665 1.0 would mean no filtering.
666 0.0 would mean no input.
667 0.5 would mean (1 part past value + 1 part current value) / 2
668 0.1 would mean (9 parts past value + 1 part current value) / 10
669 0.25 would mean (3 parts past value + 1 part current value) / 4
673 double ivalue = valueInput.get_value();
675 if ( isPropertyEnabled() ) {
677 // first time being enabled
689 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
690 average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
692 // calculate output with filter gain adjustment
693 double output = ivalue +
694 (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) +
695 filter_gain.get_value() * (current * seconds.get_value());
696 output = clamp( output );
697 set_output_value( output );
704 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
705 FGXMLAutoComponent(),
710 output.resize(2, 0.0);
711 input.resize(samplesInput.get_value() + 1, 0.0);
715 bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
717 if (aName == "type" ) {
718 string val(aNode->getStringValue());
719 if ( val == "exponential" ) {
720 filterType = exponential;
721 } else if (val == "double-exponential") {
722 filterType = doubleExponential;
723 } else if (val == "moving-average") {
724 filterType = movingAverage;
725 } else if (val == "noise-spike") {
726 filterType = noiseSpike;
727 } else if (val == "gain") {
729 } else if (val == "reciprocal") {
730 filterType = reciprocal;
731 } else if (val == "differential") {
732 filterType = differential;
733 // use a constant of two samples for current and previous input value
734 samplesInput.push_back( new FGXMLAutoInput(NULL, 2.0 ) );
736 } else if (aName == "filter-time" ) {
737 TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
738 if( filterType == none ) filterType = exponential;
739 } else if (aName == "samples" ) {
740 samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
741 if( filterType == none ) filterType = movingAverage;
742 } else if (aName == "max-rate-of-change" ) {
743 rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
744 if( filterType == none ) filterType = noiseSpike;
745 } else if (aName == "gain" ) {
746 gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
747 if( filterType == none ) filterType = gain;
749 return false; // not handled by us, let the base class try
755 void FGDigitalFilter::update(double dt)
757 if ( isPropertyEnabled() ) {
759 input.push_front(valueInput.get_value()-referenceInput.get_value());
760 input.resize(samplesInput.get_value() + 1, 0.0);
763 // first time being enabled, initialize output to the
764 // value of the output property to avoid bumping.
765 output.push_front(get_output_value());
774 if ( !enabled || dt < SGLimitsd::min() )
780 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
783 if( debug ) cout << "Updating " << get_name()
784 << " dt " << dt << endl;
786 if (filterType == exponential)
788 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
789 output.push_front(alpha * input[0] +
790 (1 - alpha) * output[0]);
792 else if (filterType == doubleExponential)
794 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
795 output.push_front(alpha * alpha * input[0] +
796 2 * (1 - alpha) * output[0] -
797 (1 - alpha) * (1 - alpha) * output[1]);
799 else if (filterType == movingAverage)
801 output.push_front(output[0] +
802 (input[0] - input.back()) / samplesInput.get_value());
804 else if (filterType == noiseSpike)
806 double maxChange = rateOfChangeInput.get_value() * dt;
808 if ((output[0] - input[0]) > maxChange)
810 output.push_front(output[0] - maxChange);
812 else if ((output[0] - input[0]) < -maxChange)
814 output.push_front(output[0] + maxChange);
816 else if (fabs(input[0] - output[0]) <= maxChange)
818 output.push_front(input[0]);
821 else if (filterType == gain)
823 output[0] = gainInput.get_value() * input[0];
825 else if (filterType == reciprocal)
827 if (input[0] != 0.0) {
828 output[0] = gainInput.get_value() / input[0];
831 else if (filterType == differential)
833 if( dt > SGLimitsd::min() ) {
834 output[0] = (input[0]-input[1]) * TfInput.get_value() / dt;
838 output[0] = clamp(output[0]) ;
839 set_output_value( output[0] );
845 cout << "input:" << input[0]
846 << "\toutput:" << output[0] << endl;
850 FGXMLAutoLogic::FGXMLAutoLogic(SGPropertyNode * node ) :
851 FGXMLAutoComponent(),
857 bool FGXMLAutoLogic::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
859 if (aName == "input") {
860 input = sgReadCondition( fgGetNode("/"), aNode );
861 } else if (aName == "inverted") {
862 inverted = aNode->getBoolValue();
870 void FGXMLAutoLogic::update(double dt)
872 if ( isPropertyEnabled() ) {
874 // we have just been enabled
882 if ( !enabled || dt < SGLimitsd::min() )
885 if( input == NULL ) {
886 if ( debug ) cout << "No input for " << get_name() << endl;
890 bool i = input->test();
892 if ( debug ) cout << "Updating " << get_name() << ": " << (inverted ? !i : i) << endl;
894 set_output_value( i );
897 class FGXMLAutoRSFlipFlop : public FGXMLAutoFlipFlop {
899 FGXMLAutoRSFlipFlop( SGPropertyNode * node ) :
900 FGXMLAutoFlipFlop( node ) {}
902 void updateState( double dt ) {
904 if( sInput == NULL ) {
905 if ( debug ) cout << "No set (S) input for " << get_name() << endl;
909 if( rInput == NULL ) {
910 if ( debug ) cout << "No reset (R) input for " << get_name() << endl;
914 bool s = sInput->test();
915 bool r = rInput->test();
917 // s == false && q == false: no change, keep state
920 if( s ) q = true; // set
921 if( r ) q = false; // reset
922 // s && q: race condition. we let r win
923 if( inverted ) q = !q;
925 if ( debug ) cout << "Updating " << get_name() << ":"
928 << ",q=" << q << endl;
929 set_output_value( q );
931 if ( debug ) cout << "Updating " << get_name() << ":"
934 << ",q=unchanged" << endl;
939 class FGXMLAutoJKFlipFlop : public FGXMLAutoFlipFlop {
943 FGXMLAutoJKFlipFlop( SGPropertyNode * node ) :
944 FGXMLAutoFlipFlop( node ),
947 void updateState( double dt ) {
949 if( jInput == NULL ) {
950 if ( debug ) cout << "No set (j) input for " << get_name() << endl;
954 if( kInput == NULL ) {
955 if ( debug ) cout << "No reset (k) input for " << get_name() << endl;
959 bool j = jInput->test();
960 bool k = kInput->test();
962 if the user provided a clock input, use it.
963 Otherwise use framerate as clock
964 This JK operates on the raising edge.
966 bool c = clockInput ? clockInput->test() : false;
967 bool raisingEdge = clockInput ? (c && !clock) : true;
970 if( !raisingEdge ) return;
972 bool q = get_bool_output_value();
973 // j == false && k == false: no change, keep state
978 if( j ) q = true; // set
979 if( k ) q = false; // reset
981 if( inverted ) q = !q;
983 if ( debug ) cout << "Updating " << get_name() << ":"
986 << ",q=" << q << endl;
987 set_output_value( q );
989 if ( debug ) cout << "Updating " << get_name() << ":"
992 << ",q=unchanged" << endl;
997 class FGXMLAutoDFlipFlop : public FGXMLAutoFlipFlop {
1001 FGXMLAutoDFlipFlop( SGPropertyNode * node ) :
1002 FGXMLAutoFlipFlop( node ),
1005 void updateState( double dt ) {
1007 if( clockInput == NULL ) {
1008 if ( debug ) cout << "No (clock) input for " << get_name() << endl;
1012 if( dInput == NULL ) {
1013 if ( debug ) cout << "No (D) input for " << get_name() << endl;
1017 bool d = dInput->test();
1019 // check the clock - raising edge
1020 bool c = clockInput->test();
1021 bool raisingEdge = c && !clock;
1026 if( inverted ) q = !q;
1028 if ( debug ) cout << "Updating " << get_name() << ":"
1030 << ",q=" << q << endl;
1031 set_output_value( q );
1033 if ( debug ) cout << "Updating " << get_name() << ":"
1035 << ",q=unchanged" << endl;
1040 class FGXMLAutoTFlipFlop : public FGXMLAutoFlipFlop {
1044 FGXMLAutoTFlipFlop( SGPropertyNode * node ) :
1045 FGXMLAutoFlipFlop( node ),
1048 void updateState( double dt ) {
1050 if( clockInput == NULL ) {
1051 if ( debug ) cout << "No (clock) input for " << get_name() << endl;
1055 // check the clock - raising edge
1056 bool c = clockInput->test();
1057 bool raisingEdge = c && !clock;
1061 bool q = !get_bool_output_value(); // toggle
1062 if( inverted ) q = !q; // doesnt really make sense for a T-FF
1064 if ( debug ) cout << "Updating " << get_name() << ":"
1065 << ",q=" << q << endl;
1066 set_output_value( q );
1068 if ( debug ) cout << "Updating " << get_name() << ":"
1069 << ",q=unchanged" << endl;
1074 FGXMLAutoFlipFlop::FGXMLAutoFlipFlop(SGPropertyNode * node ) :
1075 FGXMLAutoComponent(),
1081 bool FGXMLAutoFlipFlop::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
1083 if (aName == "set"||aName == "S") {
1084 sInput = sgReadCondition( fgGetNode("/"), aNode );
1085 } else if (aName == "reset" || aName == "R" ) {
1086 rInput = sgReadCondition( fgGetNode("/"), aNode );
1087 } else if (aName == "J") {
1088 jInput = sgReadCondition( fgGetNode("/"), aNode );
1089 } else if (aName == "K") {
1090 kInput = sgReadCondition( fgGetNode("/"), aNode );
1091 } else if (aName == "T") {
1092 tInput = sgReadCondition( fgGetNode("/"), aNode );
1093 } else if (aName == "D") {
1094 dInput = sgReadCondition( fgGetNode("/"), aNode );
1095 } else if (aName == "clock") {
1096 clockInput = sgReadCondition( fgGetNode("/"), aNode );
1097 } else if (aName == "inverted") {
1098 inverted = aNode->getBoolValue();
1099 } else if (aName == "type") {
1100 // ignore element type, evaluated by loader
1108 void FGXMLAutoFlipFlop::update(double dt)
1110 if ( isPropertyEnabled() ) {
1112 // we have just been enabled
1113 // initialize to a bool property
1114 set_output_value( get_bool_output_value() );
1122 if ( !enabled || dt < SGLimitsd::min() )
1129 FGXMLAutopilotGroup::FGXMLAutopilotGroup() :
1131 #ifdef XMLAUTO_USEHELPER
1132 ,average(0.0), // average/filtered prediction
1133 v_last(0.0), // last velocity
1134 last_static_pressure(0.0),
1135 vel(fgGetNode( "/velocities/airspeed-kt", true )),
1136 // Estimate speed in 5,10 seconds
1137 lookahead5(fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true )),
1138 lookahead10(fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true )),
1139 bug(fgGetNode( "/autopilot/settings/heading-bug-deg", true )),
1140 mag_hdg(fgGetNode( "/orientation/heading-magnetic-deg", true )),
1141 bug_error(fgGetNode( "/autopilot/internal/heading-bug-error-deg", true )),
1142 fdm_bug_error(fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true )),
1143 target_true(fgGetNode( "/autopilot/settings/true-heading-deg", true )),
1144 true_hdg(fgGetNode( "/orientation/heading-deg", true )),
1145 true_error(fgGetNode( "/autopilot/internal/true-heading-error-deg", true )),
1146 target_nav1(fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true )),
1147 true_nav1(fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true )),
1148 true_track_nav1(fgGetNode( "/autopilot/internal/nav1-track-error-deg", true )),
1149 nav1_course_error(fgGetNode( "/autopilot/internal/nav1-course-error", true )),
1150 nav1_selected_course(fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true )),
1151 vs_fps(fgGetNode( "/velocities/vertical-speed-fps", true )),
1152 vs_fpm(fgGetNode( "/autopilot/internal/vert-speed-fpm", true )),
1153 static_pressure(fgGetNode( "/systems/static[0]/pressure-inhg", true )),
1154 pressure_rate(fgGetNode( "/autopilot/internal/pressure-rate", true )),
1155 track(fgGetNode( "/orientation/track-deg", true ))
1160 void FGXMLAutopilotGroup::update( double dt )
1162 // update all configured autopilots
1163 SGSubsystemGroup::update( dt );
1164 #ifdef XMLAUTO_USEHELPER
1165 // update helper values
1166 double v = vel->getDoubleValue();
1169 a = (v - v_last) / dt;
1172 average = (1.0 - dt) * average + dt * a;
1177 lookahead5->setDoubleValue( v + average * 5.0 );
1178 lookahead10->setDoubleValue( v + average * 10.0 );
1182 // Calculate heading bug error normalized to +/- 180.0
1183 double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
1184 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1185 bug_error->setDoubleValue( diff );
1187 fdm_bug_error->setDoubleValue( diff );
1189 // Calculate true heading error normalized to +/- 180.0
1190 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
1191 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1192 true_error->setDoubleValue( diff );
1194 // Calculate nav1 target heading error normalized to +/- 180.0
1195 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
1196 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1197 true_nav1->setDoubleValue( diff );
1199 // Calculate true groundtrack
1200 diff = target_nav1->getDoubleValue() - track->getDoubleValue();
1201 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1202 true_track_nav1->setDoubleValue( diff );
1204 // Calculate nav1 selected course error normalized to +/- 180.0
1205 diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
1206 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
1207 nav1_course_error->setDoubleValue( diff );
1209 // Calculate vertical speed in fpm
1210 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
1213 // Calculate static port pressure rate in [inhg/s].
1214 // Used to determine vertical speed.
1216 double current_static_pressure = static_pressure->getDoubleValue();
1217 double current_pressure_rate =
1218 ( current_static_pressure - last_static_pressure ) / dt;
1220 pressure_rate->setDoubleValue(current_pressure_rate);
1221 last_static_pressure = current_static_pressure;
1226 void FGXMLAutopilotGroup::reinit()
1228 for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
1229 FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
1230 if( ap == NULL ) continue; // ?
1231 remove_subsystem( _autopilotNames[i] );
1234 _autopilotNames.clear();
1238 void FGXMLAutopilotGroup::init()
1240 PropertyList autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
1241 if( autopilotNodes.size() == 0 ) {
1242 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
1246 for( PropertyList::size_type i = 0; i < autopilotNodes.size(); i++ ) {
1247 SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
1248 if( pathNode == NULL ) {
1249 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
1254 SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
1255 if( nameNode != NULL ) {
1256 apName = nameNode->getStringValue();
1258 std::ostringstream buf;
1259 buf << "unnamed_autopilot_" << i;
1263 if( get_subsystem( apName.c_str() ) != NULL ) {
1264 SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
1268 SGPath config( globals->get_fg_root() );
1269 config.append( pathNode->getStringValue() );
1271 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
1273 FGXMLAutopilot * ap = new FGXMLAutopilot;
1275 SGPropertyNode_ptr root = new SGPropertyNode();
1276 readProperties( config.str(), root );
1279 if ( ! ap->build( root ) ) {
1280 SG_LOG( SG_ALL, SG_ALERT,
1281 "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
1285 } catch (const sg_exception& e) {
1286 SG_LOG( SG_AUTOPILOT, SG_ALERT, "Failed to load autopilot configuration: "
1287 << config.str() << ":" << e.getMessage() );
1292 SG_LOG( SG_AUTOPILOT, SG_INFO, "adding autopilot subsystem " << apName );
1293 set_subsystem( apName, ap );
1294 _autopilotNames.push_back( apName );
1297 SGSubsystemGroup::init();
1300 FGXMLAutopilot::FGXMLAutopilot() {
1304 FGXMLAutopilot::~FGXMLAutopilot() {
1308 /* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
1309 * and configure/add the digital filters specified in that file
1311 void FGXMLAutopilot::init()
1316 void FGXMLAutopilot::reinit() {
1322 void FGXMLAutopilot::bind() {
1325 void FGXMLAutopilot::unbind() {
1328 bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
1329 SGPropertyNode *node;
1332 int count = config_props->nChildren();
1333 for ( i = 0; i < count; ++i ) {
1334 node = config_props->getChild(i);
1335 string name = node->getName();
1336 // cout << name << endl;
1337 SG_LOG( SG_AUTOPILOT, SG_BULK, "adding autopilot component " << name );
1338 if ( name == "pid-controller" ) {
1339 components.push_back( new FGPIDController( node ) );
1340 } else if ( name == "pi-simple-controller" ) {
1341 components.push_back( new FGPISimpleController( node ) );
1342 } else if ( name == "predict-simple" ) {
1343 components.push_back( new FGPredictor( node ) );
1344 } else if ( name == "filter" ) {
1345 components.push_back( new FGDigitalFilter( node ) );
1346 } else if ( name == "logic" ) {
1347 components.push_back( new FGXMLAutoLogic( node ) );
1348 } else if ( name == "flipflop" ) {
1349 FGXMLAutoFlipFlop * flipFlop = NULL;
1350 SGPropertyNode_ptr typeNode = node->getNode( "type" );
1352 if( typeNode != NULL ) val = typeNode->getStringValue();
1353 val = simgear::strutils::strip(val);
1354 if( val == "RS" || val =="SR" ) flipFlop = new FGXMLAutoRSFlipFlop( node );
1355 else if( val == "JK" ) flipFlop = new FGXMLAutoJKFlipFlop( node );
1356 else if( val == "T" ) flipFlop = new FGXMLAutoTFlipFlop( node );
1357 else if( val == "D" ) flipFlop = new FGXMLAutoDFlipFlop( node );
1358 if( flipFlop == NULL ) {
1359 SG_LOG(SG_AUTOPILOT, SG_ALERT, "can't create flipflop of type: " << val);
1362 components.push_back( flipFlop );
1364 SG_LOG( SG_AUTOPILOT, SG_WARN, "Unknown top level autopilot section: " << name );
1373 * Update the list of autopilot components
1376 void FGXMLAutopilot::update( double dt )
1379 for ( i = 0; i < components.size(); ++i ) {
1380 components[i]->update( dt );