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"
47 <prop>/some/property</prop>
52 <node>/some/property</node>
55 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
68 if( (n = node->getChild( "scale" )) != NULL )
69 scale = n->getDoubleValue();
71 if( (n = node->getChild( "offset" )) != NULL )
72 offset = n->getDoubleValue();
74 SGPropertyNode *valueNode = node->getChild( "value" );
75 if ( valueNode != NULL ) {
76 value = valueNode->getDoubleValue();
79 n = node->getChild( "property" );
80 // if no <property> element, check for <prop> element for backwards
83 n = node->getChild( "prop" );
86 property = fgGetNode( n->getStringValue(), true );
87 if ( valueNode != NULL ) {
88 // initialize property with given value
89 // if both <prop> and <value> exist
91 property->setDoubleValue( (value - offset)/scale );
93 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
97 if ( n == NULL && valueNode == NULL ) {
98 // no <value> element and no <prop> element, use text node
99 const char * textnode = node->getStringValue();
101 // try to convert to a double value. If the textnode does not start with a number
102 // endp will point to the beginning of the string. We assume this should be
104 value = strtod( textnode, &endp );
105 if( endp == textnode ) {
106 property = fgGetNode( textnode, true );
111 FGXMLAutoComponent::FGXMLAutoComponent( SGPropertyNode * node ) :
115 passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
116 enable_value( NULL ),
117 honor_passive( false ),
123 SGPropertyNode *prop;
125 for ( i = 0; i < node->nChildren(); ++i ) {
126 SGPropertyNode *child = node->getChild(i);
127 string cname = child->getName();
128 string cval = child->getStringValue();
129 if ( cname == "name" ) {
132 } else if ( cname == "debug" ) {
133 debug = child->getBoolValue();
135 } else if ( cname == "enable" ) {
136 if( (prop = child->getChild("condition")) != NULL ) {
137 _condition = sgReadCondition(child, prop);
139 if ( (prop = child->getChild( "prop" )) != NULL ) {
140 enable_prop = fgGetNode( prop->getStringValue(), true );
143 if ( (prop = child->getChild( "value" )) != NULL ) {
145 enable_value = new string(prop->getStringValue());
148 if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
149 honor_passive = prop->getBoolValue();
152 } else if ( cname == "input" ) {
154 valueInput.parse( child );
156 } else if ( cname == "reference" ) {
158 referenceInput.parse( child );
160 } else if ( cname == "output" ) {
161 // grab all <prop> and <property> childs
163 // backwards compatibility: allow <prop> elements
164 for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) {
165 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
166 output_list.push_back( tmp );
169 for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) {
170 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
171 output_list.push_back( tmp );
175 // no <prop> elements, text node of <output> is property name
177 output_list.push_back( fgGetNode(child->getStringValue(), true ) );
179 } else if ( cname == "config" ) {
180 if( (prop = child->getChild("u_min")) != NULL ) {
181 uminInput.parse( prop );
184 if( (prop = child->getChild("u_max")) != NULL ) {
185 umaxInput.parse( prop );
188 } else if ( cname == "u_min" ) {
189 uminInput.parse( child );
191 } else if ( cname == "u_max" ) {
192 umaxInput.parse( child );
198 FGXMLAutoComponent::~FGXMLAutoComponent()
203 bool FGXMLAutoComponent::isPropertyEnabled()
206 return _condition->test();
210 return *enable_value == enable_prop->getStringValue();
212 return enable_prop->getBoolValue();
218 FGPIDController::FGPIDController( SGPropertyNode *node ):
219 FGXMLAutoComponent( node ),
231 for ( i = 0; i < node->nChildren(); ++i ) {
232 SGPropertyNode *child = node->getChild(i);
233 string cname = child->getName();
234 string cval = child->getStringValue();
235 if ( cname == "config" ) {
236 SGPropertyNode *config;
238 if ( (config = child->getChild( "Ts" )) != NULL ) {
239 desiredTs = config->getDoubleValue();
242 Kp.parse( child->getChild( "Kp" ) );
243 Ti.parse( child->getChild( "Ti" ) );
244 Td.parse( child->getChild( "Td" ) );
246 config = child->getChild( "beta" );
247 if ( config != NULL ) {
248 beta = config->getDoubleValue();
251 config = child->getChild( "alpha" );
252 if ( config != NULL ) {
253 alpha = config->getDoubleValue();
256 config = child->getChild( "gamma" );
257 if ( config != NULL ) {
258 gamma = config->getDoubleValue();
262 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
263 if ( get_name().length() ) {
264 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << get_name() );
274 * Ok! Here is the PID controller algorithm that I would like to see
277 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
278 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
280 * u_n = u_n-1 + delta_u_n
284 * delta_u : The incremental output
285 * Kp : Proportional gain
286 * ep : Proportional error with reference weighing
289 * beta : Weighing factor
290 * r : Reference (setpoint)
291 * y : Process value, measured
294 * Ts : Sampling interval
295 * Ti : Integrator time
296 * Td : Derivator time
297 * edf : Derivate error with reference weighing and filtering
298 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
301 * Tf = alpha * Td , where alpha usually is set to 0.1
302 * ed : Unfiltered derivate error with reference weighing
305 * gamma : Weighing factor
307 * u : absolute output
309 * Index n means the n'th value.
314 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
315 * Kp , Ti , Td , Ts (is the sampling time available?)
322 void FGPIDController::update( double dt ) {
323 double ep_n; // proportional error with reference weighing
325 double ed_n; // derivative error
326 double edf_n; // derivative error filter
327 double Tf; // filter time
328 double delta_u_n = 0.0; // incremental output
329 double u_n = 0.0; // absolute output
330 double Ts; // sampling interval (sec)
332 double u_min = uminInput.getValue();
333 double u_max = umaxInput.getValue();
336 if ( elapsedTime <= desiredTs ) {
337 // do nothing if time step is not positive (i.e. no time has
344 if ( isPropertyEnabled() ) {
346 // first time being enabled, seed u_n with current
347 // property tree value
348 u_n = getOutputValue();
356 if ( enabled && Ts > 0.0) {
357 if ( debug ) cout << "Updating " << get_name()
358 << " Ts " << Ts << endl;
360 double y_n = valueInput.getValue();
361 double r_n = referenceInput.getValue();
363 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
365 // Calculates proportional error:
366 ep_n = beta * r_n - y_n;
367 if ( debug ) cout << " ep_n = " << ep_n;
368 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
372 if ( debug ) cout << " e_n = " << e_n;
374 // Calculates derivate error:
375 ed_n = gamma * r_n - y_n;
376 if ( debug ) cout << " ed_n = " << ed_n;
378 double td = Td.getValue();
380 // Calculates filter time:
382 if ( debug ) cout << " Tf = " << Tf;
384 // Filters the derivate error:
385 edf_n = edf_n_1 / (Ts/Tf + 1)
386 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
387 if ( debug ) cout << " edf_n = " << edf_n;
392 // Calculates the incremental output:
393 double ti = Ti.getValue();
395 delta_u_n = Kp.getValue() * ( (ep_n - ep_n_1)
397 + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
401 cout << " delta_u_n = " << delta_u_n << endl;
402 cout << "P:" << Kp.getValue() * (ep_n - ep_n_1)
403 << " I:" << Kp.getValue() * ((Ts/ti) * e_n)
404 << " D:" << Kp.getValue() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
408 // Integrator anti-windup logic:
409 if ( delta_u_n > (u_max - u_n_1) ) {
410 delta_u_n = u_max - u_n_1;
411 if ( debug ) cout << " max saturation " << endl;
412 } else if ( delta_u_n < (u_min - u_n_1) ) {
413 delta_u_n = u_min - u_n_1;
414 if ( debug ) cout << " min saturation " << endl;
417 // Calculates absolute output:
418 u_n = u_n_1 + delta_u_n;
419 if ( debug ) cout << " output = " << u_n << endl;
421 // Updates indexed values;
427 setOutputValue( u_n );
428 } else if ( !enabled ) {
431 // Updates indexed values;
440 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
441 FGXMLAutoComponent( node ),
445 for ( i = 0; i < node->nChildren(); ++i ) {
446 SGPropertyNode *child = node->getChild(i);
447 string cname = child->getName();
448 string cval = child->getStringValue();
449 if ( cname == "config" ) {
450 Kp.parse( child->getChild( "Kp" ) );
451 Ki.parse( child->getChild( "Ki" ) );
453 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
454 if ( get_name().length() ) {
455 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << get_name() );
462 void FGPISimpleController::update( double dt ) {
464 if ( isPropertyEnabled() ) {
466 // we have just been enabled, zero out int_sum
475 if ( debug ) cout << "Updating " << get_name() << endl;
476 double y_n = valueInput.getValue();
477 double r_n = referenceInput.getValue();
479 double error = r_n - y_n;
480 if ( debug ) cout << "input = " << y_n
481 << " reference = " << r_n
482 << " error = " << error
485 double prop_comp = error * Kp.getValue();
486 int_sum += error * Ki.getValue() * dt;
489 if ( debug ) cout << "prop_comp = " << prop_comp
490 << " int_sum = " << int_sum << endl;
492 double output = prop_comp + int_sum;
493 output = Clamp( output );
494 setOutputValue( output );
495 if ( debug ) cout << "output = " << output << endl;
500 FGPredictor::FGPredictor ( SGPropertyNode *node ):
501 FGXMLAutoComponent( node ),
508 for ( i = 0; i < node->nChildren(); ++i ) {
509 SGPropertyNode *child = node->getChild(i);
510 string cname = child->getName();
511 string cval = child->getStringValue();
512 if ( cname == "seconds" ) {
513 seconds = child->getDoubleValue();
514 } else if ( cname == "filter-gain" ) {
515 filter_gain = child->getDoubleValue();
520 void FGPredictor::update( double dt ) {
522 Simple moving average filter converts input value to predicted value "seconds".
524 Smoothing as described by Curt Olson:
525 gain would be valid in the range of 0 - 1.0
526 1.0 would mean no filtering.
527 0.0 would mean no input.
528 0.5 would mean (1 part past value + 1 part current value) / 2
529 0.1 would mean (9 parts past value + 1 part current value) / 10
530 0.25 would mean (3 parts past value + 1 part current value) / 4
534 ivalue = valueInput.getValue();
536 if ( isPropertyEnabled() ) {
538 // first time being enabled
549 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
551 average = (1.0 - dt) * average + current * dt;
556 // calculate output with filter gain adjustment
557 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
558 output = Clamp( output );
559 setOutputValue( output );
566 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
567 FGXMLAutoComponent( node )
570 for ( i = 0; i < node->nChildren(); ++i ) {
571 SGPropertyNode *child = node->getChild(i);
572 string cname = child->getName();
573 string cval = child->getStringValue();
574 if ( cname == "type" ) {
575 if ( cval == "exponential" ) {
576 filterType = exponential;
577 } else if (cval == "double-exponential") {
578 filterType = doubleExponential;
579 } else if (cval == "moving-average") {
580 filterType = movingAverage;
581 } else if (cval == "noise-spike") {
582 filterType = noiseSpike;
583 } else if (cval == "gain") {
585 } else if (cval == "reciprocal") {
586 filterType = reciprocal;
588 } else if ( cname == "filter-time" ) {
589 TfInput.parse( child, 1.0 );
590 } else if ( cname == "samples" ) {
591 samplesInput.parse( child, 1 );
592 } else if ( cname == "max-rate-of-change" ) {
593 rateOfChangeInput.parse( child, 1.0 );
594 } else if ( cname == "gain" ) {
595 gainInput.parse( child );
599 output.resize(2, 0.0);
600 input.resize(samplesInput.getValue() + 1, 0.0);
603 void FGDigitalFilter::update(double dt)
605 if ( isPropertyEnabled() ) {
607 input.push_front(valueInput.getValue());
608 input.resize(samplesInput.getValue() + 1, 0.0);
611 // first time being enabled, initialize output to the
612 // value of the output property to avoid bumping.
613 output.push_front(getOutputValue());
621 if ( enabled && dt > 0.0 ) {
625 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
628 if( debug ) cout << "Updating " << get_name()
629 << " dt " << dt << endl;
631 if (filterType == exponential)
633 double alpha = 1 / ((TfInput.getValue()/dt) + 1);
634 output.push_front(alpha * input[0] +
635 (1 - alpha) * output[0]);
637 else if (filterType == doubleExponential)
639 double alpha = 1 / ((TfInput.getValue()/dt) + 1);
640 output.push_front(alpha * alpha * input[0] +
641 2 * (1 - alpha) * output[0] -
642 (1 - alpha) * (1 - alpha) * output[1]);
644 else if (filterType == movingAverage)
646 output.push_front(output[0] +
647 (input[0] - input.back()) / samplesInput.getValue());
649 else if (filterType == noiseSpike)
651 double maxChange = rateOfChangeInput.getValue() * dt;
653 if ((output[0] - input[0]) > maxChange)
655 output.push_front(output[0] - maxChange);
657 else if ((output[0] - input[0]) < -maxChange)
659 output.push_front(output[0] + maxChange);
661 else if (fabs(input[0] - output[0]) <= maxChange)
663 output.push_front(input[0]);
666 else if (filterType == gain)
668 output[0] = gainInput.getValue() * input[0];
670 else if (filterType == reciprocal)
672 if (input[0] != 0.0) {
673 output[0] = gainInput.getValue() / input[0];
677 output[0] = Clamp(output[0]) ;
678 setOutputValue( output[0] );
684 cout << "input:" << input[0]
685 << "\toutput:" << output[0] << endl;
691 FGXMLAutopilot::FGXMLAutopilot() {
695 FGXMLAutopilot::~FGXMLAutopilot() {
699 void FGXMLAutopilot::init() {
700 config_props = fgGetNode( "/autopilot/new-config", true );
702 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
705 SGPath config( globals->get_fg_root() );
706 config.append( path_n->getStringValue() );
708 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
711 readProperties( config.str(), config_props );
714 SG_LOG( SG_ALL, SG_ALERT,
715 "Detected an internal inconsistency in the autopilot");
716 SG_LOG( SG_ALL, SG_ALERT,
717 " configuration. See earlier errors for" );
718 SG_LOG( SG_ALL, SG_ALERT,
722 } catch (const sg_exception& exc) {
723 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
728 SG_LOG( SG_ALL, SG_WARN,
729 "No autopilot configuration specified for this model!");
734 void FGXMLAutopilot::reinit() {
740 void FGXMLAutopilot::bind() {
743 void FGXMLAutopilot::unbind() {
746 bool FGXMLAutopilot::build() {
747 SGPropertyNode *node;
750 int count = config_props->nChildren();
751 for ( i = 0; i < count; ++i ) {
752 node = config_props->getChild(i);
753 string name = node->getName();
754 // cout << name << endl;
755 if ( name == "pid-controller" ) {
756 components.push_back( new FGPIDController( node ) );
757 } else if ( name == "pi-simple-controller" ) {
758 components.push_back( new FGPISimpleController( node ) );
759 } else if ( name == "predict-simple" ) {
760 components.push_back( new FGPredictor( node ) );
761 } else if ( name == "filter" ) {
762 components.push_back( new FGDigitalFilter( node ) );
764 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
775 * Update helper values
777 static void update_helper( double dt ) {
778 // Estimate speed in 5,10 seconds
779 static SGPropertyNode_ptr vel = fgGetNode( "/velocities/airspeed-kt", true );
780 static SGPropertyNode_ptr lookahead5
781 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
782 static SGPropertyNode_ptr lookahead10
783 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
785 static double average = 0.0; // average/filtered prediction
786 static double v_last = 0.0; // last velocity
788 double v = vel->getDoubleValue();
791 a = (v - v_last) / dt;
794 average = (1.0 - dt) * average + dt * a;
799 lookahead5->setDoubleValue( v + average * 5.0 );
800 lookahead10->setDoubleValue( v + average * 10.0 );
804 // Calculate heading bug error normalized to +/- 180.0 (based on
805 // DG indicated heading)
806 static SGPropertyNode_ptr bug
807 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
808 static SGPropertyNode_ptr ind_hdg
809 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
811 static SGPropertyNode_ptr ind_bug_error
812 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
814 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
815 if ( diff < -180.0 ) { diff += 360.0; }
816 if ( diff > 180.0 ) { diff -= 360.0; }
817 ind_bug_error->setDoubleValue( diff );
819 // Calculate heading bug error normalized to +/- 180.0 (based on
820 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
822 static SGPropertyNode_ptr mag_hdg
823 = fgGetNode( "/orientation/heading-magnetic-deg", true );
824 static SGPropertyNode_ptr fdm_bug_error
825 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
827 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
828 if ( diff < -180.0 ) { diff += 360.0; }
829 if ( diff > 180.0 ) { diff -= 360.0; }
830 fdm_bug_error->setDoubleValue( diff );
832 // Calculate true heading error normalized to +/- 180.0
833 static SGPropertyNode_ptr target_true
834 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
835 static SGPropertyNode_ptr true_hdg
836 = fgGetNode( "/orientation/heading-deg", true );
837 static SGPropertyNode_ptr true_track
838 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
839 static SGPropertyNode_ptr true_error
840 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
842 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
843 if ( diff < -180.0 ) { diff += 360.0; }
844 if ( diff > 180.0 ) { diff -= 360.0; }
845 true_error->setDoubleValue( diff );
847 // Calculate nav1 target heading error normalized to +/- 180.0
848 static SGPropertyNode_ptr target_nav1
849 = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
850 static SGPropertyNode_ptr true_nav1
851 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
852 static SGPropertyNode_ptr true_track_nav1
853 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
855 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
856 if ( diff < -180.0 ) { diff += 360.0; }
857 if ( diff > 180.0 ) { diff -= 360.0; }
858 true_nav1->setDoubleValue( diff );
860 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
861 if ( diff < -180.0 ) { diff += 360.0; }
862 if ( diff > 180.0 ) { diff -= 360.0; }
863 true_track_nav1->setDoubleValue( diff );
865 // Calculate nav1 selected course error normalized to +/- 180.0
866 // (based on DG indicated heading)
867 static SGPropertyNode_ptr nav1_course_error
868 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
869 static SGPropertyNode_ptr nav1_selected_course
870 = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
872 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
873 // if ( diff < -180.0 ) { diff += 360.0; }
874 // if ( diff > 180.0 ) { diff -= 360.0; }
875 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
876 nav1_course_error->setDoubleValue( diff );
878 // Calculate vertical speed in fpm
879 static SGPropertyNode_ptr vs_fps
880 = fgGetNode( "/velocities/vertical-speed-fps", true );
881 static SGPropertyNode_ptr vs_fpm
882 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
884 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
887 // Calculate static port pressure rate in [inhg/s].
888 // Used to determine vertical speed.
889 static SGPropertyNode_ptr static_pressure
890 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
891 static SGPropertyNode_ptr pressure_rate
892 = fgGetNode( "/autopilot/internal/pressure-rate", true );
894 static double last_static_pressure = 0.0;
897 double current_static_pressure = static_pressure->getDoubleValue();
899 double current_pressure_rate =
900 ( current_static_pressure - last_static_pressure ) / dt;
902 pressure_rate->setDoubleValue(current_pressure_rate);
904 last_static_pressure = current_static_pressure;
911 * Update the list of autopilot components
914 void FGXMLAutopilot::update( double dt ) {
918 for ( i = 0; i < components.size(); ++i ) {
919 components[i]->update( dt );