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 <simgear/structure/SGExpression.hxx>
37 #include <Main/fg_props.hxx>
38 #include <Main/globals.hxx>
39 #include <Main/util.hxx>
41 #include "xmlauto.hxx"
46 using simgear::PropertyList;
51 FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
53 SGPropertyNode_ptr minNode = root->getChild( "min" );
54 SGPropertyNode_ptr maxNode = root->getChild( "max" );
55 if( minNode == NULL || maxNode == NULL ) {
56 SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
58 minPeriod = new FGXMLAutoInput( minNode );
59 maxPeriod = new FGXMLAutoInput( maxNode );
63 double FGPeriodicalValue::normalize( double value )
65 if( !(minPeriod && maxPeriod )) return value;
67 double p1 = minPeriod->get_value();
68 double p2 = maxPeriod->get_value();
70 double min = std::min<double>(p1,p2);
71 double max = std::max<double>(p1,p2);
72 double phase = fabs(max - min);
74 if( phase > SGLimitsd::min() ) {
75 while( value < min ) value += phase;
76 while( value >= max ) value -= phase;
78 value = min; // phase is zero
84 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
88 parse( node, value, offset, scale );
92 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
107 if( (n = node->getChild("condition")) != NULL ) {
108 _condition = sgReadCondition(fgGetNode("/"), n);
111 if( (n = node->getChild( "scale" )) != NULL ) {
112 scale = new FGXMLAutoInput( n, aScale );
115 if( (n = node->getChild( "offset" )) != NULL ) {
116 offset = new FGXMLAutoInput( n, aOffset );
119 if( (n = node->getChild( "max" )) != NULL ) {
120 max = new FGXMLAutoInput( n );
123 if( (n = node->getChild( "min" )) != NULL ) {
124 min = new FGXMLAutoInput( n );
127 if( (n = node->getChild( "abs" )) != NULL ) {
128 abs = n->getBoolValue();
131 if( (n = node->getChild( "period" )) != NULL ) {
132 periodical = new FGPeriodicalValue( n );
135 SGPropertyNode *valueNode = node->getChild( "value" );
136 if ( valueNode != NULL ) {
137 value = valueNode->getDoubleValue();
140 if ((n = node->getChild("expression")) != NULL) {
141 _expression = SGReadDoubleExpression(fgGetNode("/"), n->getChild(0));
145 n = node->getChild( "property" );
146 // if no <property> element, check for <prop> element for backwards
149 n = node->getChild( "prop" );
152 property = fgGetNode( n->getStringValue(), true );
153 if ( valueNode != NULL ) {
154 // initialize property with given value
155 // if both <prop> and <value> exist
156 double s = get_scale();
158 property->setDoubleValue( (value - get_offset())/s );
160 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
164 } // of have a <property> or <prop>
167 if (valueNode == NULL) {
168 // no <value>, <prop> or <expression> element, use text node
169 const char * textnode = node->getStringValue();
171 // try to convert to a double value. If the textnode does not start with a number
172 // endp will point to the beginning of the string. We assume this should be
174 value = strtod( textnode, &endp );
175 if( endp == textnode ) {
176 property = fgGetNode( textnode, true );
181 void FGXMLAutoInput::set_value( double aValue )
186 double s = get_scale();
188 property->setDoubleValue( (aValue - get_offset())/s );
190 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
193 double FGXMLAutoInput::get_value()
196 // compute the expression value
197 value = _expression->getValue(NULL);
198 } else if( property != NULL ) {
199 value = property->getDoubleValue();
203 value *= scale->get_value();
206 value += offset->get_value();
209 double m = min->get_value();
215 double m = max->get_value();
221 value = periodical->normalize( value );
224 return abs ? fabs(value) : value;
227 FGXMLAutoComponent::FGXMLAutoComponent() :
230 enable_value( NULL ),
231 passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
232 honor_passive( false ),
234 feedback_if_disabled( false ),
240 FGXMLAutoComponent::~FGXMLAutoComponent()
245 void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
247 SGPropertyNode *prop;
248 for (int i = 0; i < aNode->nChildren(); ++i ) {
249 SGPropertyNode *child = aNode->getChild(i);
250 string cname(child->getName());
252 if (parseNodeHook(cname, child)) {
253 // derived class handled it, fine
254 } else if ( cname == "name" ) {
255 name = child->getStringValue();
256 } else if ( cname == "feedback-if-disabled" ) {
257 feedback_if_disabled = child->getBoolValue();
258 } else if ( cname == "debug" ) {
259 debug = child->getBoolValue();
260 } else if ( cname == "enable" ) {
261 if( (prop = child->getChild("condition")) != NULL ) {
262 _condition = sgReadCondition(fgGetNode("/"), prop);
264 if ( (prop = child->getChild( "property" )) != NULL ) {
265 enable_prop = fgGetNode( prop->getStringValue(), true );
268 if ( (prop = child->getChild( "prop" )) != NULL ) {
269 enable_prop = fgGetNode( prop->getStringValue(), true );
272 if ( (prop = child->getChild( "value" )) != NULL ) {
274 enable_value = new string(prop->getStringValue());
277 if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
278 honor_passive = prop->getBoolValue();
280 } else if ( cname == "input" ) {
281 valueInput.push_back( new FGXMLAutoInput( child ) );
282 } else if ( cname == "reference" ) {
283 referenceInput.push_back( new FGXMLAutoInput( child ) );
284 } else if ( cname == "output" ) {
285 // grab all <prop> and <property> childs
287 // backwards compatibility: allow <prop> elements
288 for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) {
289 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
290 output_list.push_back( tmp );
293 for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) {
294 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
295 output_list.push_back( tmp );
299 // no <prop> elements, text node of <output> is property name
301 output_list.push_back( fgGetNode(child->getStringValue(), true ) );
302 } else if ( cname == "config" ) {
304 } else if ( cname == "min" ) {
305 uminInput.push_back( new FGXMLAutoInput( child ) );
306 } else if ( cname == "u_min" ) {
307 uminInput.push_back( new FGXMLAutoInput( child ) );
308 } else if ( cname == "max" ) {
309 umaxInput.push_back( new FGXMLAutoInput( child ) );
310 } else if ( cname == "u_max" ) {
311 umaxInput.push_back( new FGXMLAutoInput( child ) );
312 } else if ( cname == "period" ) {
313 periodical = new FGPeriodicalValue( child );
315 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:"
316 << cname << " in section " << name);
317 throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
319 } // of top-level iteration
322 void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
324 for (int i = 0; i < aConfig->nChildren(); ++i ) {
325 SGPropertyNode *child = aConfig->getChild(i);
326 string cname(child->getName());
328 if (parseConfigHook(cname, child)) {
329 // derived class handled it, fine
330 } else if ( cname == "min" ) {
331 uminInput.push_back( new FGXMLAutoInput( child ) );
332 } else if ( cname == "u_min" ) {
333 uminInput.push_back( new FGXMLAutoInput( child ) );
334 } else if ( cname == "max" ) {
335 umaxInput.push_back( new FGXMLAutoInput( child ) );
336 } else if ( cname == "u_max" ) {
337 umaxInput.push_back( new FGXMLAutoInput( child ) );
339 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:"
340 << cname << " in section " << name);
341 throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
343 } // of config iteration
346 bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
351 bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
356 bool FGXMLAutoComponent::isPropertyEnabled()
359 return _condition->test();
363 return *enable_value == enable_prop->getStringValue();
365 return enable_prop->getBoolValue();
371 void FGXMLAutoComponent::do_feedback_if_disabled()
373 if( output_list.size() > 0 ) {
374 FGXMLAutoInput * input = valueInput.get_active();
376 input->set_value( output_list[0]->getDoubleValue() );
380 double FGXMLAutoComponent::clamp( double value )
382 //If this is a periodical value, normalize it into our domain
385 value = periodical->normalize( value );
387 // clamp, if either min or max is defined
388 if( uminInput.size() + umaxInput.size() > 0 ) {
389 double d = umaxInput.get_value( 0.0 );
390 if( value > d ) value = d;
391 d = uminInput.get_value( 0.0 );
392 if( value < d ) value = d;
397 FGPIDController::FGPIDController( SGPropertyNode *node ):
398 FGXMLAutoComponent(),
412 bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
415 desiredTs = aNode->getDoubleValue();
416 } else if (aName == "Kp") {
417 Kp.push_back( new FGXMLAutoInput(aNode) );
418 } else if (aName == "Ti") {
419 Ti.push_back( new FGXMLAutoInput(aNode) );
420 } else if (aName == "Td") {
421 Td.push_back( new FGXMLAutoInput(aNode) );
422 } else if (aName == "beta") {
423 beta = aNode->getDoubleValue();
424 } else if (aName == "alpha") {
425 alpha = aNode->getDoubleValue();
426 } else if (aName == "gamma") {
427 gamma = aNode->getDoubleValue();
429 // unhandled by us, let the base class try it
439 * Ok! Here is the PID controller algorithm that I would like to see
442 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
443 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
445 * u_n = u_n-1 + delta_u_n
449 * delta_u : The incremental output
450 * Kp : Proportional gain
451 * ep : Proportional error with reference weighing
454 * beta : Weighing factor
455 * r : Reference (setpoint)
456 * y : Process value, measured
459 * Ts : Sampling interval
460 * Ti : Integrator time
461 * Td : Derivator time
462 * edf : Derivate error with reference weighing and filtering
463 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
466 * Tf = alpha * Td , where alpha usually is set to 0.1
467 * ed : Unfiltered derivate error with reference weighing
470 * gamma : Weighing factor
472 * u : absolute output
474 * Index n means the n'th value.
479 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
480 * Kp , Ti , Td , Ts (is the sampling time available?)
487 void FGPIDController::update( double dt ) {
490 double delta_u_n = 0.0; // incremental output
491 double u_n = 0.0; // absolute output
492 double Ts; // sampling interval (sec)
494 double u_min = uminInput.get_value();
495 double u_max = umaxInput.get_value();
498 if ( elapsedTime <= desiredTs ) {
499 // do nothing if time step is not positive (i.e. no time has
506 if ( isPropertyEnabled() ) {
508 // first time being enabled, seed u_n with current
509 // property tree value
510 u_n = get_output_value();
519 if ( enabled && Ts > 0.0) {
520 if ( debug ) cout << "Updating " << get_name()
521 << " Ts " << Ts << endl;
523 double y_n = valueInput.get_value();
524 double r_n = referenceInput.get_value();
526 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
528 // Calculates proportional error:
529 double ep_n = beta * r_n - y_n;
530 if ( debug ) cout << " ep_n = " << ep_n;
531 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
535 if ( debug ) cout << " e_n = " << e_n;
537 double td = Td.get_value();
538 if ( td > 0.0 ) { // do we need to calcluate derivative error?
540 // Calculates derivate error:
541 double ed_n = gamma * r_n - y_n;
542 if ( debug ) cout << " ed_n = " << ed_n;
544 // Calculates filter time:
545 double Tf = alpha * td;
546 if ( debug ) cout << " Tf = " << Tf;
548 // Filters the derivate error:
549 edf_n = edf_n_1 / (Ts/Tf + 1)
550 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
551 if ( debug ) cout << " edf_n = " << edf_n;
553 edf_n_2 = edf_n_1 = edf_n = 0.0;
556 // Calculates the incremental output:
557 double ti = Ti.get_value();
559 delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
561 + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
564 cout << " delta_u_n = " << delta_u_n << endl;
565 cout << "P:" << Kp.get_value() * (ep_n - ep_n_1)
566 << " I:" << Kp.get_value() * ((Ts/ti) * e_n)
567 << " D:" << Kp.get_value() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
572 // Integrator anti-windup logic:
573 if ( delta_u_n > (u_max - u_n_1) ) {
574 delta_u_n = u_max - u_n_1;
575 if ( debug ) cout << " max saturation " << endl;
576 } else if ( delta_u_n < (u_min - u_n_1) ) {
577 delta_u_n = u_min - u_n_1;
578 if ( debug ) cout << " min saturation " << endl;
581 // Calculates absolute output:
582 u_n = u_n_1 + delta_u_n;
583 if ( debug ) cout << " output = " << u_n << endl;
585 // Updates indexed values;
591 set_output_value( u_n );
592 } else if ( !enabled ) {
594 edf_n_2 = edf_n_1 = edf_n = 0.0;
599 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
600 FGXMLAutoComponent(),
606 bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
609 Kp.push_back( new FGXMLAutoInput(aNode) );
610 } else if (aName == "Ki") {
611 Ki.push_back( new FGXMLAutoInput(aNode) );
613 // unhandled by us, let the base class try it
620 void FGPISimpleController::update( double dt ) {
622 if ( isPropertyEnabled() ) {
624 // we have just been enabled, zero out int_sum
634 if ( debug ) cout << "Updating " << get_name() << endl;
635 double y_n = valueInput.get_value();
636 double r_n = referenceInput.get_value();
638 double error = r_n - y_n;
639 if ( debug ) cout << "input = " << y_n
640 << " reference = " << r_n
641 << " error = " << error
644 double prop_comp = clamp(error * Kp.get_value());
645 int_sum += error * Ki.get_value() * dt;
648 double output = prop_comp + int_sum;
649 double clamped_output = clamp( output );
650 if( output != clamped_output ) // anti-windup
651 int_sum = clamped_output - prop_comp;
653 if ( debug ) cout << "prop_comp = " << prop_comp
654 << " int_sum = " << int_sum << endl;
656 set_output_value( clamped_output );
657 if ( debug ) cout << "output = " << clamped_output << endl;
662 FGPredictor::FGPredictor ( SGPropertyNode *node ):
663 FGXMLAutoComponent(),
669 bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
671 if (aName == "seconds") {
672 seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
673 } else if (aName == "filter-gain") {
674 filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
682 void FGPredictor::update( double dt ) {
684 Simple moving average filter converts input value to predicted value "seconds".
686 Smoothing as described by Curt Olson:
687 gain would be valid in the range of 0 - 1.0
688 1.0 would mean no filtering.
689 0.0 would mean no input.
690 0.5 would mean (1 part past value + 1 part current value) / 2
691 0.1 would mean (9 parts past value + 1 part current value) / 10
692 0.25 would mean (3 parts past value + 1 part current value) / 4
696 double ivalue = valueInput.get_value();
698 if ( isPropertyEnabled() ) {
700 // first time being enabled
712 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
713 average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
715 // calculate output with filter gain adjustment
716 double output = ivalue +
717 (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) +
718 filter_gain.get_value() * (current * seconds.get_value());
719 output = clamp( output );
720 set_output_value( output );
727 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
728 FGXMLAutoComponent(),
733 output.resize(2, 0.0);
734 input.resize(samplesInput.get_value() + 1, 0.0);
738 bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
740 if (aName == "type" ) {
741 string val(aNode->getStringValue());
742 if ( val == "exponential" ) {
743 filterType = exponential;
744 } else if (val == "double-exponential") {
745 filterType = doubleExponential;
746 } else if (val == "moving-average") {
747 filterType = movingAverage;
748 } else if (val == "noise-spike") {
749 filterType = noiseSpike;
750 } else if (val == "gain") {
752 } else if (val == "reciprocal") {
753 filterType = reciprocal;
754 } else if (val == "differential") {
755 filterType = differential;
756 // use a constant of two samples for current and previous input value
757 samplesInput.push_back( new FGXMLAutoInput(NULL, 2.0 ) );
759 } else if (aName == "filter-time" ) {
760 TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
761 if( filterType == none ) filterType = exponential;
762 } else if (aName == "samples" ) {
763 samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
764 if( filterType == none ) filterType = movingAverage;
765 } else if (aName == "max-rate-of-change" ) {
766 rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
767 if( filterType == none ) filterType = noiseSpike;
768 } else if (aName == "gain" ) {
769 gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
770 if( filterType == none ) filterType = gain;
772 return false; // not handled by us, let the base class try
778 void FGDigitalFilter::update(double dt)
780 if ( isPropertyEnabled() ) {
782 input.push_front(valueInput.get_value()-referenceInput.get_value());
783 input.resize(samplesInput.get_value() + 1, 0.0);
786 // first time being enabled, initialize output to the
787 // value of the output property to avoid bumping.
788 output.push_front(get_output_value());
797 if ( !enabled || dt < SGLimitsd::min() )
803 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
806 if( debug ) cout << "Updating " << get_name()
807 << " dt " << dt << endl;
809 if (filterType == exponential)
811 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
812 output.push_front(alpha * input[0] +
813 (1 - alpha) * output[0]);
815 else if (filterType == doubleExponential)
817 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
818 output.push_front(alpha * alpha * input[0] +
819 2 * (1 - alpha) * output[0] -
820 (1 - alpha) * (1 - alpha) * output[1]);
822 else if (filterType == movingAverage)
824 output.push_front(output[0] +
825 (input[0] - input.back()) / samplesInput.get_value());
827 else if (filterType == noiseSpike)
829 double maxChange = rateOfChangeInput.get_value() * dt;
831 if ((output[0] - input[0]) > maxChange)
833 output.push_front(output[0] - maxChange);
835 else if ((output[0] - input[0]) < -maxChange)
837 output.push_front(output[0] + maxChange);
839 else if (fabs(input[0] - output[0]) <= maxChange)
841 output.push_front(input[0]);
844 else if (filterType == gain)
846 output[0] = gainInput.get_value() * input[0];
848 else if (filterType == reciprocal)
850 if (input[0] != 0.0) {
851 output[0] = gainInput.get_value() / input[0];
854 else if (filterType == differential)
856 if( dt > SGLimitsd::min() ) {
857 output[0] = (input[0]-input[1]) * TfInput.get_value() / dt;
861 output[0] = clamp(output[0]) ;
862 set_output_value( output[0] );
868 cout << "input:" << input[0]
869 << "\toutput:" << output[0] << endl;
873 FGXMLAutoLogic::FGXMLAutoLogic(SGPropertyNode * node ) :
874 FGXMLAutoComponent(),
880 bool FGXMLAutoLogic::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
882 if (aName == "input") {
883 input = sgReadCondition( fgGetNode("/"), aNode );
884 } else if (aName == "inverted") {
885 inverted = aNode->getBoolValue();
893 void FGXMLAutoLogic::update(double dt)
895 if ( isPropertyEnabled() ) {
897 // we have just been enabled
905 if ( !enabled || dt < SGLimitsd::min() )
908 if( input == NULL ) {
909 if ( debug ) cout << "No input for " << get_name() << endl;
913 bool i = input->test();
915 if ( debug ) cout << "Updating " << get_name() << ": " << (inverted ? !i : i) << endl;
917 set_output_value( i );
920 class FGXMLAutoRSFlipFlop : public FGXMLAutoFlipFlop {
924 FGXMLAutoRSFlipFlop( SGPropertyNode * node ) :
925 FGXMLAutoFlipFlop( node ) {
926 // type exists here, otherwise we were not constructed
927 string val = node->getNode( "type" )->getStringValue();
931 void updateState( double dt ) {
933 if( sInput == NULL ) {
934 if ( debug ) cout << "No set (S) input for " << get_name() << endl;
938 if( rInput == NULL ) {
939 if ( debug ) cout << "No reset (R) input for " << get_name() << endl;
943 bool s = sInput->test();
944 bool r = rInput->test();
946 // s == false && q == false: no change, keep state
949 if( _rs ) { // RS: reset is dominant
950 if( s ) q = true; // set
951 if( r ) q = false; // reset
952 } else { // SR: set is dominant
953 if( r ) q = false; // reset
954 if( s ) q = true; // set
956 if( inverted ) q = !q;
958 if ( debug ) cout << "Updating " << get_name() << ":"
961 << ",q=" << q << endl;
962 set_output_value( q );
964 if ( debug ) cout << "Updating " << get_name() << ":"
967 << ",q=unchanged" << endl;
972 class FGXMLAutoJKFlipFlop : public FGXMLAutoFlipFlop {
976 FGXMLAutoJKFlipFlop( SGPropertyNode * node ) :
977 FGXMLAutoFlipFlop( node ),
980 void updateState( double dt ) {
982 if( jInput == NULL ) {
983 if ( debug ) cout << "No set (j) input for " << get_name() << endl;
987 if( kInput == NULL ) {
988 if ( debug ) cout << "No reset (k) input for " << get_name() << endl;
992 bool j = jInput->test();
993 bool k = kInput->test();
995 if the user provided a clock input, use it.
996 Otherwise use framerate as clock
997 This JK operates on the raising edge.
999 bool c = clockInput ? clockInput->test() : false;
1000 bool raisingEdge = clockInput ? (c && !clock) : true;
1003 if( !raisingEdge ) return;
1005 bool q = get_bool_output_value();
1006 // j == false && k == false: no change, keep state
1011 if( j ) q = true; // set
1012 if( k ) q = false; // reset
1014 if( inverted ) q = !q;
1016 if ( debug ) cout << "Updating " << get_name() << ":"
1019 << ",q=" << q << endl;
1020 set_output_value( q );
1022 if ( debug ) cout << "Updating " << get_name() << ":"
1025 << ",q=unchanged" << endl;
1030 class FGXMLAutoDFlipFlop : public FGXMLAutoFlipFlop {
1034 FGXMLAutoDFlipFlop( SGPropertyNode * node ) :
1035 FGXMLAutoFlipFlop( node ),
1038 void updateState( double dt ) {
1040 if( clockInput == NULL ) {
1041 if ( debug ) cout << "No (clock) input for " << get_name() << endl;
1045 if( dInput == NULL ) {
1046 if ( debug ) cout << "No (D) input for " << get_name() << endl;
1050 bool d = dInput->test();
1052 // check the clock - raising edge
1053 bool c = clockInput->test();
1054 bool raisingEdge = c && !clock;
1059 if( inverted ) q = !q;
1061 if ( debug ) cout << "Updating " << get_name() << ":"
1063 << ",q=" << q << endl;
1064 set_output_value( q );
1066 if ( debug ) cout << "Updating " << get_name() << ":"
1068 << ",q=unchanged" << endl;
1073 class FGXMLAutoTFlipFlop : public FGXMLAutoFlipFlop {
1077 FGXMLAutoTFlipFlop( SGPropertyNode * node ) :
1078 FGXMLAutoFlipFlop( node ),
1081 void updateState( double dt ) {
1083 if( clockInput == NULL ) {
1084 if ( debug ) cout << "No (clock) input for " << get_name() << endl;
1088 // check the clock - raising edge
1089 bool c = clockInput->test();
1090 bool raisingEdge = c && !clock;
1094 bool q = !get_bool_output_value(); // toggle
1095 if( inverted ) q = !q; // doesnt really make sense for a T-FF
1097 if ( debug ) cout << "Updating " << get_name() << ":"
1098 << ",q=" << q << endl;
1099 set_output_value( q );
1101 if ( debug ) cout << "Updating " << get_name() << ":"
1102 << ",q=unchanged" << endl;
1107 FGXMLAutoFlipFlop::FGXMLAutoFlipFlop(SGPropertyNode * node ) :
1108 FGXMLAutoComponent(),
1114 bool FGXMLAutoFlipFlop::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
1116 if (aName == "set"||aName == "S") {
1117 sInput = sgReadCondition( fgGetNode("/"), aNode );
1118 } else if (aName == "reset" || aName == "R" ) {
1119 rInput = sgReadCondition( fgGetNode("/"), aNode );
1120 } else if (aName == "J") {
1121 jInput = sgReadCondition( fgGetNode("/"), aNode );
1122 } else if (aName == "K") {
1123 kInput = sgReadCondition( fgGetNode("/"), aNode );
1124 } else if (aName == "T") {
1125 tInput = sgReadCondition( fgGetNode("/"), aNode );
1126 } else if (aName == "D") {
1127 dInput = sgReadCondition( fgGetNode("/"), aNode );
1128 } else if (aName == "clock") {
1129 clockInput = sgReadCondition( fgGetNode("/"), aNode );
1130 } else if (aName == "inverted") {
1131 inverted = aNode->getBoolValue();
1132 } else if (aName == "type") {
1133 // ignore element type, evaluated by loader
1141 void FGXMLAutoFlipFlop::update(double dt)
1143 if ( isPropertyEnabled() ) {
1145 // we have just been enabled
1146 // initialize to a bool property
1147 set_output_value( get_bool_output_value() );
1155 if ( !enabled || dt < SGLimitsd::min() )
1162 FGXMLAutopilotGroup::FGXMLAutopilotGroup() :
1164 #ifdef XMLAUTO_USEHELPER
1165 ,average(0.0), // average/filtered prediction
1166 v_last(0.0), // last velocity
1167 last_static_pressure(0.0),
1168 vel(fgGetNode( "/velocities/airspeed-kt", true )),
1169 // Estimate speed in 5,10 seconds
1170 lookahead5(fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true )),
1171 lookahead10(fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true )),
1172 bug(fgGetNode( "/autopilot/settings/heading-bug-deg", true )),
1173 mag_hdg(fgGetNode( "/orientation/heading-magnetic-deg", true )),
1174 bug_error(fgGetNode( "/autopilot/internal/heading-bug-error-deg", true )),
1175 fdm_bug_error(fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true )),
1176 target_true(fgGetNode( "/autopilot/settings/true-heading-deg", true )),
1177 true_hdg(fgGetNode( "/orientation/heading-deg", true )),
1178 true_error(fgGetNode( "/autopilot/internal/true-heading-error-deg", true )),
1179 target_nav1(fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true )),
1180 true_nav1(fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true )),
1181 true_track_nav1(fgGetNode( "/autopilot/internal/nav1-track-error-deg", true )),
1182 nav1_course_error(fgGetNode( "/autopilot/internal/nav1-course-error", true )),
1183 nav1_selected_course(fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true )),
1184 vs_fps(fgGetNode( "/velocities/vertical-speed-fps", true )),
1185 vs_fpm(fgGetNode( "/autopilot/internal/vert-speed-fpm", true )),
1186 static_pressure(fgGetNode( "/systems/static[0]/pressure-inhg", true )),
1187 pressure_rate(fgGetNode( "/autopilot/internal/pressure-rate", true )),
1188 track(fgGetNode( "/orientation/track-deg", true ))
1193 void FGXMLAutopilotGroup::update( double dt )
1195 // update all configured autopilots
1196 SGSubsystemGroup::update( dt );
1197 #ifdef XMLAUTO_USEHELPER
1198 // update helper values
1199 double v = vel->getDoubleValue();
1202 a = (v - v_last) / dt;
1205 average = (1.0 - dt) * average + dt * a;
1210 lookahead5->setDoubleValue( v + average * 5.0 );
1211 lookahead10->setDoubleValue( v + average * 10.0 );
1215 // Calculate heading bug error normalized to +/- 180.0
1216 double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
1217 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1218 bug_error->setDoubleValue( diff );
1220 fdm_bug_error->setDoubleValue( diff );
1222 // Calculate true heading error normalized to +/- 180.0
1223 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
1224 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1225 true_error->setDoubleValue( diff );
1227 // Calculate nav1 target heading error normalized to +/- 180.0
1228 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
1229 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1230 true_nav1->setDoubleValue( diff );
1232 // Calculate true groundtrack
1233 diff = target_nav1->getDoubleValue() - track->getDoubleValue();
1234 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
1235 true_track_nav1->setDoubleValue( diff );
1237 // Calculate nav1 selected course error normalized to +/- 180.0
1238 diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
1239 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
1240 nav1_course_error->setDoubleValue( diff );
1242 // Calculate vertical speed in fpm
1243 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
1246 // Calculate static port pressure rate in [inhg/s].
1247 // Used to determine vertical speed.
1249 double current_static_pressure = static_pressure->getDoubleValue();
1250 double current_pressure_rate =
1251 ( current_static_pressure - last_static_pressure ) / dt;
1253 pressure_rate->setDoubleValue(current_pressure_rate);
1254 last_static_pressure = current_static_pressure;
1259 void FGXMLAutopilotGroup::reinit()
1261 for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
1262 FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
1263 if( ap == NULL ) continue; // ?
1264 remove_subsystem( _autopilotNames[i] );
1267 _autopilotNames.clear();
1271 void FGXMLAutopilotGroup::init()
1273 PropertyList autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
1274 if( autopilotNodes.size() == 0 ) {
1275 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
1279 for( PropertyList::size_type i = 0; i < autopilotNodes.size(); i++ ) {
1280 SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
1281 if( pathNode == NULL ) {
1282 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
1287 SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
1288 if( nameNode != NULL ) {
1289 apName = nameNode->getStringValue();
1291 std::ostringstream buf;
1292 buf << "unnamed_autopilot_" << i;
1296 if( get_subsystem( apName.c_str() ) != NULL ) {
1297 SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
1301 SGPath config( globals->get_fg_root() );
1302 config.append( pathNode->getStringValue() );
1304 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
1306 FGXMLAutopilot * ap = new FGXMLAutopilot;
1308 SGPropertyNode_ptr root = new SGPropertyNode();
1309 readProperties( config.str(), root );
1312 if ( ! ap->build( root ) ) {
1313 SG_LOG( SG_ALL, SG_ALERT,
1314 "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
1318 } catch (const sg_exception& e) {
1319 SG_LOG( SG_AUTOPILOT, SG_ALERT, "Failed to load autopilot configuration: "
1320 << config.str() << ":" << e.getMessage() );
1325 SG_LOG( SG_AUTOPILOT, SG_INFO, "adding autopilot subsystem " << apName );
1326 set_subsystem( apName, ap );
1327 _autopilotNames.push_back( apName );
1330 SGSubsystemGroup::init();
1333 FGXMLAutopilot::FGXMLAutopilot() {
1337 FGXMLAutopilot::~FGXMLAutopilot() {
1341 /* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
1342 * and configure/add the digital filters specified in that file
1344 void FGXMLAutopilot::init()
1349 void FGXMLAutopilot::reinit() {
1355 void FGXMLAutopilot::bind() {
1358 void FGXMLAutopilot::unbind() {
1361 bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
1362 SGPropertyNode *node;
1365 int count = config_props->nChildren();
1366 for ( i = 0; i < count; ++i ) {
1367 node = config_props->getChild(i);
1368 string name = node->getName();
1369 // cout << name << endl;
1370 SG_LOG( SG_AUTOPILOT, SG_BULK, "adding autopilot component " << name );
1371 if ( name == "pid-controller" ) {
1372 components.push_back( new FGPIDController( node ) );
1373 } else if ( name == "pi-simple-controller" ) {
1374 components.push_back( new FGPISimpleController( node ) );
1375 } else if ( name == "predict-simple" ) {
1376 components.push_back( new FGPredictor( node ) );
1377 } else if ( name == "filter" ) {
1378 components.push_back( new FGDigitalFilter( node ) );
1379 } else if ( name == "logic" ) {
1380 components.push_back( new FGXMLAutoLogic( node ) );
1381 } else if ( name == "flipflop" ) {
1382 FGXMLAutoFlipFlop * flipFlop = NULL;
1383 SGPropertyNode_ptr typeNode = node->getNode( "type" );
1385 if( typeNode != NULL ) val = typeNode->getStringValue();
1386 val = simgear::strutils::strip(val);
1387 if( val == "RS" || val =="SR" ) flipFlop = new FGXMLAutoRSFlipFlop( node );
1388 else if( val == "JK" ) flipFlop = new FGXMLAutoJKFlipFlop( node );
1389 else if( val == "T" ) flipFlop = new FGXMLAutoTFlipFlop( node );
1390 else if( val == "D" ) flipFlop = new FGXMLAutoDFlipFlop( node );
1391 if( flipFlop == NULL ) {
1392 SG_LOG(SG_AUTOPILOT, SG_ALERT, "can't create flipflop of type: " << val);
1395 components.push_back( flipFlop );
1397 SG_LOG( SG_AUTOPILOT, SG_WARN, "Unknown top level autopilot section: " << name );
1406 * Update the list of autopilot components
1409 void FGXMLAutopilot::update( double dt )
1412 for ( i = 0; i < components.size(); ++i ) {
1413 components[i]->update( dt );