]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/xmlauto.cxx
9aa550c5598933016f58f0f73feaf9a5c26232a9
[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     y_scale( 1.0 ),
38     r_scale( 1.0 ),
39     Kp( 0.0 ),
40     alpha( 0.1 ),
41     beta( 1.0 ),
42     gamma( 0.0 ),
43     Ti( 0.0 ),
44     Td( 0.0 ),
45     u_min( 0.0 ),
46     u_max( 0.0 ),
47     ep_n_1( 0.0 ),
48     edf_n_1( 0.0 ),
49     edf_n_2( 0.0 ),
50     u_n_1( 0.0 )
51 {
52     int i;
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" ) {
58             name = cval;
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" );
64             if ( prop != NULL ) {
65                 // cout << "prop = " << prop->getStringValue() << endl;
66                 enable_prop = fgGetNode( prop->getStringValue(), true );
67             } else {
68                 // cout << "no prop child" << endl;
69             }
70             SGPropertyNode *val = child->getChild( "value" );
71             if ( val != NULL ) {
72                 enable_value = val->getStringValue();
73             }
74         } else if ( cname == "input" ) {
75             SGPropertyNode *prop = child->getChild( "prop" );
76             if ( prop != NULL ) {
77                 input_prop = fgGetNode( prop->getStringValue(), true );
78             }
79             prop = child->getChild( "scale" );
80             if ( prop != NULL ) {
81                 y_scale = prop->getDoubleValue();
82             }
83         } else if ( cname == "reference" ) {
84             SGPropertyNode *prop = child->getChild( "prop" );
85             if ( prop != NULL ) {
86                 r_n_prop = fgGetNode( prop->getStringValue(), true );
87             } else {
88                 prop = child->getChild( "value" );
89                 if ( prop != NULL ) {
90                     r_n = prop->getDoubleValue();
91                 }
92             }
93             prop = child->getChild( "scale" );
94             if ( prop != NULL ) {
95                 r_scale = prop->getDoubleValue();
96             }
97         } else if ( cname == "output" ) {
98             int i = 0;
99             SGPropertyNode *prop;
100             while ( (prop = child->getChild("prop", i)) != NULL ) {
101                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
102                 output_list.push_back( tmp );
103                 i++;
104             }
105         } else if ( cname == "config" ) {
106             SGPropertyNode *prop;
107
108             prop = child->getChild( "Kp" );
109             if ( prop != NULL ) {
110                 Kp = prop->getDoubleValue();
111             }
112
113             prop = child->getChild( "beta" );
114             if ( prop != NULL ) {
115                 beta = prop->getDoubleValue();
116             }
117
118             prop = child->getChild( "alpha" );
119             if ( prop != NULL ) {
120                 alpha = prop->getDoubleValue();
121             }
122
123             prop = child->getChild( "gamma" );
124             if ( prop != NULL ) {
125                 gamma = prop->getDoubleValue();
126             }
127
128             prop = child->getChild( "Ti" );
129             if ( prop != NULL ) {
130                 Ti = prop->getDoubleValue();
131             }
132
133             prop = child->getChild( "Td" );
134             if ( prop != NULL ) {
135                 Td = prop->getDoubleValue();
136             }
137
138             prop = child->getChild( "u_min" );
139             if ( prop != NULL ) {
140                 u_min = prop->getDoubleValue();
141             }
142
143             prop = child->getChild( "u_max" );
144             if ( prop != NULL ) {
145                 u_max = prop->getDoubleValue();
146             }
147         } else {
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 );
151             }
152         }
153     }   
154 }
155
156
157 /*
158  * Roy Vegard Ovesen:
159  *
160  * Ok! Here is the PID controller algorithm that I would like to see
161  * implemented:
162  *
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) ]
165  *
166  *   u_n = u_n-1 + delta_u_n
167  *
168  * where:
169  *
170  * delta_u : The incremental output
171  * Kp      : Proportional gain
172  * ep      : Proportional error with reference weighing
173  *           ep = beta * r - y
174  *           where:
175  *           beta : Weighing factor
176  *           r    : Reference (setpoint)
177  *           y    : Process value, measured
178  * e       : Error
179  *           e = r - y
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)
185  *           where:
186  *           Tf : Filter time
187  *           Tf = alpha * Td , where alpha usually is set to 0.1
188  *           ed : Unfiltered derivate error with reference weighing
189  *             ed = gamma * r - y
190  *             where:
191  *             gamma : Weighing factor
192  * 
193  * u       : absolute output
194  * 
195  * Index n means the n'th value.
196  * 
197  * 
198  * Inputs:
199  * enabled ,
200  * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
201  * Kp , Ti , Td , Ts (is the sampling time available?)
202  * u_min , u_max
203  * 
204  * Output:
205  * u_n
206  */
207
208 void FGPIDController::update( double dt ) {
209     double ep_n;            // proportional error with reference weighing
210     double e_n;             // error
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)
217
218     if ( Ts <= 0.0 ) {
219         // do nothing if time step is not positive (i.e. no time has
220         // elapsed)
221         return;
222     }
223
224     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
225         if ( !enabled ) {
226             // first time being enabled, seed u_n with current
227             // property tree value
228             u_n = output_list[0]->getDoubleValue();
229             // and clip
230             if ( u_n < u_min ) { u_n = u_min; }
231             if ( u_n > u_max ) { u_n = u_max; }
232             u_n_1 = u_n;
233         }
234         enabled = true;
235     } else {
236         enabled = false;
237     }
238
239     if ( enabled && Ts > 0.0) {
240         if ( debug ) cout << "Updating " << name << endl;
241
242         double y_n = 0.0;
243         if ( input_prop != NULL ) {
244             y_n = input_prop->getDoubleValue() * y_scale;
245         }
246
247         double r_n = 0.0;
248         if ( r_n_prop != NULL ) {
249             r_n = r_n_prop->getDoubleValue() * r_scale;
250         } else {
251             r_n = r_n_value;
252         }
253                       
254         if ( debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
255
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;
260
261         // Calculates error:
262         e_n = r_n - y_n;
263         if ( debug ) cout << " e_n = " << e_n;
264
265         // Calculates derivate error:
266         ed_n = gamma * r_n - y_n;
267         if ( debug ) cout << " ed_n = " << ed_n;
268
269         if ( Td > 0.0 ) {
270             // Calculates filter time:
271             Tf = alpha * Td;
272             if ( debug ) cout << " Tf = " << Tf;
273
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;
278         } else {
279             edf_n = ed_n;
280         }
281
282         // Calculates the incremental output:
283         if ( Ti > 0.0 ) {
284             delta_u_n = Kp * ( (ep_n - ep_n_1)
285                                + ((Ts/Ti) * e_n)
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)) );
290         }
291
292         if ( debug ) {
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))
297                  << endl;
298         }
299
300         // Integrator anti-windup logic:
301         if ( delta_u_n > (u_max - u_n_1) ) {
302             delta_u_n = 0;
303             if ( debug ) cout << " max saturation " << endl;
304         } else if ( delta_u_n < (u_min - u_n_1) ) {
305             delta_u_n = 0;
306             if ( debug ) cout << " min saturation " << endl;
307         }
308
309         // Calculates absolute output:
310         u_n = u_n_1 + delta_u_n;
311         if ( debug ) cout << "  output = " << u_n << endl;
312
313         // Updates indexed values;
314         u_n_1   = u_n;
315         ep_n_1  = ep_n;
316         edf_n_2 = edf_n_1;
317         edf_n_1 = edf_n;
318
319         unsigned int i;
320         for ( i = 0; i < output_list.size(); ++i ) {
321             output_list[i]->setDoubleValue( u_n );
322         }
323     } else if ( !enabled ) {
324         ep_n  = 0.0;
325         edf_n = 0.0;
326         // Updates indexed values;
327         u_n_1   = u_n;
328         ep_n_1  = ep_n;
329         edf_n_2 = edf_n_1;
330         edf_n_1 = edf_n;
331     }
332 }
333
334
335 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
336     proportional( false ),
337     Kp( 0.0 ),
338     offset_prop( NULL ),
339     offset_value( 0.0 ),
340     integral( false ),
341     Ki( 0.0 ),
342     int_sum( 0.0 ),
343     clamp( false ),
344     debug( false ),
345     y_n( 0.0 ),
346     r_n( 0.0 ),
347     y_scale( 1.0 ),
348     r_scale ( 1.0 ),
349     u_min( 0.0 ),
350     u_max( 0.0 )
351 {
352     int i;
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" ) {
358             name = cval;
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 );
367             } else {
368                 // cout << "no prop child" << endl;
369             }
370             SGPropertyNode *val = child->getChild( "value" );
371             if ( val != NULL ) {
372                 enable_value = val->getStringValue();
373             }
374         } else if ( cname == "input" ) {
375             SGPropertyNode *prop = child->getChild( "prop" );
376             if ( prop != NULL ) {
377                 input_prop = fgGetNode( prop->getStringValue(), true );
378             }
379             prop = child->getChild( "scale" );
380             if ( prop != NULL ) {
381                 y_scale = prop->getDoubleValue();
382             }
383         } else if ( cname == "reference" ) {
384             SGPropertyNode *prop = child->getChild( "prop" );
385             if ( prop != NULL ) {
386                 r_n_prop = fgGetNode( prop->getStringValue(), true );
387             } else {
388                 prop = child->getChild( "value" );
389                 if ( prop != NULL ) {
390                     r_n = prop->getDoubleValue();
391                 }
392             }
393             prop = child->getChild( "scale" );
394             if ( prop != NULL ) {
395                 r_scale = prop->getDoubleValue();
396             }
397         } else if ( cname == "output" ) {
398             int i = 0;
399             SGPropertyNode *prop;
400             while ( (prop = child->getChild("prop", i)) != NULL ) {
401                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
402                 output_list.push_back( tmp );
403                 i++;
404             }
405         } else if ( cname == "config" ) {
406             SGPropertyNode *prop;
407
408             prop = child->getChild( "Kp" );
409             if ( prop != NULL ) {
410                 Kp = prop->getDoubleValue();
411                 proportional = true;
412             }
413
414             prop = child->getChild( "Ki" );
415             if ( prop != NULL ) {
416                 Ki = prop->getDoubleValue();
417                 integral = true;
418             }
419
420             prop = child->getChild( "u_min" );
421             if ( prop != NULL ) {
422                 u_min = prop->getDoubleValue();
423                 clamp = true;
424             }
425
426             prop = child->getChild( "u_max" );
427             if ( prop != NULL ) {
428                 u_max = prop->getDoubleValue();
429                 clamp = true;
430             }
431         } else {
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 );
435             }
436         }
437     }   
438 }
439
440
441 void FGPISimpleController::update( double dt ) {
442     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
443         if ( !enabled ) {
444             // we have just been enabled, zero out int_sum
445             int_sum = 0.0;
446         }
447         enabled = true;
448     } else {
449         enabled = false;
450     }
451
452     if ( enabled ) {
453         if ( debug ) cout << "Updating " << name << endl;
454         double input = 0.0;
455         if ( input_prop != NULL ) {
456             input = input_prop->getDoubleValue() * y_scale;
457         }
458
459         double r_n = 0.0;
460         if ( r_n_prop != NULL ) {
461             r_n = r_n_prop->getDoubleValue() * r_scale;
462         } else {
463             r_n = r_n_value;
464         }
465                       
466         double error = r_n - input;
467         if ( debug ) cout << "input = " << input
468                           << " reference = " << r_n
469                           << " error = " << error
470                           << endl;
471
472         double prop_comp = 0.0;
473         double offset = 0.0;
474         if ( offset_prop != NULL ) {
475             offset = offset_prop->getDoubleValue();
476             if ( debug ) cout << "offset = " << offset << endl;
477         } else {
478             offset = offset_value;
479         }
480
481         if ( proportional ) {
482             prop_comp = error * Kp + offset;
483         }
484
485         if ( integral ) {
486             int_sum += error * Ki * dt;
487         } else {
488             int_sum = 0.0;
489         }
490
491         if ( debug ) cout << "prop_comp = " << prop_comp
492                           << " int_sum = " << int_sum << endl;
493
494         double output = prop_comp + int_sum;
495
496         if ( clamp ) {
497             if ( output < u_min ) {
498                 output = u_min;
499             }
500             if ( output > u_max ) {
501                 output = u_max;
502             }
503         }
504         if ( debug ) cout << "output = " << output << endl;
505
506         unsigned int i;
507         for ( i = 0; i < output_list.size(); ++i ) {
508             output_list[i]->setDoubleValue( output );
509         }
510     }
511 }
512
513
514 FGPredictor::FGPredictor ( SGPropertyNode *node ):
515     last_value ( 999999999.9 ),
516     average ( 0.0 ),
517     seconds( 0.0 ),
518     filter_gain( 0.0 ),
519     debug( false ),
520     ivalue( 0.0 )
521 {
522     int i;
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" ) {
528             name = cval;
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 );
540         }
541     }   
542 }
543
544 void FGPredictor::update( double dt ) {
545     /*
546        Simple moving average filter converts input value to predicted value "seconds".
547
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
555
556     */
557
558     if ( input_prop != NULL ) {
559         ivalue = input_prop->getDoubleValue();
560         // no sense if there isn't an input :-)
561         enabled = true;
562     } else {
563         enabled = false;
564     }
565
566     if ( enabled ) {
567
568         // first time initialize average
569         if (last_value >= 999999999.0) {
570            last_value = ivalue;
571         }
572
573         if ( dt > 0.0 ) {
574             double current = (ivalue - last_value)/dt; // calculate current error change (per second)
575             if ( dt < 1.0 ) {
576                 average = (1.0 - dt) * average + current * dt;
577             } else {
578                 average = current;
579             }
580
581             // calculate output with filter gain adjustment
582             double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
583
584             unsigned int i;
585             for ( i = 0; i < output_list.size(); ++i ) {
586                 output_list[i]->setDoubleValue( output );
587             }
588         }
589         last_value = ivalue;
590     }
591 }
592
593
594 FGXMLAutopilot::FGXMLAutopilot() {
595 }
596
597
598 FGXMLAutopilot::~FGXMLAutopilot() {
599 }
600
601  
602 void FGXMLAutopilot::init() {
603     config_props = fgGetNode( "/autopilot/new-config", true );
604
605     SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
606
607     if ( path_n ) {
608         SGPath config( globals->get_fg_root() );
609         config.append( path_n->getStringValue() );
610
611         SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
612                 << config.str() );
613         try {
614             readProperties( config.str(), config_props );
615
616             if ( ! build() ) {
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,
622                         " details.");
623                 exit(-1);
624             }        
625         } catch (const sg_exception& exc) {
626             SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
627                     << config.str() );
628         }
629
630     } else {
631         SG_LOG( SG_ALL, SG_WARN,
632                 "No autopilot configuration specified for this model!");
633     }
634 }
635
636
637 void FGXMLAutopilot::reinit() {
638     components.clear();
639     init();
640     build();
641 }
642
643
644 void FGXMLAutopilot::bind() {
645 }
646
647 void FGXMLAutopilot::unbind() {
648 }
649
650 bool FGXMLAutopilot::build() {
651     SGPropertyNode *node;
652     int i;
653
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 );
668         } else {
669             SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
670                     << name );
671             return false;
672         }
673     }
674
675     return true;
676 }
677
678
679 /*
680  * Update helper values
681  */
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 );
689
690     static double average = 0.0; // average/filtered prediction
691     static double v_last = 0.0;  // last velocity
692
693     double v = vel->getDoubleValue();
694     double a = 0.0;
695     if ( dt > 0.0 ) {
696         a = (v - v_last) / dt;
697
698         if ( dt < 1.0 ) {
699             average = (1.0 - dt) * average + dt * a;
700         } else {
701             average = a;
702         }
703
704         lookahead5->setDoubleValue( v + average * 5.0 );
705         lookahead10->setDoubleValue( v + average * 10.0 );
706         v_last = v;
707     }
708
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",
715                      true );
716     static SGPropertyNode *ind_bug_error
717         = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
718
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 );
723
724     // Calculate heading bug error normalized to +/- 180.0 (based on
725     // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
726     // compass.)
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 );
731
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 );
736
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 );
746
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 );
751
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 );
759
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 );
764
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 );
769
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 );
775
776     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );  
777 }
778
779
780 /*
781  * Update the list of autopilot components
782  */
783
784 void FGXMLAutopilot::update( double dt ) {
785     update_helper( dt );
786
787     unsigned int i;
788     for ( i = 0; i < components.size(); ++i ) {
789         components[i]->update( dt );
790     }
791 }