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 FGPeriodicalValue::FGPeriodicalValue( SGPropertyNode_ptr root )
45 SGPropertyNode_ptr minNode = root->getChild( "min" );
46 SGPropertyNode_ptr maxNode = root->getChild( "max" );
47 if( minNode == NULL || maxNode == NULL ) {
48 SG_LOG(SG_AUTOPILOT, SG_ALERT, "periodical defined, but no <min> and/or <max> tag. Period ignored." );
50 minPeriod = new FGXMLAutoInput( minNode );
51 maxPeriod = new FGXMLAutoInput( maxNode );
55 double FGPeriodicalValue::normalize( double value )
57 if( !(minPeriod && maxPeriod )) return value;
59 double p1 = minPeriod->get_value();
60 double p2 = maxPeriod->get_value();
62 double min = std::min<double>(p1,p2);
63 double max = std::max<double>(p1,p2);
64 double phase = fabs(max - min);
66 if( phase > SGLimitsd::min() ) {
67 while( value < min ) value += phase;
68 while( value >= max ) value -= phase;
70 value = min; // phase is zero
76 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
81 parse( node, value, offset, scale );
85 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
100 if( (n = node->getChild("condition")) != NULL ) {
101 _condition = sgReadCondition(fgGetNode("/"), n);
104 if( (n = node->getChild( "scale" )) != NULL ) {
105 scale = new FGXMLAutoInput( n, aScale );
108 if( (n = node->getChild( "offset" )) != NULL ) {
109 offset = new FGXMLAutoInput( n, aOffset );
112 if( (n = node->getChild( "max" )) != NULL ) {
113 max = new FGXMLAutoInput( n );
116 if( (n = node->getChild( "min" )) != NULL ) {
117 min = new FGXMLAutoInput( n );
120 if( (n = node->getChild( "abs" )) != NULL ) {
121 abs = n->getBoolValue();
124 if( (n = node->getChild( "period" )) != NULL ) {
125 periodical = new FGPeriodicalValue( n );
128 SGPropertyNode *valueNode = node->getChild( "value" );
129 if ( valueNode != NULL ) {
130 value = valueNode->getDoubleValue();
133 n = node->getChild( "property" );
134 // if no <property> element, check for <prop> element for backwards
137 n = node->getChild( "prop" );
140 property = fgGetNode( n->getStringValue(), true );
141 if ( valueNode != NULL ) {
142 // initialize property with given value
143 // if both <prop> and <value> exist
144 double s = get_scale();
146 property->setDoubleValue( (value - get_offset())/s );
148 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
152 if ( n == NULL && valueNode == NULL ) {
153 // no <value> element and no <prop> element, use text node
154 const char * textnode = node->getStringValue();
156 // try to convert to a double value. If the textnode does not start with a number
157 // endp will point to the beginning of the string. We assume this should be
159 value = strtod( textnode, &endp );
160 if( endp == textnode ) {
161 property = fgGetNode( textnode, true );
166 void FGXMLAutoInput::set_value( double aValue )
168 double s = get_scale();
170 property->setDoubleValue( (aValue - get_offset())/s );
172 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
175 double FGXMLAutoInput::get_value()
177 if( property != NULL )
178 value = property->getDoubleValue();
181 value *= scale->get_value();
184 value += offset->get_value();
187 double m = min->get_value();
193 double m = max->get_value();
199 value = periodical->normalize( value );
202 return abs ? fabs(value) : value;
205 FGXMLAutoComponent::FGXMLAutoComponent() :
208 enable_value( NULL ),
209 passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
210 honor_passive( false ),
212 feedback_if_disabled( false ),
218 FGXMLAutoComponent::~FGXMLAutoComponent()
223 void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
225 SGPropertyNode *prop;
226 for (int i = 0; i < aNode->nChildren(); ++i ) {
227 SGPropertyNode *child = aNode->getChild(i);
228 string cname(child->getName());
230 if (parseNodeHook(cname, child)) {
231 // derived class handled it, fine
232 } else if ( cname == "name" ) {
233 name = child->getStringValue();
234 } else if ( cname == "feedback-if-disabled" ) {
235 feedback_if_disabled = child->getBoolValue();
236 } else if ( cname == "debug" ) {
237 debug = child->getBoolValue();
238 } else if ( cname == "enable" ) {
239 if( (prop = child->getChild("condition")) != NULL ) {
240 _condition = sgReadCondition(fgGetNode("/"), prop);
242 if ( (prop = child->getChild( "prop" )) != NULL ) {
243 enable_prop = fgGetNode( prop->getStringValue(), true );
246 if ( (prop = child->getChild( "value" )) != NULL ) {
248 enable_value = new string(prop->getStringValue());
251 if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
252 honor_passive = prop->getBoolValue();
254 } else if ( cname == "input" ) {
255 valueInput.push_back( new FGXMLAutoInput( child ) );
256 } else if ( cname == "reference" ) {
257 referenceInput.push_back( new FGXMLAutoInput( child ) );
258 } else if ( cname == "output" ) {
259 // grab all <prop> and <property> childs
261 // backwards compatibility: allow <prop> elements
262 for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) {
263 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
264 output_list.push_back( tmp );
267 for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) {
268 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
269 output_list.push_back( tmp );
273 // no <prop> elements, text node of <output> is property name
275 output_list.push_back( fgGetNode(child->getStringValue(), true ) );
276 } else if ( cname == "config" ) {
278 } else if ( cname == "min" ) {
279 uminInput.push_back( new FGXMLAutoInput( child ) );
280 } else if ( cname == "u_min" ) {
281 uminInput.push_back( new FGXMLAutoInput( child ) );
282 } else if ( cname == "max" ) {
283 umaxInput.push_back( new FGXMLAutoInput( child ) );
284 } else if ( cname == "u_max" ) {
285 umaxInput.push_back( new FGXMLAutoInput( child ) );
286 } else if ( cname == "period" ) {
287 periodical = new FGPeriodicalValue( child );
289 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:"
290 << cname << " in section " << name);
291 throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
293 } // of top-level iteration
296 void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
298 for (int i = 0; i < aConfig->nChildren(); ++i ) {
299 SGPropertyNode *child = aConfig->getChild(i);
300 string cname(child->getName());
302 if (parseConfigHook(cname, child)) {
303 // derived class handled it, fine
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 ) );
313 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:"
314 << cname << " in section " << name);
315 throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
317 } // of config iteration
320 bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
325 bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
330 bool FGXMLAutoComponent::isPropertyEnabled()
333 return _condition->test();
337 return *enable_value == enable_prop->getStringValue();
339 return enable_prop->getBoolValue();
345 void FGXMLAutoComponent::do_feedback_if_disabled()
347 if( output_list.size() > 0 ) {
348 FGXMLAutoInput * input = valueInput.get_active();
350 input->set_value( output_list[0]->getDoubleValue() );
354 double FGXMLAutoComponent::clamp( double value )
356 //If this is a periodical value, normalize it into our domain
359 value = periodical->normalize( value );
361 // clamp, if either min or max is defined
362 if( uminInput.size() + umaxInput.size() > 0 ) {
363 double d = umaxInput.get_value( 0.0 );
364 if( value > d ) value = d;
365 d = uminInput.get_value( 0.0 );
366 if( value < d ) value = d;
371 FGPIDController::FGPIDController( SGPropertyNode *node ):
372 FGXMLAutoComponent(),
386 bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
389 desiredTs = aNode->getDoubleValue();
390 } else if (aName == "Kp") {
391 Kp.push_back( new FGXMLAutoInput(aNode) );
392 } else if (aName == "Ti") {
393 Ti.push_back( new FGXMLAutoInput(aNode) );
394 } else if (aName == "Td") {
395 Td.push_back( new FGXMLAutoInput(aNode) );
396 } else if (aName == "beta") {
397 beta = aNode->getDoubleValue();
398 } else if (aName == "alpha") {
399 alpha = aNode->getDoubleValue();
400 } else if (aName == "gamma") {
401 gamma = aNode->getDoubleValue();
403 // unhandled by us, let the base class try it
413 * Ok! Here is the PID controller algorithm that I would like to see
416 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
417 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
419 * u_n = u_n-1 + delta_u_n
423 * delta_u : The incremental output
424 * Kp : Proportional gain
425 * ep : Proportional error with reference weighing
428 * beta : Weighing factor
429 * r : Reference (setpoint)
430 * y : Process value, measured
433 * Ts : Sampling interval
434 * Ti : Integrator time
435 * Td : Derivator time
436 * edf : Derivate error with reference weighing and filtering
437 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
440 * Tf = alpha * Td , where alpha usually is set to 0.1
441 * ed : Unfiltered derivate error with reference weighing
444 * gamma : Weighing factor
446 * u : absolute output
448 * Index n means the n'th value.
453 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
454 * Kp , Ti , Td , Ts (is the sampling time available?)
461 void FGPIDController::update( double dt ) {
462 double ep_n; // proportional error with reference weighing
464 double ed_n; // derivative error
465 double edf_n; // derivative error filter
466 double Tf; // filter time
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 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 // Calculates derivate error:
515 ed_n = gamma * r_n - y_n;
516 if ( debug ) cout << " ed_n = " << ed_n;
518 double td = Td.get_value();
520 // Calculates filter time:
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;
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)) );
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))
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 ) {
571 // Updates indexed values;
580 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
581 FGXMLAutoComponent(),
587 bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
590 Kp.push_back( new FGXMLAutoInput(aNode) );
591 } else if (aName == "Ki") {
592 Ki.push_back( new FGXMLAutoInput(aNode) );
594 // unhandled by us, let the base class try it
601 void FGPISimpleController::update( double dt ) {
603 if ( isPropertyEnabled() ) {
605 // we have just been enabled, zero out int_sum
615 if ( debug ) cout << "Updating " << get_name() << endl;
616 double y_n = valueInput.get_value();
617 double r_n = referenceInput.get_value();
619 double error = r_n - y_n;
620 if ( debug ) cout << "input = " << y_n
621 << " reference = " << r_n
622 << " error = " << error
625 double prop_comp = error * Kp.get_value();
626 int_sum += error * Ki.get_value() * dt;
629 if ( debug ) cout << "prop_comp = " << prop_comp
630 << " int_sum = " << int_sum << endl;
632 double output = prop_comp + int_sum;
633 output = clamp( output );
634 set_output_value( output );
635 if ( debug ) cout << "output = " << output << endl;
640 FGPredictor::FGPredictor ( SGPropertyNode *node ):
641 FGXMLAutoComponent(),
647 bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
649 if (aName == "seconds") {
650 seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
651 } else if (aName == "filter-gain") {
652 filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
660 void FGPredictor::update( double dt ) {
662 Simple moving average filter converts input value to predicted value "seconds".
664 Smoothing as described by Curt Olson:
665 gain would be valid in the range of 0 - 1.0
666 1.0 would mean no filtering.
667 0.0 would mean no input.
668 0.5 would mean (1 part past value + 1 part current value) / 2
669 0.1 would mean (9 parts past value + 1 part current value) / 10
670 0.25 would mean (3 parts past value + 1 part current value) / 4
674 double ivalue = valueInput.get_value();
676 if ( isPropertyEnabled() ) {
678 // first time being enabled
690 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
691 average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
693 // calculate output with filter gain adjustment
694 double output = ivalue +
695 (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) +
696 filter_gain.get_value() * (current * seconds.get_value());
697 output = clamp( output );
698 set_output_value( output );
705 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
706 FGXMLAutoComponent(),
711 output.resize(2, 0.0);
712 input.resize(samplesInput.get_value() + 1, 0.0);
716 bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
718 if (aName == "type" ) {
719 string val(aNode->getStringValue());
720 if ( val == "exponential" ) {
721 filterType = exponential;
722 } else if (val == "double-exponential") {
723 filterType = doubleExponential;
724 } else if (val == "moving-average") {
725 filterType = movingAverage;
726 } else if (val == "noise-spike") {
727 filterType = noiseSpike;
728 } else if (val == "gain") {
730 } else if (val == "reciprocal") {
731 filterType = reciprocal;
732 } else if (val == "differential") {
733 filterType = differential;
734 // use a constant of two samples for current and previous input value
735 samplesInput.push_back( new FGXMLAutoInput(NULL, 2.0 ) );
737 } else if (aName == "filter-time" ) {
738 TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
739 if( filterType == none ) filterType = exponential;
740 } else if (aName == "samples" ) {
741 samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
742 if( filterType == none ) filterType = movingAverage;
743 } else if (aName == "max-rate-of-change" ) {
744 rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
745 if( filterType == none ) filterType = noiseSpike;
746 } else if (aName == "gain" ) {
747 gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
748 if( filterType == none ) filterType = gain;
750 return false; // not handled by us, let the base class try
756 void FGDigitalFilter::update(double dt)
758 if ( isPropertyEnabled() ) {
760 input.push_front(valueInput.get_value());
761 input.resize(samplesInput.get_value() + 1, 0.0);
764 // first time being enabled, initialize output to the
765 // value of the output property to avoid bumping.
766 output.push_front(get_output_value());
775 if ( !enabled || dt < SGLimitsd::min() )
781 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
784 if( debug ) cout << "Updating " << get_name()
785 << " dt " << dt << endl;
787 if (filterType == exponential)
789 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
790 output.push_front(alpha * input[0] +
791 (1 - alpha) * output[0]);
793 else if (filterType == doubleExponential)
795 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
796 output.push_front(alpha * alpha * input[0] +
797 2 * (1 - alpha) * output[0] -
798 (1 - alpha) * (1 - alpha) * output[1]);
800 else if (filterType == movingAverage)
802 output.push_front(output[0] +
803 (input[0] - input.back()) / samplesInput.get_value());
805 else if (filterType == noiseSpike)
807 double maxChange = rateOfChangeInput.get_value() * dt;
809 if ((output[0] - input[0]) > maxChange)
811 output.push_front(output[0] - maxChange);
813 else if ((output[0] - input[0]) < -maxChange)
815 output.push_front(output[0] + maxChange);
817 else if (fabs(input[0] - output[0]) <= maxChange)
819 output.push_front(input[0]);
822 else if (filterType == gain)
824 output[0] = gainInput.get_value() * input[0];
826 else if (filterType == reciprocal)
828 if (input[0] != 0.0) {
829 output[0] = gainInput.get_value() / input[0];
832 else if (filterType == differential)
834 if( dt > SGLimitsd::min() ) {
835 output[0] = (input[0]-input[1]) * TfInput.get_value() / dt;
839 output[0] = clamp(output[0]) ;
840 set_output_value( output[0] );
846 cout << "input:" << input[0]
847 << "\toutput:" << output[0] << endl;
851 FGXMLAutoLogic::FGXMLAutoLogic(SGPropertyNode * node ) :
852 FGXMLAutoComponent(),
858 bool FGXMLAutoLogic::parseNodeHook(const std::string& aName, SGPropertyNode* aNode)
860 if (aName == "input") {
861 input = sgReadCondition( fgGetNode("/"), aNode );
862 } else if (aName == "inverted") {
863 inverted = aNode->getBoolValue();
871 void FGXMLAutoLogic::update(double dt)
873 if ( isPropertyEnabled() ) {
875 // we have just been enabled
883 if ( !enabled || dt < SGLimitsd::min() )
886 if( input == NULL ) {
887 if ( debug ) cout << "No input for " << get_name() << endl;
891 bool i = input->test();
893 if ( debug ) cout << "Updating " << get_name() << ": " << (inverted ? !i : i) << endl;
895 set_output_value( i );
899 FGXMLAutopilotGroup::FGXMLAutopilotGroup() :
901 #ifdef XMLAUTO_USEHELPER
902 ,average(0.0), // average/filtered prediction
903 v_last(0.0), // last velocity
904 last_static_pressure(0.0),
905 vel(fgGetNode( "/velocities/airspeed-kt", true )),
906 // Estimate speed in 5,10 seconds
907 lookahead5(fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true )),
908 lookahead10(fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true )),
909 bug(fgGetNode( "/autopilot/settings/heading-bug-deg", true )),
910 mag_hdg(fgGetNode( "/orientation/heading-magnetic-deg", true )),
911 bug_error(fgGetNode( "/autopilot/internal/heading-bug-error-deg", true )),
912 fdm_bug_error(fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true )),
913 target_true(fgGetNode( "/autopilot/settings/true-heading-deg", true )),
914 true_hdg(fgGetNode( "/orientation/heading-deg", true )),
915 true_error(fgGetNode( "/autopilot/internal/true-heading-error-deg", true )),
916 target_nav1(fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true )),
917 true_nav1(fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true )),
918 true_track_nav1(fgGetNode( "/autopilot/internal/nav1-track-error-deg", true )),
919 nav1_course_error(fgGetNode( "/autopilot/internal/nav1-course-error", true )),
920 nav1_selected_course(fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true )),
921 vs_fps(fgGetNode( "/velocities/vertical-speed-fps", true )),
922 vs_fpm(fgGetNode( "/autopilot/internal/vert-speed-fpm", true )),
923 static_pressure(fgGetNode( "/systems/static[0]/pressure-inhg", true )),
924 pressure_rate(fgGetNode( "/autopilot/internal/pressure-rate", true )),
925 track(fgGetNode( "/orientation/track-deg", true ))
930 void FGXMLAutopilotGroup::update( double dt )
932 // update all configured autopilots
933 SGSubsystemGroup::update( dt );
934 #ifdef XMLAUTO_USEHELPER
935 // update helper values
936 double v = vel->getDoubleValue();
939 a = (v - v_last) / dt;
942 average = (1.0 - dt) * average + dt * a;
947 lookahead5->setDoubleValue( v + average * 5.0 );
948 lookahead10->setDoubleValue( v + average * 10.0 );
952 // Calculate heading bug error normalized to +/- 180.0
953 double diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
954 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
955 bug_error->setDoubleValue( diff );
957 fdm_bug_error->setDoubleValue( diff );
959 // Calculate true heading error normalized to +/- 180.0
960 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
961 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
962 true_error->setDoubleValue( diff );
964 // Calculate nav1 target heading error normalized to +/- 180.0
965 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
966 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
967 true_nav1->setDoubleValue( diff );
969 // Calculate true groundtrack
970 diff = target_nav1->getDoubleValue() - track->getDoubleValue();
971 SG_NORMALIZE_RANGE(diff, -180.0, 180.0);
972 true_track_nav1->setDoubleValue( diff );
974 // Calculate nav1 selected course error normalized to +/- 180.0
975 diff = nav1_selected_course->getDoubleValue() - mag_hdg->getDoubleValue();
976 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
977 nav1_course_error->setDoubleValue( diff );
979 // Calculate vertical speed in fpm
980 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
983 // Calculate static port pressure rate in [inhg/s].
984 // Used to determine vertical speed.
986 double current_static_pressure = static_pressure->getDoubleValue();
987 double current_pressure_rate =
988 ( current_static_pressure - last_static_pressure ) / dt;
990 pressure_rate->setDoubleValue(current_pressure_rate);
991 last_static_pressure = current_static_pressure;
996 void FGXMLAutopilotGroup::reinit()
998 for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
999 FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
1000 if( ap == NULL ) continue; // ?
1001 remove_subsystem( _autopilotNames[i] );
1004 _autopilotNames.clear();
1008 void FGXMLAutopilotGroup::init()
1010 vector<SGPropertyNode_ptr> autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
1011 if( autopilotNodes.size() == 0 ) {
1012 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
1016 for( vector<SGPropertyNode_ptr>::size_type i = 0; i < autopilotNodes.size(); i++ ) {
1017 SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
1018 if( pathNode == NULL ) {
1019 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
1024 SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
1025 if( nameNode != NULL ) {
1026 apName = nameNode->getStringValue();
1028 std::ostringstream buf;
1029 buf << "unnamed_autopilot_" << i;
1033 if( get_subsystem( apName.c_str() ) != NULL ) {
1034 SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
1038 SGPath config( globals->get_fg_root() );
1039 config.append( pathNode->getStringValue() );
1041 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
1043 FGXMLAutopilot * ap = new FGXMLAutopilot;
1045 SGPropertyNode_ptr root = new SGPropertyNode();
1046 readProperties( config.str(), root );
1049 if ( ! ap->build( root ) ) {
1050 SG_LOG( SG_ALL, SG_ALERT,
1051 "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
1055 } catch (const sg_exception& e) {
1056 SG_LOG( SG_AUTOPILOT, SG_ALERT, "Failed to load autopilot configuration: "
1057 << config.str() << ":" << e.getMessage() );
1062 SG_LOG( SG_AUTOPILOT, SG_INFO, "adding autopilot subsystem " << apName );
1063 set_subsystem( apName, ap );
1064 _autopilotNames.push_back( apName );
1067 SGSubsystemGroup::init();
1070 FGXMLAutopilot::FGXMLAutopilot() {
1074 FGXMLAutopilot::~FGXMLAutopilot() {
1078 /* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
1079 * and configure/add the digital filters specified in that file
1081 void FGXMLAutopilot::init()
1086 void FGXMLAutopilot::reinit() {
1092 void FGXMLAutopilot::bind() {
1095 void FGXMLAutopilot::unbind() {
1098 bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
1099 SGPropertyNode *node;
1102 int count = config_props->nChildren();
1103 for ( i = 0; i < count; ++i ) {
1104 node = config_props->getChild(i);
1105 string name = node->getName();
1106 // cout << name << endl;
1107 SG_LOG( SG_AUTOPILOT, SG_BULK, "adding autopilot component " << name );
1108 if ( name == "pid-controller" ) {
1109 components.push_back( new FGPIDController( node ) );
1110 } else if ( name == "pi-simple-controller" ) {
1111 components.push_back( new FGPISimpleController( node ) );
1112 } else if ( name == "predict-simple" ) {
1113 components.push_back( new FGPredictor( node ) );
1114 } else if ( name == "filter" ) {
1115 components.push_back( new FGDigitalFilter( node ) );
1116 } else if ( name == "logic" ) {
1117 components.push_back( new FGXMLAutoLogic( node ) );
1119 SG_LOG( SG_AUTOPILOT, SG_WARN, "Unknown top level autopilot section: " << name );
1128 * Update the list of autopilot components
1131 void FGXMLAutopilot::update( double dt )
1134 for ( i = 0; i < components.size(); ++i ) {
1135 components[i]->update( dt );