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 FGPISimpleController::FGPISimpleController( 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 == "debug" ) {
322 debug = child->getBoolValue();
323 } else if ( cname == "enable" ) {
324 // cout << "parsing enable" << endl;
325 SGPropertyNode *prop = child->getChild( "prop" );
326 if ( prop != NULL ) {
327 // cout << "prop = " << prop->getStringValue() << endl;
328 enable_prop = fgGetNode( prop->getStringValue(), true );
330 // cout << "no prop child" << endl;
332 SGPropertyNode *val = child->getChild( "value" );
334 enable_value = val->getStringValue();
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 = 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 } else if ( cname == "config" ) {
360 SGPropertyNode *prop;
362 prop = child->getChild( "Kp" );
363 if ( prop != NULL ) {
364 Kp = prop->getDoubleValue();
368 prop = child->getChild( "Ki" );
369 if ( prop != NULL ) {
370 Ki = prop->getDoubleValue();
374 prop = child->getChild( "u_min" );
375 if ( prop != NULL ) {
376 u_min = prop->getDoubleValue();
380 prop = child->getChild( "u_max" );
381 if ( prop != NULL ) {
382 u_max = prop->getDoubleValue();
386 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
387 if ( name.length() ) {
388 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
395 void FGPISimpleController::update( double dt ) {
396 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
398 // we have just been enabled, zero out int_sum
407 if ( debug ) cout << "Updating " << name << endl;
409 if ( input_prop != NULL ) {
410 input = input_prop->getDoubleValue();
414 if ( r_n_prop != NULL ) {
415 r_n = r_n_prop->getDoubleValue();
420 double error = r_n - input;
421 if ( debug ) cout << "input = " << input
422 << " reference = " << r_n
423 << " error = " << error
426 double prop_comp = 0.0;
428 if ( offset_prop != NULL ) {
429 offset = offset_prop->getDoubleValue();
430 if ( debug ) cout << "offset = " << offset << endl;
432 offset = offset_value;
435 if ( proportional ) {
436 prop_comp = error * Kp + offset;
440 int_sum += error * Ki * dt;
445 if ( debug ) cout << "prop_comp = " << prop_comp
446 << " int_sum = " << int_sum << endl;
448 double output = prop_comp + int_sum;
451 if ( output < u_min ) {
454 if ( output > u_max ) {
458 if ( debug ) cout << "output = " << output << endl;
461 for ( i = 0; i < output_list.size(); ++i ) {
462 output_list[i]->setDoubleValue( output );
468 FGXMLAutopilot::FGXMLAutopilot() {
472 FGXMLAutopilot::~FGXMLAutopilot() {
476 void FGXMLAutopilot::init() {
477 config_props = fgGetNode( "/autopilot/new-config", true );
479 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
482 SGPath config( globals->get_fg_root() );
483 config.append( path_n->getStringValue() );
485 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
488 readProperties( config.str(), config_props );
491 SG_LOG( SG_ALL, SG_ALERT,
492 "Detected an internal inconsistancy in the autopilot");
493 SG_LOG( SG_ALL, SG_ALERT,
494 " configuration. See earlier errors for" );
495 SG_LOG( SG_ALL, SG_ALERT,
499 } catch (const sg_exception& exc) {
500 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
505 SG_LOG( SG_ALL, SG_WARN,
506 "No autopilot configuration specified for this model!");
511 void FGXMLAutopilot::reinit() {
518 void FGXMLAutopilot::bind() {
521 void FGXMLAutopilot::unbind() {
524 bool FGXMLAutopilot::build() {
525 SGPropertyNode *node;
528 int count = config_props->nChildren();
529 for ( i = 0; i < count; ++i ) {
530 node = config_props->getChild(i);
531 string name = node->getName();
532 // cout << name << endl;
533 if ( name == "pid-controller" ) {
534 FGXMLAutoComponent *c = new FGPIDController( node );
535 components.push_back( c );
536 } else if ( name == "pi-simple-controller" ) {
537 FGXMLAutoComponent *c = new FGPISimpleController( node );
538 components.push_back( c );
540 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
551 * Update helper values
553 static void update_helper( double dt ) {
554 // Estimate speed in 5,10 seconds
555 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
556 static SGPropertyNode *lookahead5
557 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
558 static SGPropertyNode *lookahead10
559 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
561 static double average = 0.0; // average/filtered prediction
562 static double v_last = 0.0; // last velocity
564 double v = vel->getDoubleValue();
567 a = (v - v_last) / dt;
570 average = (1.0 - dt) * average + dt * a;
575 lookahead5->setDoubleValue( v + average * 5.0 );
576 lookahead10->setDoubleValue( v + average * 10.0 );
580 // Calculate heading bug error normalized to +/- 180.0 (based on
581 // DG indicated heading)
582 static SGPropertyNode *bug
583 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
584 static SGPropertyNode *ind_hdg
585 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
587 static SGPropertyNode *ind_bug_error
588 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
590 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
591 if ( diff < -180.0 ) { diff += 360.0; }
592 if ( diff > 180.0 ) { diff -= 360.0; }
593 ind_bug_error->setDoubleValue( diff );
595 // Calculate heading bug error normalized to +/- 180.0 (based on
596 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
598 static SGPropertyNode *mag_hdg
599 = fgGetNode( "/orientation/heading-magnetic-deg", true );
600 static SGPropertyNode *fdm_bug_error
601 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
603 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
604 if ( diff < -180.0 ) { diff += 360.0; }
605 if ( diff > 180.0 ) { diff -= 360.0; }
606 fdm_bug_error->setDoubleValue( diff );
608 // Calculate true heading error normalized to +/- 180.0
609 static SGPropertyNode *target_true
610 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
611 static SGPropertyNode *true_hdg
612 = fgGetNode( "/orientation/heading-deg", true );
613 static SGPropertyNode *true_error
614 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
616 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
617 if ( diff < -180.0 ) { diff += 360.0; }
618 if ( diff > 180.0 ) { diff -= 360.0; }
619 true_error->setDoubleValue( diff );
621 // Calculate nav1 target heading error normalized to +/- 180.0
622 static SGPropertyNode *target_nav1
623 = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
624 static SGPropertyNode *true_nav1
625 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
627 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
628 if ( diff < -180.0 ) { diff += 360.0; }
629 if ( diff > 180.0 ) { diff -= 360.0; }
630 true_nav1->setDoubleValue( diff );
632 // Calculate vertical speed in fpm
633 static SGPropertyNode *vs_fps
634 = fgGetNode( "/velocities/vertical-speed-fps", true );
635 static SGPropertyNode *vs_fpm
636 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
638 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
643 * Update the list of autopilot components
646 void FGXMLAutopilot::update( double dt ) {
650 for ( i = 0; i < components.size(); ++i ) {
651 components[i]->update( dt );