]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/xmlauto.cxx
e329d46b3dca5c624822ca2d0070065650f04ea4
[flightgear.git] / src / Autopilot / xmlauto.cxx
1 // xmlauto.cxx - a more flexible, generic way to build autopilots
2 //
3 // Written by Curtis Olson, started January 2004.
4 //
5 // Copyright (C) 2004  Curtis L. Olson  - curt@flightgear.org
6 //
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.
11 //
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.
16 //
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.
20 //
21 // $Id$
22
23
24 #include <simgear/structure/exception.hxx>
25 #include <simgear/misc/sg_path.hxx>
26
27 #include <Main/fg_props.hxx>
28 #include <Main/globals.hxx>
29
30 #include "xmlauto.hxx"
31
32
33 FGPIDController::FGPIDController( SGPropertyNode *node ):
34     debug( false ),
35     y_n( 0.0 ),
36     r_n( 0.0 ),
37     Kp( 0.0 ),
38     alpha( 0.1 ),
39     beta( 1.0 ),
40     gamma( 0.0 ),
41     Ti( 0.0 ),
42     Td( 0.0 ),
43     u_min( 0.0 ),
44     u_max( 0.0 ),
45     ep_n_1( 0.0 ),
46     edf_n_1( 0.0 ),
47     edf_n_2( 0.0 ),
48     u_n_1( 0.0 )
49 {
50     int i;
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" ) {
56             name = cval;
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" );
62             if ( prop != NULL ) {
63                 // cout << "prop = " << prop->getStringValue() << endl;
64                 enable_prop = fgGetNode( prop->getStringValue(), true );
65             } else {
66                 // cout << "no prop child" << endl;
67             }
68             SGPropertyNode *val = child->getChild( "value" );
69             if ( val != NULL ) {
70                 enable_value = val->getStringValue();
71             }
72         } else if ( cname == "input" ) {
73             SGPropertyNode *prop = child->getChild( "prop" );
74             if ( prop != NULL ) {
75                 input_prop = fgGetNode( prop->getStringValue(), true );
76             }
77         } else if ( cname == "reference" ) {
78             SGPropertyNode *prop = child->getChild( "prop" );
79             if ( prop != NULL ) {
80                 r_n_prop = fgGetNode( prop->getStringValue(), true );
81             } else {
82                 prop = child->getChild( "value" );
83                 if ( prop != NULL ) {
84                     r_n = prop->getDoubleValue();
85                 }
86             }
87         } else if ( cname == "output" ) {
88             int i = 0;
89             SGPropertyNode *prop;
90             while ( (prop = child->getChild("prop", i)) != NULL ) {
91                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
92                 output_list.push_back( tmp );
93                 i++;
94             }
95         } else if ( cname == "config" ) {
96             SGPropertyNode *prop;
97
98             prop = child->getChild( "Kp" );
99             if ( prop != NULL ) {
100                 Kp = prop->getDoubleValue();
101             }
102
103             prop = child->getChild( "beta" );
104             if ( prop != NULL ) {
105                 beta = prop->getDoubleValue();
106             }
107
108             prop = child->getChild( "alpha" );
109             if ( prop != NULL ) {
110                 alpha = prop->getDoubleValue();
111             }
112
113             prop = child->getChild( "gamma" );
114             if ( prop != NULL ) {
115                 gamma = prop->getDoubleValue();
116             }
117
118             prop = child->getChild( "Ti" );
119             if ( prop != NULL ) {
120                 Ti = prop->getDoubleValue();
121             }
122
123             prop = child->getChild( "Td" );
124             if ( prop != NULL ) {
125                 Td = prop->getDoubleValue();
126             }
127
128             prop = child->getChild( "u_min" );
129             if ( prop != NULL ) {
130                 u_min = prop->getDoubleValue();
131             }
132
133             prop = child->getChild( "u_max" );
134             if ( prop != NULL ) {
135                 u_max = prop->getDoubleValue();
136             }
137         } else {
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 );
141             }
142         }
143     }   
144 }
145
146
147 /*
148  * Roy Vegard Ovesen:
149  *
150  * Ok! Here is the PID controller algorithm that I would like to see
151  * implemented:
152  *
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) ]
155  *
156  *   u_n = u_n-1 + delta_u_n
157  *
158  * where:
159  *
160  * delta_u : The incremental output
161  * Kp      : Proportional gain
162  * ep      : Proportional error with reference weighing
163  *           ep = beta * r - y
164  *           where:
165  *           beta : Weighing factor
166  *           r    : Reference (setpoint)
167  *           y    : Process value, measured
168  * e       : Error
169  *           e = r - y
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)
175  *           where:
176  *           Tf : Filter time
177  *           Tf = alpha * Td , where alpha usually is set to 0.1
178  *           ed : Unfiltered derivate error with reference weighing
179  *             ed = gamma * r - y
180  *             where:
181  *             gamma : Weighing factor
182  * 
183  * u       : absolute output
184  * 
185  * Index n means the n'th value.
186  * 
187  * 
188  * Inputs:
189  * enabled ,
190  * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
191  * Kp , Ti , Td , Ts (is the sampling time available?)
192  * u_min , u_max
193  * 
194  * Output:
195  * u_n
196  */
197
198 void FGPIDController::update( double dt ) {
199     double ep_n;         // proportional error with reference weighing
200     double e_n;          // error
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)
207
208     if ( Ts <= 0.0 ) {
209         // do nothing if time step is not positive (i.e. no time has
210         // elapsed)
211         return;
212     }
213
214     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
215         enabled = true;
216     } else {
217         enabled = false;
218     }
219
220     if ( enabled ) {
221         if ( debug ) cout << "Updating " << name << endl;
222
223         double y_n = 0.0;
224         if ( input_prop != NULL ) {
225             y_n = input_prop->getDoubleValue();
226         }
227
228         double r_n = 0.0;
229         if ( r_n_prop != NULL ) {
230             r_n = r_n_prop->getDoubleValue();
231         } else {
232             r_n = r_n_value;
233         }
234                       
235         if ( debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
236
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;
241
242         // Calculates error:
243         e_n = r_n - y_n;
244         if ( debug ) cout << " e_n = " << e_n;
245
246         // Calculates derivate error:
247         ed_n = gamma * r_n - y_n;
248         if ( debug ) cout << " ed_n = " << ed_n;
249
250         // Calculates filter time:
251         Tf = alpha * Td;
252         if ( debug ) cout << " Tf = " << Tf;
253
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;
258
259         // Calculates the incremental output:
260         delta_u_n = Kp * ( (ep_n - ep_n_1)
261                            + ((Ts/Ti) * e_n)
262                            + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
263         if ( debug ) cout << " delta_u_n = " << delta_u_n << endl;
264
265         // Integrator anti-windup logic:
266         if ( delta_u_n > (u_max - u_n_1) ) {
267             delta_u_n = 0;
268         } else if ( delta_u_n < (u_min - u_n_1) ) {
269             delta_u_n = 0;
270         }
271
272         // Calculates absolute output:
273         u_n = u_n_1 + delta_u_n;
274         if ( debug ) cout << "  output = " << u_n << endl;
275
276         // Updates indexed values;
277         u_n_1   = u_n;
278         ep_n_1  = ep_n;
279         edf_n_2 = edf_n_1;
280         edf_n_1 = edf_n;
281
282         unsigned int i;
283         for ( i = 0; i < output_list.size(); ++i ) {
284             output_list[i]->setDoubleValue( u_n );
285         }
286     } else if ( !enabled ) {
287         u_n   = 0.0;
288         ep_n  = 0.0;
289         edf_n = 0.0;
290         // Updates indexed values;
291         u_n_1   = u_n;
292         ep_n_1  = ep_n;
293         edf_n_2 = edf_n_1;
294         edf_n_1 = edf_n;
295     }
296 }
297
298
299 FGSimplePIController::FGSimplePIController( SGPropertyNode *node ):
300     proportional( false ),
301     factor( 0.0 ),
302     offset_prop( NULL ),
303     offset_value( 0.0 ),
304     integral( false ),
305     gain( 0.0 ),
306     int_sum( 0.0 ),
307     clamp( false ),
308     debug( false ),
309     y_n( 0.0 ),
310     r_n( 0.0 ),
311     u_min( 0.0 ),
312     u_max( 0.0 )
313 {
314     int i;
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" ) {
320             name = cval;
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 );
327             } else {
328                 // cout << "no prop child" << endl;
329             }
330             SGPropertyNode *val = child->getChild( "value" );
331             if ( val != NULL ) {
332                 enable_value = val->getStringValue();
333             }
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 );
340             }
341         } else if ( cname == "reference" ) {
342             SGPropertyNode *prop = child->getChild( "prop" );
343             if ( prop != NULL ) {
344                 r_n_prop = fgGetNode( prop->getStringValue(), true );
345             } else {
346                 prop = child->getChild( "value" );
347                 if ( prop != NULL ) {
348                     r_n_value = prop->getDoubleValue();
349                 }
350             }
351         } else if ( cname == "output" ) {
352             int i = 0;
353             SGPropertyNode *prop;
354             while ( (prop = child->getChild("prop", i)) != NULL ) {
355                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
356                 output_list.push_back( tmp );
357                 i++;
358             }
359             prop = child->getChild( "clamp" );
360             if ( prop != NULL ) {
361                 clamp = true;
362
363                 SGPropertyNode *tmp;
364
365                 tmp = prop->getChild( "min" );
366                 if ( tmp != NULL ) {
367                     u_min = tmp->getDoubleValue();
368                     // cout << "min = " << u_min << endl;
369                 }
370
371                 tmp = prop->getChild( "max" );
372                 if ( tmp != NULL ) {
373                     u_max = tmp->getDoubleValue();
374                     // cout << "max = " << u_max << endl;
375                 }
376             }
377         } else if ( cname == "proportional" ) {
378             proportional = true;
379
380             SGPropertyNode *prop;
381
382             prop = child->getChild( "factor" );
383             if ( prop != NULL ) {
384                 factor = prop->getDoubleValue();
385             }
386
387             prop = child->getChild( "offset" );
388             if ( prop != NULL ) {
389                 SGPropertyNode *sub = prop->getChild( "prop" );
390                 if ( sub != NULL ) {
391                     offset_prop = fgGetNode( sub->getStringValue(), true );
392                     // cout << "offset prop = " << sub->getStringValue() << endl;
393                 } else {
394                     sub = prop->getChild( "value" );
395                     if ( sub != NULL ) {
396                         offset_value = sub->getDoubleValue();
397                         // cout << "offset value = " << offset_value << endl;
398                     }
399                 }
400             }
401         } else if ( cname == "integral" ) {
402             integral = true;
403
404             SGPropertyNode *prop;
405             prop = child->getChild( "gain" );
406             if ( prop != NULL ) {
407                 gain = prop->getDoubleValue();
408             }
409         } else {
410             SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
411         }
412     }   
413 }
414
415
416 void FGSimplePIController::update( double dt ) {
417     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
418         if ( !enabled ) {
419             // we have just been enabled, zero out int_sum
420             int_sum = 0.0;
421         }
422         enabled = true;
423     } else {
424         enabled = false;
425     }
426
427     if ( enabled ) {
428         if ( debug ) cout << "Updating " << name << endl;
429         double input = 0.0;
430         if ( input_prop != NULL ) {
431             input = input_prop->getDoubleValue();
432         }
433
434         double r_n = 0.0;
435         if ( r_n_prop != NULL ) {
436             r_n = r_n_prop->getDoubleValue();
437         } else {
438             r_n = r_n_value;
439         }
440                       
441         double error = r_n - input;
442         if ( debug ) cout << "input = " << input
443                           << " reference = " << r_n
444                           << " error = " << error
445                           << endl;
446
447         double prop_comp = 0.0;
448         double offset = 0.0;
449         if ( offset_prop != NULL ) {
450             offset = offset_prop->getDoubleValue();
451             if ( debug ) cout << "offset = " << offset << endl;
452         } else {
453             offset = offset_value;
454         }
455
456         if ( proportional ) {
457             prop_comp = error * factor + offset;
458         }
459
460         if ( integral ) {
461             int_sum += error * gain * dt;
462         } else {
463             int_sum = 0.0;
464         }
465
466         if ( debug ) cout << "prop_comp = " << prop_comp
467                           << " int_sum = " << int_sum << endl;
468
469         double output = prop_comp + int_sum;
470
471         if ( clamp ) {
472             if ( output < u_min ) {
473                 output = u_min;
474             }
475             if ( output > u_max ) {
476                 output = u_max;
477             }
478         }
479         if ( debug ) cout << "output = " << output << endl;
480
481         unsigned int i;
482         for ( i = 0; i < output_list.size(); ++i ) {
483             output_list[i]->setDoubleValue( output );
484         }
485     }
486 }
487
488
489 FGXMLAutopilot::FGXMLAutopilot() {
490 }
491
492
493 FGXMLAutopilot::~FGXMLAutopilot() {
494 }
495
496  
497 void FGXMLAutopilot::init() {
498     config_props = fgGetNode( "/autopilot/new-config", true );
499
500     SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
501
502     if ( path_n ) {
503         SGPath config( globals->get_fg_root() );
504         config.append( path_n->getStringValue() );
505
506         SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
507                 << config.str() );
508         try {
509             readProperties( config.str(), config_props );
510
511             if ( ! build() ) {
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,
517                         " details.");
518                 exit(-1);
519             }        
520         } catch (const sg_exception& exc) {
521             SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
522                     << config.str() );
523         }
524
525     } else {
526         SG_LOG( SG_ALL, SG_WARN,
527                 "No autopilot configuration specified for this model!");
528     }
529 }
530
531
532 void FGXMLAutopilot::reinit() {
533     components.clear();
534     init();
535     build();
536 }
537
538
539 void FGXMLAutopilot::bind() {
540 }
541
542 void FGXMLAutopilot::unbind() {
543 }
544
545 bool FGXMLAutopilot::build() {
546     SGPropertyNode *node;
547     int i;
548
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 );
557         } else {
558             SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
559                     << name );
560             return false;
561         }
562     }
563
564     return true;
565 }
566
567
568 /*
569  * Update helper values
570  */
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 );
578
579     static double average = 0.0; // average/filtered prediction
580     static double v_last = 0.0;  // last velocity
581
582     double v = vel->getDoubleValue();
583     double a = 0.0;
584     if ( dt > 0.0 ) {
585         a = (v - v_last) / dt;
586
587         if ( dt < 1.0 ) {
588             average = (1.0 - dt) * average + dt * a;
589         } else {
590             average = a;
591         }
592
593         lookahead5->setDoubleValue( v + average * 5.0 );
594         lookahead10->setDoubleValue( v + average * 10.0 );
595         v_last = v;
596     }
597
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",
604                      true );
605     static SGPropertyNode *ind_bug_error
606         = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
607
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 );
612
613     // Calculate heading bug error normalized to +/- 180.0 (based on
614     // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
615     // compass.)
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 );
620
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 );
625
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 );
633
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 );
638
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 );
644
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 );
649
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 );
655
656     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );  
657 }
658
659
660 /*
661  * Update the list of autopilot components
662  */
663
664 void FGXMLAutopilot::update( double dt ) {
665     update_helper( dt );
666
667     unsigned int i;
668     for ( i = 0; i < components.size(); ++i ) {
669         components[i]->update( dt );
670     }
671 }