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 ):
51 for ( i = 0; i < node->nChildren(); ++i ) {
52 SGPropertyNode *child = node->getChild(i);
53 string cname = child->getName();
54 string cval = child->getStringValue();
55 if ( cname == "name" ) {
57 } else if ( cname == "debug" ) {
58 debug = child->getBoolValue();
59 } else if ( cname == "enable" ) {
60 // cout << "parsing enable" << endl;
61 SGPropertyNode *prop = child->getChild( "prop" );
63 // cout << "prop = " << prop->getStringValue() << endl;
64 enable_prop = fgGetNode( prop->getStringValue(), true );
66 // cout << "no prop child" << endl;
68 SGPropertyNode *val = child->getChild( "value" );
70 enable_value = val->getStringValue();
72 } else if ( cname == "input" ) {
73 SGPropertyNode *prop = child->getChild( "prop" );
75 input_prop = fgGetNode( prop->getStringValue(), true );
77 } else if ( cname == "reference" ) {
78 SGPropertyNode *prop = child->getChild( "prop" );
80 r_n_prop = fgGetNode( prop->getStringValue(), true );
82 prop = child->getChild( "value" );
84 r_n = prop->getDoubleValue();
87 } else if ( cname == "output" ) {
90 while ( (prop = child->getChild("prop", i)) != NULL ) {
91 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
92 output_list.push_back( tmp );
95 } else if ( cname == "config" ) {
98 prop = child->getChild( "Kp" );
100 Kp = prop->getDoubleValue();
103 prop = child->getChild( "beta" );
104 if ( prop != NULL ) {
105 beta = prop->getDoubleValue();
108 prop = child->getChild( "alpha" );
109 if ( prop != NULL ) {
110 alpha = prop->getDoubleValue();
113 prop = child->getChild( "gamma" );
114 if ( prop != NULL ) {
115 gamma = prop->getDoubleValue();
118 prop = child->getChild( "Ti" );
119 if ( prop != NULL ) {
120 Ti = prop->getDoubleValue();
123 prop = child->getChild( "Td" );
124 if ( prop != NULL ) {
125 Td = prop->getDoubleValue();
128 prop = child->getChild( "u_min" );
129 if ( prop != NULL ) {
130 u_min = prop->getDoubleValue();
133 prop = child->getChild( "u_max" );
134 if ( prop != NULL ) {
135 u_max = prop->getDoubleValue();
138 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
139 if ( name.length() ) {
140 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
150 * Ok! Here is the PID controller algorithm that I would like to see
153 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
154 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
156 * u_n = u_n-1 + delta_u_n
160 * delta_u : The incremental output
161 * Kp : Proportional gain
162 * ep : Proportional error with reference weighing
165 * beta : Weighing factor
166 * r : Reference (setpoint)
167 * y : Process value, measured
170 * Ts : Sampling interval
171 * Ti : Integrator time
172 * Td : Derivator time
173 * edf : Derivate error with reference weighing and filtering
174 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
177 * Tf = alpha * Td , where alpha usually is set to 0.1
178 * ed : Unfiltered derivate error with reference weighing
181 * gamma : Weighing factor
183 * u : absolute output
185 * Index n means the n'th value.
190 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
191 * Kp , Ti , Td , Ts (is the sampling time available?)
198 void FGPIDController::update( double dt ) {
199 double ep_n; // proportional error with reference weighing
201 double ed_n; // derivative error
202 double edf_n; // derivative error filter
203 double Tf; // filter time
204 double delta_u_n; // incremental output
205 double u_n; // absolute output
206 double Ts = dt; // Sampling interval (sec)
209 // do nothing if time step is not positive (i.e. no time has
214 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
221 if ( debug ) cout << "Updating " << name << endl;
224 if ( input_prop != NULL ) {
225 y_n = input_prop->getDoubleValue();
229 if ( r_n_prop != NULL ) {
230 r_n = r_n_prop->getDoubleValue();
235 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
237 // Calculates proportional error:
238 ep_n = beta * r_n - y_n;
239 if ( debug ) cout << " ep_n = " << ep_n;
240 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
244 if ( debug ) cout << " e_n = " << e_n;
246 // Calculates derivate error:
247 ed_n = gamma * r_n - y_n;
248 if ( debug ) cout << " ed_n = " << ed_n;
250 // Calculates filter time:
252 if ( debug ) cout << " Tf = " << Tf;
254 // Filters the derivate error:
255 edf_n = edf_n_1 / (Ts/Tf + 1)
256 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
257 if ( debug ) cout << " edf_n = " << edf_n;
259 // Calculates the incremental output:
260 delta_u_n = Kp * ( (ep_n - ep_n_1)
262 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
263 if ( debug ) cout << " delta_u_n = " << delta_u_n << endl;
265 // Integrator anti-windup logic:
266 if ( delta_u_n > (u_max - u_n_1) ) {
268 } else if ( delta_u_n < (u_min - u_n_1) ) {
272 // Calculates absolute output:
273 u_n = u_n_1 + delta_u_n;
274 if ( debug ) cout << " output = " << u_n << endl;
276 // Updates indexed values;
283 for ( i = 0; i < output_list.size(); ++i ) {
284 output_list[i]->setDoubleValue( u_n );
286 } else if ( !enabled ) {
290 // Updates indexed values;
299 FGSimplePIController::FGSimplePIController( SGPropertyNode *node ):
300 proportional( false ),
315 for ( i = 0; i < node->nChildren(); ++i ) {
316 SGPropertyNode *child = node->getChild(i);
317 string cname = child->getName();
318 string cval = child->getStringValue();
319 if ( cname == "name" ) {
321 } else if ( cname == "enable" ) {
322 // cout << "parsing enable" << endl;
323 SGPropertyNode *prop = child->getChild( "prop" );
324 if ( prop != NULL ) {
325 // cout << "prop = " << prop->getStringValue() << endl;
326 enable_prop = fgGetNode( prop->getStringValue(), true );
328 // cout << "no prop child" << endl;
330 SGPropertyNode *val = child->getChild( "value" );
332 enable_value = val->getStringValue();
334 } else if ( cname == "debug" ) {
335 debug = child->getBoolValue();
336 } else if ( cname == "input" ) {
337 SGPropertyNode *prop = child->getChild( "prop" );
338 if ( prop != NULL ) {
339 input_prop = fgGetNode( prop->getStringValue(), true );
341 } else if ( cname == "reference" ) {
342 SGPropertyNode *prop = child->getChild( "prop" );
343 if ( prop != NULL ) {
344 r_n_prop = fgGetNode( prop->getStringValue(), true );
346 prop = child->getChild( "value" );
347 if ( prop != NULL ) {
348 r_n_value = prop->getDoubleValue();
351 } else if ( cname == "output" ) {
353 SGPropertyNode *prop;
354 while ( (prop = child->getChild("prop", i)) != NULL ) {
355 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
356 output_list.push_back( tmp );
359 prop = child->getChild( "clamp" );
360 if ( prop != NULL ) {
365 tmp = prop->getChild( "min" );
367 u_min = tmp->getDoubleValue();
368 // cout << "min = " << u_min << endl;
371 tmp = prop->getChild( "max" );
373 u_max = tmp->getDoubleValue();
374 // cout << "max = " << u_max << endl;
377 } else if ( cname == "proportional" ) {
380 SGPropertyNode *prop;
382 prop = child->getChild( "factor" );
383 if ( prop != NULL ) {
384 factor = prop->getDoubleValue();
387 prop = child->getChild( "offset" );
388 if ( prop != NULL ) {
389 SGPropertyNode *sub = prop->getChild( "prop" );
391 offset_prop = fgGetNode( sub->getStringValue(), true );
392 // cout << "offset prop = " << sub->getStringValue() << endl;
394 sub = prop->getChild( "value" );
396 offset_value = sub->getDoubleValue();
397 // cout << "offset value = " << offset_value << endl;
401 } else if ( cname == "integral" ) {
404 SGPropertyNode *prop;
405 prop = child->getChild( "gain" );
406 if ( prop != NULL ) {
407 gain = prop->getDoubleValue();
410 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
416 void FGSimplePIController::update( double dt ) {
417 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
419 // we have just been enabled, zero out int_sum
428 if ( debug ) cout << "Updating " << name << endl;
430 if ( input_prop != NULL ) {
431 input = input_prop->getDoubleValue();
435 if ( r_n_prop != NULL ) {
436 r_n = r_n_prop->getDoubleValue();
441 double error = r_n - input;
442 if ( debug ) cout << "input = " << input
443 << " reference = " << r_n
444 << " error = " << error
447 double prop_comp = 0.0;
449 if ( offset_prop != NULL ) {
450 offset = offset_prop->getDoubleValue();
451 if ( debug ) cout << "offset = " << offset << endl;
453 offset = offset_value;
456 if ( proportional ) {
457 prop_comp = error * factor + offset;
461 int_sum += error * gain * dt;
466 if ( debug ) cout << "prop_comp = " << prop_comp
467 << " int_sum = " << int_sum << endl;
469 double output = prop_comp + int_sum;
472 if ( output < u_min ) {
475 if ( output > u_max ) {
479 if ( debug ) cout << "output = " << output << endl;
482 for ( i = 0; i < output_list.size(); ++i ) {
483 output_list[i]->setDoubleValue( output );
489 FGXMLAutopilot::FGXMLAutopilot() {
493 FGXMLAutopilot::~FGXMLAutopilot() {
497 void FGXMLAutopilot::init() {
498 config_props = fgGetNode( "/autopilot/new-config", true );
500 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
503 SGPath config( globals->get_fg_root() );
504 config.append( path_n->getStringValue() );
506 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
509 readProperties( config.str(), config_props );
512 SG_LOG( SG_ALL, SG_ALERT,
513 "Detected an internal inconsistancy in the autopilot");
514 SG_LOG( SG_ALL, SG_ALERT,
515 " configuration. See earlier errors for" );
516 SG_LOG( SG_ALL, SG_ALERT,
520 } catch (const sg_exception& exc) {
521 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
526 SG_LOG( SG_ALL, SG_WARN,
527 "No autopilot configuration specified for this model!");
532 void FGXMLAutopilot::reinit() {
539 void FGXMLAutopilot::bind() {
542 void FGXMLAutopilot::unbind() {
545 bool FGXMLAutopilot::build() {
546 SGPropertyNode *node;
549 int count = config_props->nChildren();
550 for ( i = 0; i < count; ++i ) {
551 node = config_props->getChild(i);
552 string name = node->getName();
553 // cout << name << endl;
554 if ( name == "pid-controller" ) {
555 FGXMLAutoComponent *c = new FGPIDController( node );
556 components.push_back( c );
558 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
569 * Update helper values
571 static void update_helper( double dt ) {
572 // Estimate speed in 5,10 seconds
573 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
574 static SGPropertyNode *lookahead5
575 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
576 static SGPropertyNode *lookahead10
577 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
579 static double average = 0.0; // average/filtered prediction
580 static double v_last = 0.0; // last velocity
582 double v = vel->getDoubleValue();
585 a = (v - v_last) / dt;
588 average = (1.0 - dt) * average + dt * a;
593 lookahead5->setDoubleValue( v + average * 5.0 );
594 lookahead10->setDoubleValue( v + average * 10.0 );
598 // Calculate heading bug error normalized to +/- 180.0 (based on
599 // DG indicated heading)
600 static SGPropertyNode *bug
601 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
602 static SGPropertyNode *ind_hdg
603 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
605 static SGPropertyNode *ind_bug_error
606 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
608 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
609 if ( diff < -180.0 ) { diff += 360.0; }
610 if ( diff > 180.0 ) { diff -= 360.0; }
611 ind_bug_error->setDoubleValue( diff );
613 // Calculate heading bug error normalized to +/- 180.0 (based on
614 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
616 static SGPropertyNode *mag_hdg
617 = fgGetNode( "/orientation/heading-magnetic-deg", true );
618 static SGPropertyNode *fdm_bug_error
619 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
621 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
622 if ( diff < -180.0 ) { diff += 360.0; }
623 if ( diff > 180.0 ) { diff -= 360.0; }
624 fdm_bug_error->setDoubleValue( diff );
626 // Calculate true heading error normalized to +/- 180.0
627 static SGPropertyNode *target_true
628 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
629 static SGPropertyNode *true_hdg
630 = fgGetNode( "/orientation/heading-deg", true );
631 static SGPropertyNode *true_error
632 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
634 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
635 if ( diff < -180.0 ) { diff += 360.0; }
636 if ( diff > 180.0 ) { diff -= 360.0; }
637 true_error->setDoubleValue( diff );
639 // Calculate nav1 target heading error normalized to +/- 180.0
640 static SGPropertyNode *target_nav1
641 = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
642 static SGPropertyNode *true_nav1
643 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
645 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
646 if ( diff < -180.0 ) { diff += 360.0; }
647 if ( diff > 180.0 ) { diff -= 360.0; }
648 true_nav1->setDoubleValue( diff );
650 // Calculate vertical speed in fpm
651 static SGPropertyNode *vs_fps
652 = fgGetNode( "/velocities/vertical-speed-fps", true );
653 static SGPropertyNode *vs_fpm
654 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
656 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
661 * Update the list of autopilot components
664 void FGXMLAutopilot::update( double dt ) {
668 for ( i = 0; i < components.size(); ++i ) {
669 components[i]->update( dt );