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/structure/exception.hxx>
30 #include <simgear/misc/sg_path.hxx>
31 #include <simgear/sg_inlines.h>
32 #include <simgear/props/props_io.hxx>
34 #include <Main/fg_props.hxx>
35 #include <Main/globals.hxx>
36 #include <Main/util.hxx>
38 #include "xmlauto.hxx"
43 using simgear::PropertyList;
45 FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
47 SGPropertyNode_ptr minNode = root->getChild( "min" );
48 SGPropertyNode_ptr maxNode = root->getChild( "max" );
49 if( minNode == NULL || maxNode == NULL ) {
50 SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
52 minPeriod = new FGXMLAutoInput( minNode );
53 maxPeriod = new FGXMLAutoInput( maxNode );
57 double FGPeriodicalValue::normalize( double value )
59 if( !(minPeriod && maxPeriod )) return value;
61 double p1 = minPeriod->get_value();
62 double p2 = maxPeriod->get_value();
64 double min = std::min<double>(p1,p2);
65 double max = std::max<double>(p1,p2);
66 double phase = fabs(max - min);
68 if( phase > SGLimitsd::min() ) {
69 while( value < min ) value += phase;
70 while( value >= max ) value -= phase;
72 value = min; // phase is zero
78 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
83 parse( node, value, offset, scale );
87 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
102 if( (n = node->getChild("condition")) != NULL ) {
103 _condition = sgReadCondition(fgGetNode("/"), n);
106 if( (n = node->getChild( "scale" )) != NULL ) {
107 scale = new FGXMLAutoInput( n, aScale );
110 if( (n = node->getChild( "offset" )) != NULL ) {
111 offset = new FGXMLAutoInput( n, aOffset );
114 if( (n = node->getChild( "max" )) != NULL ) {
115 max = new FGXMLAutoInput( n );
118 if( (n = node->getChild( "min" )) != NULL ) {
119 min = new FGXMLAutoInput( n );
122 if( (n = node->getChild( "abs" )) != NULL ) {
123 abs = n->getBoolValue();
126 if( (n = node->getChild( "period" )) != NULL ) {
127 periodical = new FGPeriodicalValue( n );
130 SGPropertyNode *valueNode = node->getChild( "value" );
131 if ( valueNode != NULL ) {
132 value = valueNode->getDoubleValue();
135 n = node->getChild( "property" );
136 // if no <property> element, check for <prop> element for backwards
139 n = node->getChild( "prop" );
142 property = fgGetNode( n->getStringValue(), true );
143 if ( valueNode != NULL ) {
144 // initialize property with given value
145 // if both <prop> and <value> exist
146 double s = get_scale();
148 property->setDoubleValue( (value - get_offset())/s );
150 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
154 if ( n == NULL && valueNode == NULL ) {
155 // no <value> element and no <prop> element, use text node
156 const char * textnode = node->getStringValue();
158 // try to convert to a double value. If the textnode does not start with a number
159 // endp will point to the beginning of the string. We assume this should be
161 value = strtod( textnode, &endp );
162 if( endp == textnode ) {
163 property = fgGetNode( textnode, true );
168 void FGXMLAutoInput::set_value( double aValue )
170 double s = get_scale();
172 property->setDoubleValue( (aValue - get_offset())/s );
174 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
177 double FGXMLAutoInput::get_value()
179 if( property != NULL )
180 value = property->getDoubleValue();
183 value *= scale->get_value();
186 value += offset->get_value();
189 double m = min->get_value();
195 double m = max->get_value();
201 value = periodical->normalize( value );
204 return abs ? fabs(value) : value;
207 FGXMLAutoComponent::FGXMLAutoComponent() :
210 enable_value( NULL ),
211 passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
212 honor_passive( false ),
214 feedback_if_disabled( false ),
220 FGXMLAutoComponent::~FGXMLAutoComponent()
225 void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
227 SGPropertyNode *prop;
228 for (int i = 0; i < aNode->nChildren(); ++i ) {
229 SGPropertyNode *child = aNode->getChild(i);
230 string cname(child->getName());
232 if (parseNodeHook(cname, child)) {
233 // derived class handled it, fine
234 } else if ( cname == "name" ) {
235 name = child->getStringValue();
236 } else if ( cname == "feedback-if-disabled" ) {
237 feedback_if_disabled = child->getBoolValue();
238 } else if ( cname == "debug" ) {
239 debug = child->getBoolValue();
240 } else if ( cname == "enable" ) {
241 if( (prop = child->getChild("condition")) != NULL ) {
242 _condition = sgReadCondition(fgGetNode("/"), prop);
244 if ( (prop = child->getChild( "prop" )) != NULL ) {
245 enable_prop = fgGetNode( prop->getStringValue(), true );
248 if ( (prop = child->getChild( "value" )) != NULL ) {
250 enable_value = new string(prop->getStringValue());
253 if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
254 honor_passive = prop->getBoolValue();
256 } else if ( cname == "input" ) {
257 valueInput.push_back( new FGXMLAutoInput( child ) );
258 } else if ( cname == "reference" ) {
259 referenceInput.push_back( new FGXMLAutoInput( child ) );
260 } else if ( cname == "output" ) {
261 // grab all <prop> and <property> childs
263 // backwards compatibility: allow <prop> elements
264 for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) {
265 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
266 output_list.push_back( tmp );
269 for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) {
270 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
271 output_list.push_back( tmp );
275 // no <prop> elements, text node of <output> is property name
277 output_list.push_back( fgGetNode(child->getStringValue(), true ) );
278 } else if ( cname == "config" ) {
280 } else if ( cname == "min" ) {
281 uminInput.push_back( new FGXMLAutoInput( child ) );
282 } else if ( cname == "u_min" ) {
283 uminInput.push_back( new FGXMLAutoInput( child ) );
284 } else if ( cname == "max" ) {
285 umaxInput.push_back( new FGXMLAutoInput( child ) );
286 } else if ( cname == "u_max" ) {
287 umaxInput.push_back( new FGXMLAutoInput( child ) );
288 } else if ( cname == "period" ) {
289 periodical = new FGPeriodicalValue( child );
291 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:"
292 << cname << " in section " << name);
293 throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
295 } // of top-level iteration
298 void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
300 for (int i = 0; i < aConfig->nChildren(); ++i ) {
301 SGPropertyNode *child = aConfig->getChild(i);
302 string cname(child->getName());
304 if (parseConfigHook(cname, child)) {
305 // derived class handled it, fine
306 } else if ( cname == "min" ) {
307 uminInput.push_back( new FGXMLAutoInput( child ) );
308 } else if ( cname == "u_min" ) {
309 uminInput.push_back( new FGXMLAutoInput( child ) );
310 } else if ( cname == "max" ) {
311 umaxInput.push_back( new FGXMLAutoInput( child ) );
312 } else if ( cname == "u_max" ) {
313 umaxInput.push_back( new FGXMLAutoInput( child ) );
315 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:"
316 << cname << " in section " << name);
317 throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
319 } // of config iteration
322 bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
327 bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
332 bool FGXMLAutoComponent::isPropertyEnabled()
335 return _condition->test();
339 return *enable_value == enable_prop->getStringValue();
341 return enable_prop->getBoolValue();
347 void FGXMLAutoComponent::do_feedback_if_disabled()
349 if( output_list.size() > 0 ) {
350 FGXMLAutoInput * input = valueInput.get_active();
352 input->set_value( output_list[0]->getDoubleValue() );
356 double FGXMLAutoComponent::clamp( double value )
358 //If this is a periodical value, normalize it into our domain
361 value = periodical->normalize( value );
363 // clamp, if either min or max is defined
364 if( uminInput.size() + umaxInput.size() > 0 ) {
365 double d = umaxInput.get_value( 0.0 );
366 if( value > d ) value = d;
367 d = uminInput.get_value( 0.0 );
368 if( value < d ) value = d;
373 FGPIDController::FGPIDController( SGPropertyNode *node ):
374 FGXMLAutoComponent(),
388 bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
391 desiredTs = aNode->getDoubleValue();
392 } else if (aName == "Kp") {
393 Kp.push_back( new FGXMLAutoInput(aNode) );
394 } else if (aName == "Ti") {
395 Ti.push_back( new FGXMLAutoInput(aNode) );
396 } else if (aName == "Td") {
397 Td.push_back( new FGXMLAutoInput(aNode) );
398 } else if (aName == "beta") {
399 beta = aNode->getDoubleValue();
400 } else if (aName == "alpha") {
401 alpha = aNode->getDoubleValue();
402 } else if (aName == "gamma") {
403 gamma = aNode->getDoubleValue();
405 // unhandled by us, let the base class try it
415 * Ok! Here is the PID controller algorithm that I would like to see
418 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
419 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
421 * u_n = u_n-1 + delta_u_n
425 * delta_u : The incremental output
426 * Kp : Proportional gain
427 * ep : Proportional error with reference weighing
430 * beta : Weighing factor
431 * r : Reference (setpoint)
432 * y : Process value, measured
435 * Ts : Sampling interval
436 * Ti : Integrator time
437 * Td : Derivator time
438 * edf : Derivate error with reference weighing and filtering
439 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
442 * Tf = alpha * Td , where alpha usually is set to 0.1
443 * ed : Unfiltered derivate error with reference weighing
446 * gamma : Weighing factor
448 * u : absolute output
450 * Index n means the n'th value.
455 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
456 * Kp , Ti , Td , Ts (is the sampling time available?)
463 void FGPIDController::update( double dt ) {
466 double delta_u_n = 0.0; // incremental output
467 double u_n = 0.0; // absolute output
468 double Ts; // sampling interval (sec)
470 double u_min = uminInput.get_value();
471 double u_max = umaxInput.get_value();
474 if ( elapsedTime <= desiredTs ) {
475 // do nothing if time step is not positive (i.e. no time has
482 if ( isPropertyEnabled() ) {
484 // first time being enabled, seed u_n with current
485 // property tree value
486 u_n = get_output_value();
495 if ( enabled && Ts > 0.0) {
496 if ( debug ) cout << "Updating " << get_name()
497 << " Ts " << Ts << endl;
499 double y_n = valueInput.get_value();
500 double r_n = referenceInput.get_value();
502 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
504 // Calculates proportional error:
505 double ep_n = beta * r_n - y_n;
506 if ( debug ) cout << " ep_n = " << ep_n;
507 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
511 if ( debug ) cout << " e_n = " << e_n;
513 double td = Td.get_value();
514 if ( td > 0.0 ) { // do we need to calcluate derivative error?
516 // Calculates derivate error:
517 double ed_n = gamma * r_n - y_n;
518 if ( debug ) cout << " ed_n = " << ed_n;
520 // Calculates filter time:
521 double Tf = alpha * td;
522 if ( debug ) cout << " Tf = " << Tf;
524 // Filters the derivate error:
525 edf_n = edf_n_1 / (Ts/Tf + 1)
526 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
527 if ( debug ) cout << " edf_n = " << edf_n;
529 edf_n_2 = edf_n_1 = edf_n = 0.0;
532 // Calculates the incremental output:
533 double ti = Ti.get_value();
535 delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
537 + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
540 cout << " delta_u_n = " << delta_u_n << endl;
541 cout << "P:" << Kp.get_value() * (ep_n - ep_n_1)
542 << " I:" << Kp.get_value() * ((Ts/ti) * e_n)
543 << " D:" << Kp.get_value() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
548 // Integrator anti-windup logic:
549 if ( delta_u_n > (u_max - u_n_1) ) {
550 delta_u_n = u_max - u_n_1;
551 if ( debug ) cout << " max saturation " << endl;
552 } else if ( delta_u_n < (u_min - u_n_1) ) {
553 delta_u_n = u_min - u_n_1;
554 if ( debug ) cout << " min saturation " << endl;
557 // Calculates absolute output:
558 u_n = u_n_1 + delta_u_n;
559 if ( debug ) cout << " output = " << u_n << endl;
561 // Updates indexed values;
567 set_output_value( u_n );
568 } else if ( !enabled ) {
570 edf_n_2 = edf_n_1 = edf_n = 0.0;
575 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
576 FGXMLAutoComponent(),
582 bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
585 Kp.push_back( new FGXMLAutoInput(aNode) );
586 } else if (aName == "Ki") {
587 Ki.push_back( new FGXMLAutoInput(aNode) );
589 // unhandled by us, let the base class try it
596 void FGPISimpleController::update( double dt ) {
598 if ( isPropertyEnabled() ) {
600 // we have just been enabled, zero out int_sum
610 if ( debug ) cout << "Updating " << get_name() << endl;
611 double y_n = valueInput.get_value();
612 double r_n = referenceInput.get_value();
614 double error = r_n - y_n;
615 if ( debug ) cout << "input = " << y_n
616 << " reference = " << r_n
617 << " error = " << error
620 double prop_comp = clamp(error * Kp.get_value());
621 int_sum += error * Ki.get_value() * dt;
624 double output = prop_comp + int_sum;
625 double clamped_output = clamp( output );
626 if( output != clamped_output ) // anti-windup
627 int_sum = clamped_output - prop_comp;
629 if ( debug ) cout << "prop_comp = " << prop_comp
630 << " int_sum = " << int_sum << endl;
632 set_output_value( clamped_output );
633 if ( debug ) cout << "output = " << clamped_output << endl;
638 FGPredictor::FGPredictor ( SGPropertyNode *node ):
639 FGXMLAutoComponent(),
645 bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
647 if (aName == "seconds") {
648 seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
649 } else if (aName == "filter-gain") {
650 filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
658 void FGPredictor::update( double dt ) {
660 Simple moving average filter converts input value to predicted value "seconds".
662 Smoothing as described by Curt Olson:
663 gain would be valid in the range of 0 - 1.0
664 1.0 would mean no filtering.
665 0.0 would mean no input.
666 0.5 would mean (1 part past value + 1 part current value) / 2
667 0.1 would mean (9 parts past value + 1 part current value) / 10
668 0.25 would mean (3 parts past value + 1 part current value) / 4
672 double ivalue = valueInput.get_value();
674 if ( isPropertyEnabled() ) {
676 // first time being enabled
688 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
689 average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
691 // calculate output with filter gain adjustment
692 double output = ivalue +
693 (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) +
694 filter_gain.get_value() * (current * seconds.get_value());
695 output = clamp( output );
696 set_output_value( output );
703 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
704 FGXMLAutoComponent(),
709 output.resize(2, 0.0);
710 input.resize(samplesInput.get_value() + 1, 0.0);
714 bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
716 if (aName == "type" ) {
717 string val(aNode->getStringValue());
718 if ( val == "exponential" ) {
719 filterType = exponential;
720 } else if (val == "double-exponential") {
721 filterType = doubleExponential;
722 } else if (val == "moving-average") {
723 filterType = movingAverage;
724 } else if (val == "noise-spike") {
725 filterType = noiseSpike;
726 } else if (val == "gain") {
728 } else if (val == "reciprocal") {
729 filterType = reciprocal;
730 } else if (val == "differential") {
731 filterType = differential;
732 // use a constant of two samples for current and previous input value
733 samplesInput.push_back( new FGXMLAutoInput(NULL, 2.0 ) );
735 } else if (aName == "filter-time" ) {
736 TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
737 if( filterType == none ) filterType = exponential;
738 } else if (aName == "samples" ) {
739 samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
740 if( filterType == none ) filterType = movingAverage;
741 } else if (aName == "max-rate-of-change" ) {
742 rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
743 if( filterType == none ) filterType = noiseSpike;
744 } else if (aName == "gain" ) {
745 gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
746 if( filterType == none ) filterType = gain;
748 return false; // not handled by us, let the base class try
754 void FGDigitalFilter::update(double dt)
756 if ( isPropertyEnabled() ) {
758 input.push_front(valueInput.get_value()-referenceInput.get_value());
759 input.resize(samplesInput.get_value() + 1, 0.0);
762 // first time being enabled, initialize output to the
763 // value of the output property to avoid bumping.
764 output.push_front(get_output_value());
773 if ( !enabled || dt < SGLimitsd::min() )
779 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
782 if( debug ) cout << "Updating " << get_name()
783 << " dt " << dt << endl;
785 if (filterType == exponential)
787 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
788 output.push_front(alpha * input[0] +
789 (1 - alpha) * output[0]);
791 else if (filterType == doubleExponential)
793 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
794 output.push_front(alpha * alpha * input[0] +
795 2 * (1 - alpha) * output[0] -
796 (1 - alpha) * (1 - alpha) * output[1]);
798 else if (filterType == movingAverage)
800 output.push_front(output[0] +
801 (input[0] - input.back()) / samplesInput.get_value());
803 else if (filterType == noiseSpike)
805 double maxChange = rateOfChangeInput.get_value() * dt;
807 if ((output[0] - input[0]) > maxChange)
809 output.push_front(output[0] - maxChange);
811 else if ((output[0] - input[0]) < -maxChange)
813 output.push_front(output[0] + maxChange);
815 else if (fabs(input[0] - output[0]) <= maxChange)
817 output.push_front(input[0]);
820 else if (filterType == gain)
822 output[0] = gainInput.get_value() * input[0];
824 else if (filterType == reciprocal)
826 if (input[0] != 0.0) {
827 output[0] = gainInput.get_value() / input[0];
830 else if (filterType == differential)
832 if( dt > SGLimitsd::min() ) {
833 output[0] = (input[0]-input[1]) * TfInput.get_value() / dt;
837 output[0] = clamp(output[0]) ;
838 set_output_value( output[0] );
844 cout << "input:" << input[0]
845 << "\toutput:" << output[0] << endl;
849 FGXMLAutoLogic::FGXMLAutoLogic(SGPropertyNode * node ) :
850 FGXMLAutoComponent(),
856 bool FGXMLAutoLogic::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
858 if (aName == "input") {
859 input = sgReadCondition( fgGetNode("/"), aNode );
860 } else if (aName == "inverted") {
861 inverted = aNode->getBoolValue();
869 void FGXMLAutoLogic::update(double dt)
871 if ( isPropertyEnabled() ) {
873 // we have just been enabled
881 if ( !enabled || dt < SGLimitsd::min() )
884 if( input == NULL ) {
885 if ( debug ) cout << "No input for " << get_name() << endl;
889 bool i = input->test();
891 if ( debug ) cout << "Updating " << get_name() << ": " << (inverted ? !i : i) << endl;
893 set_output_value( i );
897 FGXMLAutopilotGroup::FGXMLAutopilotGroup() :
899 #ifdef XMLAUTO_USEHELPER
900 ,average(0.0), // average/filtered prediction
901 v_last(0.0), // last velocity
902 last_static_pressure(0.0),
903 vel(fgGetNode( "/velocities/airspeed-kt", true )),
904 // Estimate speed in 5,10 seconds
905 lookahead5(fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true )),
906 lookahead10(fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true )),
907 bug(fgGetNode( "/autopilot/settings/heading-bug-deg", true )),
908 mag_hdg(fgGetNode( "/orientation/heading-magnetic-deg", true )),
909 bug_error(fgGetNode( "/autopilot/internal/heading-bug-error-deg", true )),
910 fdm_bug_error(fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true )),
911 target_true(fgGetNode( "/autopilot/settings/true-heading-deg", true )),
912 true_hdg(fgGetNode( "/orientation/heading-deg", true )),
913 true_error(fgGetNode( "/autopilot/internal/true-heading-error-deg", true )),
914 target_nav1(fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true )),
915 true_nav1(fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true )),
916 true_track_nav1(fgGetNode( "/autopilot/internal/nav1-track-error-deg", true )),
917 nav1_course_error(fgGetNode( "/autopilot/internal/nav1-course-error", true )),
918 nav1_selected_course(fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true )),
919 vs_fps(fgGetNode( "/velocities/vertical-speed-fps", true )),
920 vs_fpm(fgGetNode( "/autopilot/internal/vert-speed-fpm", true )),
921 static_pressure(fgGetNode( "/systems/static[0]/pressure-inhg", true )),
922 pressure_rate(fgGetNode( "/autopilot/internal/pressure-rate", true )),
923 track(fgGetNode( "/orientation/track-deg", true ))
928 void FGXMLAutopilotGroup::update( double dt )
930 // update all configured autopilots
931 SGSubsystemGroup::update( dt );
932 #ifdef XMLAUTO_USEHELPER
933 // update helper values
934 double v = vel->getDoubleValue();
937 a = (v - v_last) / dt;
940 average = (1.0 - dt) * average + dt * a;
945 lookahead5->setDoubleValue( v + average * 5.0 );
946 lookahead10->setDoubleValue( v + average * 10.0 );
950 // Calculate heading bug error normalized to +/- 180.0
951 double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
952 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
953 bug_error->setDoubleValue( diff );
955 fdm_bug_error->setDoubleValue( diff );
957 // Calculate true heading error normalized to +/- 180.0
958 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
959 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
960 true_error->setDoubleValue( diff );
962 // Calculate nav1 target heading error normalized to +/- 180.0
963 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
964 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
965 true_nav1->setDoubleValue( diff );
967 // Calculate true groundtrack
968 diff = target_nav1->getDoubleValue() - track->getDoubleValue();
969 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
970 true_track_nav1->setDoubleValue( diff );
972 // Calculate nav1 selected course error normalized to +/- 180.0
973 diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
974 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
975 nav1_course_error->setDoubleValue( diff );
977 // Calculate vertical speed in fpm
978 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
981 // Calculate static port pressure rate in [inhg/s].
982 // Used to determine vertical speed.
984 double current_static_pressure = static_pressure->getDoubleValue();
985 double current_pressure_rate =
986 ( current_static_pressure - last_static_pressure ) / dt;
988 pressure_rate->setDoubleValue(current_pressure_rate);
989 last_static_pressure = current_static_pressure;
994 void FGXMLAutopilotGroup::reinit()
996 for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
997 FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
998 if( ap == NULL ) continue; // ?
999 remove_subsystem( _autopilotNames[i] );
1002 _autopilotNames.clear();
1006 void FGXMLAutopilotGroup::init()
1008 PropertyList autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
1009 if( autopilotNodes.size() == 0 ) {
1010 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
1014 for( PropertyList::size_type i = 0; i < autopilotNodes.size(); i++ ) {
1015 SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
1016 if( pathNode == NULL ) {
1017 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
1022 SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
1023 if( nameNode != NULL ) {
1024 apName = nameNode->getStringValue();
1026 std::ostringstream buf;
1027 buf << "unnamed_autopilot_" << i;
1031 if( get_subsystem( apName.c_str() ) != NULL ) {
1032 SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
1036 SGPath config( globals->get_fg_root() );
1037 config.append( pathNode->getStringValue() );
1039 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
1041 FGXMLAutopilot * ap = new FGXMLAutopilot;
1043 SGPropertyNode_ptr root = new SGPropertyNode();
1044 readProperties( config.str(), root );
1047 if ( ! ap->build( root ) ) {
1048 SG_LOG( SG_ALL, SG_ALERT,
1049 "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
1053 } catch (const sg_exception& e) {
1054 SG_LOG( SG_AUTOPILOT, SG_ALERT, "Failed to load autopilot configuration: "
1055 << config.str() << ":" << e.getMessage() );
1060 SG_LOG( SG_AUTOPILOT, SG_INFO, "adding autopilot subsystem " << apName );
1061 set_subsystem( apName, ap );
1062 _autopilotNames.push_back( apName );
1065 SGSubsystemGroup::init();
1068 FGXMLAutopilot::FGXMLAutopilot() {
1072 FGXMLAutopilot::~FGXMLAutopilot() {
1076 /* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
1077 * and configure/add the digital filters specified in that file
1079 void FGXMLAutopilot::init()
1084 void FGXMLAutopilot::reinit() {
1090 void FGXMLAutopilot::bind() {
1093 void FGXMLAutopilot::unbind() {
1096 bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
1097 SGPropertyNode *node;
1100 int count = config_props->nChildren();
1101 for ( i = 0; i < count; ++i ) {
1102 node = config_props->getChild(i);
1103 string name = node->getName();
1104 // cout << name << endl;
1105 SG_LOG( SG_AUTOPILOT, SG_BULK, "adding autopilot component " << name );
1106 if ( name == "pid-controller" ) {
1107 components.push_back( new FGPIDController( node ) );
1108 } else if ( name == "pi-simple-controller" ) {
1109 components.push_back( new FGPISimpleController( node ) );
1110 } else if ( name == "predict-simple" ) {
1111 components.push_back( new FGPredictor( node ) );
1112 } else if ( name == "filter" ) {
1113 components.push_back( new FGDigitalFilter( node ) );
1114 } else if ( name == "logic" ) {
1115 components.push_back( new FGXMLAutoLogic( node ) );
1117 SG_LOG( SG_AUTOPILOT, SG_WARN, "Unknown top level autopilot section: " << name );
1126 * Update the list of autopilot components
1129 void FGXMLAutopilot::update( double dt )
1132 for ( i = 0; i < components.size(); ++i ) {
1133 components[i]->update( dt );