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 - curt@flightgear.org
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., 675 Mass Ave, Cambridge, MA 02139, USA.
24 #include <simgear/structure/exception.hxx>
25 #include <simgear/misc/sg_path.hxx>
27 #include <Main/fg_props.hxx>
28 #include <Main/globals.hxx>
30 #include "xmlauto.hxx"
33 FGPIDController::FGPIDController( SGPropertyNode *node ):
53 for ( i = 0; i < node->nChildren(); ++i ) {
54 SGPropertyNode *child = node->getChild(i);
55 string cname = child->getName();
56 string cval = child->getStringValue();
57 if ( cname == "name" ) {
59 } else if ( cname == "debug" ) {
60 debug = child->getBoolValue();
61 } else if ( cname == "enable" ) {
62 // cout << "parsing enable" << endl;
63 SGPropertyNode *prop = child->getChild( "prop" );
65 // cout << "prop = " << prop->getStringValue() << endl;
66 enable_prop = fgGetNode( prop->getStringValue(), true );
68 // cout << "no prop child" << endl;
70 SGPropertyNode *val = child->getChild( "value" );
72 enable_value = val->getStringValue();
74 } else if ( cname == "input" ) {
75 SGPropertyNode *prop = child->getChild( "prop" );
77 input_prop = fgGetNode( prop->getStringValue(), true );
79 prop = child->getChild( "scale" );
81 y_scale = prop->getDoubleValue();
83 } else if ( cname == "reference" ) {
84 SGPropertyNode *prop = child->getChild( "prop" );
86 r_n_prop = fgGetNode( prop->getStringValue(), true );
88 prop = child->getChild( "value" );
90 r_n = prop->getDoubleValue();
93 prop = child->getChild( "scale" );
95 r_scale = prop->getDoubleValue();
97 } else if ( cname == "output" ) {
100 while ( (prop = child->getChild("prop", i)) != NULL ) {
101 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
102 output_list.push_back( tmp );
105 } else if ( cname == "config" ) {
106 SGPropertyNode *prop;
108 prop = child->getChild( "Kp" );
109 if ( prop != NULL ) {
110 Kp = prop->getDoubleValue();
113 prop = child->getChild( "beta" );
114 if ( prop != NULL ) {
115 beta = prop->getDoubleValue();
118 prop = child->getChild( "alpha" );
119 if ( prop != NULL ) {
120 alpha = prop->getDoubleValue();
123 prop = child->getChild( "gamma" );
124 if ( prop != NULL ) {
125 gamma = prop->getDoubleValue();
128 prop = child->getChild( "Ti" );
129 if ( prop != NULL ) {
130 Ti = prop->getDoubleValue();
133 prop = child->getChild( "Td" );
134 if ( prop != NULL ) {
135 Td = prop->getDoubleValue();
138 prop = child->getChild( "u_min" );
139 if ( prop != NULL ) {
140 u_min = prop->getDoubleValue();
143 prop = child->getChild( "u_max" );
144 if ( prop != NULL ) {
145 u_max = prop->getDoubleValue();
148 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
149 if ( name.length() ) {
150 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
160 * Ok! Here is the PID controller algorithm that I would like to see
163 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
164 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
166 * u_n = u_n-1 + delta_u_n
170 * delta_u : The incremental output
171 * Kp : Proportional gain
172 * ep : Proportional error with reference weighing
175 * beta : Weighing factor
176 * r : Reference (setpoint)
177 * y : Process value, measured
180 * Ts : Sampling interval
181 * Ti : Integrator time
182 * Td : Derivator time
183 * edf : Derivate error with reference weighing and filtering
184 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
187 * Tf = alpha * Td , where alpha usually is set to 0.1
188 * ed : Unfiltered derivate error with reference weighing
191 * gamma : Weighing factor
193 * u : absolute output
195 * Index n means the n'th value.
200 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
201 * Kp , Ti , Td , Ts (is the sampling time available?)
208 void FGPIDController::update( double dt ) {
209 double ep_n; // proportional error with reference weighing
211 double ed_n; // derivative error
212 double edf_n; // derivative error filter
213 double Tf; // filter time
214 double delta_u_n = 0.0; // incremental output
215 double u_n = 0.0; // absolute output
216 double Ts = dt; // Sampling interval (sec)
219 // do nothing if time step is not positive (i.e. no time has
224 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
226 // first time being enabled, seed u_n with current
227 // property tree value
228 u_n = output_list[0]->getDoubleValue();
230 if ( u_n < u_min ) { u_n = u_min; }
231 if ( u_n > u_max ) { u_n = u_max; }
239 if ( enabled && Ts > 0.0) {
240 if ( debug ) cout << "Updating " << name << endl;
243 if ( input_prop != NULL ) {
244 y_n = input_prop->getDoubleValue() * y_scale;
248 if ( r_n_prop != NULL ) {
249 r_n = r_n_prop->getDoubleValue() * r_scale;
254 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
256 // Calculates proportional error:
257 ep_n = beta * r_n - y_n;
258 if ( debug ) cout << " ep_n = " << ep_n;
259 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
263 if ( debug ) cout << " e_n = " << e_n;
265 // Calculates derivate error:
266 ed_n = gamma * r_n - y_n;
267 if ( debug ) cout << " ed_n = " << ed_n;
270 // Calculates filter time:
272 if ( debug ) cout << " Tf = " << Tf;
274 // Filters the derivate error:
275 edf_n = edf_n_1 / (Ts/Tf + 1)
276 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
277 if ( debug ) cout << " edf_n = " << edf_n;
282 // Calculates the incremental output:
284 delta_u_n = Kp * ( (ep_n - ep_n_1)
286 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
287 } else if ( Ti <= 0.0 ) {
288 delta_u_n = Kp * ( (ep_n - ep_n_1)
289 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
293 cout << " delta_u_n = " << delta_u_n << endl;
294 cout << "P:" << Kp * (ep_n - ep_n_1)
295 << " I:" << Kp * ((Ts/Ti) * e_n)
296 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
300 // Integrator anti-windup logic:
301 if ( delta_u_n > (u_max - u_n_1) ) {
303 if ( debug ) cout << " max saturation " << endl;
304 } else if ( delta_u_n < (u_min - u_n_1) ) {
306 if ( debug ) cout << " min saturation " << endl;
309 // Calculates absolute output:
310 u_n = u_n_1 + delta_u_n;
311 if ( debug ) cout << " output = " << u_n << endl;
313 // Updates indexed values;
320 for ( i = 0; i < output_list.size(); ++i ) {
321 output_list[i]->setDoubleValue( u_n );
323 } else if ( !enabled ) {
326 // Updates indexed values;
335 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
336 proportional( false ),
353 for ( i = 0; i < node->nChildren(); ++i ) {
354 SGPropertyNode *child = node->getChild(i);
355 string cname = child->getName();
356 string cval = child->getStringValue();
357 if ( cname == "name" ) {
359 } else if ( cname == "debug" ) {
360 debug = child->getBoolValue();
361 } else if ( cname == "enable" ) {
362 // cout << "parsing enable" << endl;
363 SGPropertyNode *prop = child->getChild( "prop" );
364 if ( prop != NULL ) {
365 // cout << "prop = " << prop->getStringValue() << endl;
366 enable_prop = fgGetNode( prop->getStringValue(), true );
368 // cout << "no prop child" << endl;
370 SGPropertyNode *val = child->getChild( "value" );
372 enable_value = val->getStringValue();
374 } else if ( cname == "input" ) {
375 SGPropertyNode *prop = child->getChild( "prop" );
376 if ( prop != NULL ) {
377 input_prop = fgGetNode( prop->getStringValue(), true );
379 prop = child->getChild( "scale" );
380 if ( prop != NULL ) {
381 y_scale = prop->getDoubleValue();
383 } else if ( cname == "reference" ) {
384 SGPropertyNode *prop = child->getChild( "prop" );
385 if ( prop != NULL ) {
386 r_n_prop = fgGetNode( prop->getStringValue(), true );
388 prop = child->getChild( "value" );
389 if ( prop != NULL ) {
390 r_n = prop->getDoubleValue();
393 prop = child->getChild( "scale" );
394 if ( prop != NULL ) {
395 r_scale = prop->getDoubleValue();
397 } else if ( cname == "output" ) {
399 SGPropertyNode *prop;
400 while ( (prop = child->getChild("prop", i)) != NULL ) {
401 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
402 output_list.push_back( tmp );
405 } else if ( cname == "config" ) {
406 SGPropertyNode *prop;
408 prop = child->getChild( "Kp" );
409 if ( prop != NULL ) {
410 Kp = prop->getDoubleValue();
414 prop = child->getChild( "Ki" );
415 if ( prop != NULL ) {
416 Ki = prop->getDoubleValue();
420 prop = child->getChild( "u_min" );
421 if ( prop != NULL ) {
422 u_min = prop->getDoubleValue();
426 prop = child->getChild( "u_max" );
427 if ( prop != NULL ) {
428 u_max = prop->getDoubleValue();
432 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
433 if ( name.length() ) {
434 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
441 void FGPISimpleController::update( double dt ) {
442 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
444 // we have just been enabled, zero out int_sum
453 if ( debug ) cout << "Updating " << name << endl;
455 if ( input_prop != NULL ) {
456 input = input_prop->getDoubleValue() * y_scale;
460 if ( r_n_prop != NULL ) {
461 r_n = r_n_prop->getDoubleValue() * r_scale;
466 double error = r_n - input;
467 if ( debug ) cout << "input = " << input
468 << " reference = " << r_n
469 << " error = " << error
472 double prop_comp = 0.0;
474 if ( offset_prop != NULL ) {
475 offset = offset_prop->getDoubleValue();
476 if ( debug ) cout << "offset = " << offset << endl;
478 offset = offset_value;
481 if ( proportional ) {
482 prop_comp = error * Kp + offset;
486 int_sum += error * Ki * dt;
491 if ( debug ) cout << "prop_comp = " << prop_comp
492 << " int_sum = " << int_sum << endl;
494 double output = prop_comp + int_sum;
497 if ( output < u_min ) {
500 if ( output > u_max ) {
504 if ( debug ) cout << "output = " << output << endl;
507 for ( i = 0; i < output_list.size(); ++i ) {
508 output_list[i]->setDoubleValue( output );
514 FGPredictor::FGPredictor ( SGPropertyNode *node ):
517 last_value ( 999999999.9 ),
523 for ( i = 0; i < node->nChildren(); ++i ) {
524 SGPropertyNode *child = node->getChild(i);
525 string cname = child->getName();
526 string cval = child->getStringValue();
527 if ( cname == "name" ) {
529 } else if ( cname == "debug" ) {
530 debug = child->getBoolValue();
531 } else if ( cname == "input" ) {
532 input_prop = fgGetNode( child->getStringValue(), true );
533 } else if ( cname == "seconds" ) {
534 seconds = child->getDoubleValue();
535 } else if ( cname == "filter-gain" ) {
536 filter_gain = child->getDoubleValue();
537 } else if ( cname == "output" ) {
538 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
539 output_list.push_back( tmp );
544 void FGPredictor::update( double dt ) {
546 Simple moving average filter converts input value to predicted value "seconds".
548 Smoothing as described by Curt Olson:
549 gain would be valid in the range of 0 - 1.0
550 1.0 would mean no filtering.
551 0.0 would mean no input.
552 0.5 would mean (1 part past value + 1 part current value) / 2
553 0.1 would mean (9 parts past value + 1 part current value) / 10
554 0.25 would mean (3 parts past value + 1 part current value) / 4
558 if ( input_prop != NULL ) {
559 ivalue = input_prop->getDoubleValue();
560 // no sense if there isn't an input :-)
568 // first time initialize average
569 if (last_value >= 999999999.0) {
574 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
576 average = (1.0 - dt) * average + current * dt;
581 // calculate output with filter gain adjustment
582 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
585 for ( i = 0; i < output_list.size(); ++i ) {
586 output_list[i]->setDoubleValue( output );
594 FGXMLAutopilot::FGXMLAutopilot() {
598 FGXMLAutopilot::~FGXMLAutopilot() {
602 void FGXMLAutopilot::init() {
603 config_props = fgGetNode( "/autopilot/new-config", true );
605 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
608 SGPath config( globals->get_fg_root() );
609 config.append( path_n->getStringValue() );
611 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
614 readProperties( config.str(), config_props );
617 SG_LOG( SG_ALL, SG_ALERT,
618 "Detected an internal inconsistancy in the autopilot");
619 SG_LOG( SG_ALL, SG_ALERT,
620 " configuration. See earlier errors for" );
621 SG_LOG( SG_ALL, SG_ALERT,
625 } catch (const sg_exception& exc) {
626 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
631 SG_LOG( SG_ALL, SG_WARN,
632 "No autopilot configuration specified for this model!");
637 void FGXMLAutopilot::reinit() {
644 void FGXMLAutopilot::bind() {
647 void FGXMLAutopilot::unbind() {
650 bool FGXMLAutopilot::build() {
651 SGPropertyNode *node;
654 int count = config_props->nChildren();
655 for ( i = 0; i < count; ++i ) {
656 node = config_props->getChild(i);
657 string name = node->getName();
658 // cout << name << endl;
659 if ( name == "pid-controller" ) {
660 FGXMLAutoComponent *c = new FGPIDController( node );
661 components.push_back( c );
662 } else if ( name == "pi-simple-controller" ) {
663 FGXMLAutoComponent *c = new FGPISimpleController( node );
664 components.push_back( c );
665 } else if ( name == "predict-simple" ) {
666 FGXMLAutoComponent *c = new FGPredictor( node );
667 components.push_back( c );
669 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
680 * Update helper values
682 static void update_helper( double dt ) {
683 // Estimate speed in 5,10 seconds
684 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
685 static SGPropertyNode *lookahead5
686 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
687 static SGPropertyNode *lookahead10
688 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
690 static double average = 0.0; // average/filtered prediction
691 static double v_last = 0.0; // last velocity
693 double v = vel->getDoubleValue();
696 a = (v - v_last) / dt;
699 average = (1.0 - dt) * average + dt * a;
704 lookahead5->setDoubleValue( v + average * 5.0 );
705 lookahead10->setDoubleValue( v + average * 10.0 );
709 // Calculate heading bug error normalized to +/- 180.0 (based on
710 // DG indicated heading)
711 static SGPropertyNode *bug
712 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
713 static SGPropertyNode *ind_hdg
714 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
716 static SGPropertyNode *ind_bug_error
717 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
719 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
720 if ( diff < -180.0 ) { diff += 360.0; }
721 if ( diff > 180.0 ) { diff -= 360.0; }
722 ind_bug_error->setDoubleValue( diff );
724 // Calculate heading bug error normalized to +/- 180.0 (based on
725 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
727 static SGPropertyNode *mag_hdg
728 = fgGetNode( "/orientation/heading-magnetic-deg", true );
729 static SGPropertyNode *fdm_bug_error
730 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
732 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
733 if ( diff < -180.0 ) { diff += 360.0; }
734 if ( diff > 180.0 ) { diff -= 360.0; }
735 fdm_bug_error->setDoubleValue( diff );
737 // Calculate true heading error normalized to +/- 180.0
738 static SGPropertyNode *target_true
739 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
740 static SGPropertyNode *true_hdg
741 = fgGetNode( "/orientation/heading-deg", true );
742 static SGPropertyNode *true_track
743 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
744 static SGPropertyNode *true_error
745 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
747 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
748 if ( diff < -180.0 ) { diff += 360.0; }
749 if ( diff > 180.0 ) { diff -= 360.0; }
750 true_error->setDoubleValue( diff );
752 // Calculate nav1 target heading error normalized to +/- 180.0
753 static SGPropertyNode *target_nav1
754 = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
755 static SGPropertyNode *true_nav1
756 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
757 static SGPropertyNode *true_track_nav1
758 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
760 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
761 if ( diff < -180.0 ) { diff += 360.0; }
762 if ( diff > 180.0 ) { diff -= 360.0; }
763 true_nav1->setDoubleValue( diff );
765 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
766 if ( diff < -180.0 ) { diff += 360.0; }
767 if ( diff > 180.0 ) { diff -= 360.0; }
768 true_track_nav1->setDoubleValue( diff );
770 // Calculate vertical speed in fpm
771 static SGPropertyNode *vs_fps
772 = fgGetNode( "/velocities/vertical-speed-fps", true );
773 static SGPropertyNode *vs_fpm
774 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
776 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
781 * Update the list of autopilot components
784 void FGXMLAutopilot::update( double dt ) {
788 for ( i = 0; i < components.size(); ++i ) {
789 components[i]->update( dt );