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) {
216 // first time being enabled, seed u_n with current
217 // property tree value
218 u_n = output_list[0]->getDoubleValue();
220 if ( u_n < u_min ) { u_n = u_min; }
221 if ( u_n > u_max ) { u_n = u_max; }
230 if ( debug ) cout << "Updating " << name << endl;
233 if ( input_prop != NULL ) {
234 y_n = input_prop->getDoubleValue();
238 if ( r_n_prop != NULL ) {
239 r_n = r_n_prop->getDoubleValue();
244 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
246 // Calculates proportional error:
247 ep_n = beta * r_n - y_n;
248 if ( debug ) cout << " ep_n = " << ep_n;
249 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
253 if ( debug ) cout << " e_n = " << e_n;
255 // Calculates derivate error:
256 ed_n = gamma * r_n - y_n;
257 if ( debug ) cout << " ed_n = " << ed_n;
259 // Calculates filter time:
261 if ( debug ) cout << " Tf = " << Tf;
263 // Filters the derivate error:
264 edf_n = edf_n_1 / (Ts/Tf + 1)
265 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
266 if ( debug ) cout << " edf_n = " << edf_n;
268 // Calculates the incremental output:
269 delta_u_n = Kp * ( (ep_n - ep_n_1)
271 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
272 if ( debug ) cout << " delta_u_n = " << delta_u_n << endl;
274 // Integrator anti-windup logic:
275 if ( delta_u_n > (u_max - u_n_1) ) {
277 } else if ( delta_u_n < (u_min - u_n_1) ) {
281 // Calculates absolute output:
282 u_n = u_n_1 + delta_u_n;
283 if ( debug ) cout << " output = " << u_n << endl;
285 // Updates indexed values;
292 for ( i = 0; i < output_list.size(); ++i ) {
293 output_list[i]->setDoubleValue( u_n );
295 } else if ( !enabled ) {
299 // Updates indexed values;
308 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
309 proportional( false ),
324 for ( i = 0; i < node->nChildren(); ++i ) {
325 SGPropertyNode *child = node->getChild(i);
326 string cname = child->getName();
327 string cval = child->getStringValue();
328 if ( cname == "name" ) {
330 } else if ( cname == "debug" ) {
331 debug = child->getBoolValue();
332 } else if ( cname == "enable" ) {
333 // cout << "parsing enable" << endl;
334 SGPropertyNode *prop = child->getChild( "prop" );
335 if ( prop != NULL ) {
336 // cout << "prop = " << prop->getStringValue() << endl;
337 enable_prop = fgGetNode( prop->getStringValue(), true );
339 // cout << "no prop child" << endl;
341 SGPropertyNode *val = child->getChild( "value" );
343 enable_value = val->getStringValue();
345 } else if ( cname == "input" ) {
346 SGPropertyNode *prop = child->getChild( "prop" );
347 if ( prop != NULL ) {
348 input_prop = fgGetNode( prop->getStringValue(), true );
350 } else if ( cname == "reference" ) {
351 SGPropertyNode *prop = child->getChild( "prop" );
352 if ( prop != NULL ) {
353 r_n_prop = fgGetNode( prop->getStringValue(), true );
355 prop = child->getChild( "value" );
356 if ( prop != NULL ) {
357 r_n = prop->getDoubleValue();
360 } else if ( cname == "output" ) {
362 SGPropertyNode *prop;
363 while ( (prop = child->getChild("prop", i)) != NULL ) {
364 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
365 output_list.push_back( tmp );
368 } else if ( cname == "config" ) {
369 SGPropertyNode *prop;
371 prop = child->getChild( "Kp" );
372 if ( prop != NULL ) {
373 Kp = prop->getDoubleValue();
377 prop = child->getChild( "Ki" );
378 if ( prop != NULL ) {
379 Ki = prop->getDoubleValue();
383 prop = child->getChild( "u_min" );
384 if ( prop != NULL ) {
385 u_min = prop->getDoubleValue();
389 prop = child->getChild( "u_max" );
390 if ( prop != NULL ) {
391 u_max = prop->getDoubleValue();
395 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
396 if ( name.length() ) {
397 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
404 void FGPISimpleController::update( double dt ) {
405 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
407 // we have just been enabled, zero out int_sum
416 if ( debug ) cout << "Updating " << name << endl;
418 if ( input_prop != NULL ) {
419 input = input_prop->getDoubleValue();
423 if ( r_n_prop != NULL ) {
424 r_n = r_n_prop->getDoubleValue();
429 double error = r_n - input;
430 if ( debug ) cout << "input = " << input
431 << " reference = " << r_n
432 << " error = " << error
435 double prop_comp = 0.0;
437 if ( offset_prop != NULL ) {
438 offset = offset_prop->getDoubleValue();
439 if ( debug ) cout << "offset = " << offset << endl;
441 offset = offset_value;
444 if ( proportional ) {
445 prop_comp = error * Kp + offset;
449 int_sum += error * Ki * dt;
454 if ( debug ) cout << "prop_comp = " << prop_comp
455 << " int_sum = " << int_sum << endl;
457 double output = prop_comp + int_sum;
460 if ( output < u_min ) {
463 if ( output > u_max ) {
467 if ( debug ) cout << "output = " << output << endl;
470 for ( i = 0; i < output_list.size(); ++i ) {
471 output_list[i]->setDoubleValue( output );
477 FGXMLAutopilot::FGXMLAutopilot() {
481 FGXMLAutopilot::~FGXMLAutopilot() {
485 void FGXMLAutopilot::init() {
486 config_props = fgGetNode( "/autopilot/new-config", true );
488 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
491 SGPath config( globals->get_fg_root() );
492 config.append( path_n->getStringValue() );
494 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
497 readProperties( config.str(), config_props );
500 SG_LOG( SG_ALL, SG_ALERT,
501 "Detected an internal inconsistancy in the autopilot");
502 SG_LOG( SG_ALL, SG_ALERT,
503 " configuration. See earlier errors for" );
504 SG_LOG( SG_ALL, SG_ALERT,
508 } catch (const sg_exception& exc) {
509 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
514 SG_LOG( SG_ALL, SG_WARN,
515 "No autopilot configuration specified for this model!");
520 void FGXMLAutopilot::reinit() {
527 void FGXMLAutopilot::bind() {
530 void FGXMLAutopilot::unbind() {
533 bool FGXMLAutopilot::build() {
534 SGPropertyNode *node;
537 int count = config_props->nChildren();
538 for ( i = 0; i < count; ++i ) {
539 node = config_props->getChild(i);
540 string name = node->getName();
541 // cout << name << endl;
542 if ( name == "pid-controller" ) {
543 FGXMLAutoComponent *c = new FGPIDController( node );
544 components.push_back( c );
545 } else if ( name == "pi-simple-controller" ) {
546 FGXMLAutoComponent *c = new FGPISimpleController( node );
547 components.push_back( c );
549 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
560 * Update helper values
562 static void update_helper( double dt ) {
563 // Estimate speed in 5,10 seconds
564 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
565 static SGPropertyNode *lookahead5
566 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
567 static SGPropertyNode *lookahead10
568 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
570 static double average = 0.0; // average/filtered prediction
571 static double v_last = 0.0; // last velocity
573 double v = vel->getDoubleValue();
576 a = (v - v_last) / dt;
579 average = (1.0 - dt) * average + dt * a;
584 lookahead5->setDoubleValue( v + average * 5.0 );
585 lookahead10->setDoubleValue( v + average * 10.0 );
589 // Calculate heading bug error normalized to +/- 180.0 (based on
590 // DG indicated heading)
591 static SGPropertyNode *bug
592 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
593 static SGPropertyNode *ind_hdg
594 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
596 static SGPropertyNode *ind_bug_error
597 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
599 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
600 if ( diff < -180.0 ) { diff += 360.0; }
601 if ( diff > 180.0 ) { diff -= 360.0; }
602 ind_bug_error->setDoubleValue( diff );
604 // Calculate heading bug error normalized to +/- 180.0 (based on
605 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
607 static SGPropertyNode *mag_hdg
608 = fgGetNode( "/orientation/heading-magnetic-deg", true );
609 static SGPropertyNode *fdm_bug_error
610 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
612 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
613 if ( diff < -180.0 ) { diff += 360.0; }
614 if ( diff > 180.0 ) { diff -= 360.0; }
615 fdm_bug_error->setDoubleValue( diff );
617 // Calculate true heading error normalized to +/- 180.0
618 static SGPropertyNode *target_true
619 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
620 static SGPropertyNode *true_hdg
621 = fgGetNode( "/orientation/heading-deg", true );
622 static SGPropertyNode *true_error
623 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
625 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
626 if ( diff < -180.0 ) { diff += 360.0; }
627 if ( diff > 180.0 ) { diff -= 360.0; }
628 true_error->setDoubleValue( diff );
630 // Calculate nav1 target heading error normalized to +/- 180.0
631 static SGPropertyNode *target_nav1
632 = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
633 static SGPropertyNode *true_nav1
634 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
636 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
637 if ( diff < -180.0 ) { diff += 360.0; }
638 if ( diff > 180.0 ) { diff -= 360.0; }
639 true_nav1->setDoubleValue( diff );
641 // Calculate vertical speed in fpm
642 static SGPropertyNode *vs_fps
643 = fgGetNode( "/velocities/vertical-speed-fps", true );
644 static SGPropertyNode *vs_fpm
645 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
647 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
652 * Update the list of autopilot components
655 void FGXMLAutopilot::update( double dt ) {
659 for ( i = 0; i < components.size(); ++i ) {
660 components[i]->update( dt );