]> git.mxchange.org Git - flightgear.git/blob - src/Autopilot/xmlauto.cxx
191d745a3a8cbe0c1140543be5e227422078204d
[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 = 0.0; // incremental output
205     double u_n = 0.0;       // 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         if ( !enabled ) {
216             // first time being enabled, seed u_n with current
217             // property tree value
218             u_n = output_list[0]->getDoubleValue();
219             // and clip
220             if ( u_n < u_min ) { u_n = u_min; }
221             if ( u_n > u_max ) { u_n = u_max; }
222             u_n_1 = u_n;
223         }
224         enabled = true;
225     } else {
226         enabled = false;
227     }
228
229     if ( enabled && Ts > 0.0) {
230         if ( debug ) cout << "Updating " << name << endl;
231
232         double y_n = 0.0;
233         if ( input_prop != NULL ) {
234             y_n = input_prop->getDoubleValue();
235         }
236
237         double r_n = 0.0;
238         if ( r_n_prop != NULL ) {
239             r_n = r_n_prop->getDoubleValue();
240         } else {
241             r_n = r_n_value;
242         }
243                       
244         if ( debug ) cout << "  input = " << y_n << " ref = " << r_n << endl;
245
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;
250
251         // Calculates error:
252         e_n = r_n - y_n;
253         if ( debug ) cout << " e_n = " << e_n;
254
255         // Calculates derivate error:
256         ed_n = gamma * r_n - y_n;
257         if ( debug ) cout << " ed_n = " << ed_n;
258
259         if ( Td > 0.0 ) {
260             // Calculates filter time:
261             Tf = alpha * Td;
262             if ( debug ) cout << " Tf = " << Tf;
263
264             // Filters the derivate error:
265             edf_n = edf_n_1 / (Ts/Tf + 1)
266                 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
267             if ( debug ) cout << " edf_n = " << edf_n;
268         } else {
269             edf_n = ed_n;
270         }
271
272         // Calculates the incremental output:
273         if ( Ti > 0.0 ) {
274             delta_u_n = Kp * ( (ep_n - ep_n_1)
275                                + ((Ts/Ti) * e_n)
276                                + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
277         } else if ( Ti <= 0.0 ) {
278             delta_u_n = Kp * ( (ep_n - ep_n_1)
279                                + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
280         }
281
282         if ( debug ) {
283             cout << " delta_u_n = " << delta_u_n << endl;
284             cout << "P:" << Kp * (ep_n - ep_n_1)
285                  << " I:" << Kp * ((Ts/Ti) * e_n)
286                  << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
287                  << endl;
288         }
289
290         // Integrator anti-windup logic:
291         if ( delta_u_n > (u_max - u_n_1) ) {
292             delta_u_n = 0;
293             if ( debug ) cout << " max saturation " << endl;
294         } else if ( delta_u_n < (u_min - u_n_1) ) {
295             delta_u_n = 0;
296             if ( debug ) cout << " min saturation " << endl;
297         }
298
299         // Calculates absolute output:
300         u_n = u_n_1 + delta_u_n;
301         if ( debug ) cout << "  output = " << u_n << endl;
302
303         // Updates indexed values;
304         u_n_1   = u_n;
305         ep_n_1  = ep_n;
306         edf_n_2 = edf_n_1;
307         edf_n_1 = edf_n;
308
309         unsigned int i;
310         for ( i = 0; i < output_list.size(); ++i ) {
311             output_list[i]->setDoubleValue( u_n );
312         }
313     } else if ( !enabled ) {
314         ep_n  = 0.0;
315         edf_n = 0.0;
316         // Updates indexed values;
317         u_n_1   = u_n;
318         ep_n_1  = ep_n;
319         edf_n_2 = edf_n_1;
320         edf_n_1 = edf_n;
321     }
322 }
323
324
325 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
326     proportional( false ),
327     Kp( 0.0 ),
328     offset_prop( NULL ),
329     offset_value( 0.0 ),
330     integral( false ),
331     Ki( 0.0 ),
332     int_sum( 0.0 ),
333     clamp( false ),
334     debug( false ),
335     y_n( 0.0 ),
336     r_n( 0.0 ),
337     u_min( 0.0 ),
338     u_max( 0.0 )
339 {
340     int i;
341     for ( i = 0; i < node->nChildren(); ++i ) {
342         SGPropertyNode *child = node->getChild(i);
343         string cname = child->getName();
344         string cval = child->getStringValue();
345         if ( cname == "name" ) {
346             name = cval;
347         } else if ( cname == "debug" ) {
348             debug = child->getBoolValue();
349         } else if ( cname == "enable" ) {
350             // cout << "parsing enable" << endl;
351             SGPropertyNode *prop = child->getChild( "prop" );
352             if ( prop != NULL ) {
353                 // cout << "prop = " << prop->getStringValue() << endl;
354                 enable_prop = fgGetNode( prop->getStringValue(), true );
355             } else {
356                 // cout << "no prop child" << endl;
357             }
358             SGPropertyNode *val = child->getChild( "value" );
359             if ( val != NULL ) {
360                 enable_value = val->getStringValue();
361             }
362         } else if ( cname == "input" ) {
363             SGPropertyNode *prop = child->getChild( "prop" );
364             if ( prop != NULL ) {
365                 input_prop = fgGetNode( prop->getStringValue(), true );
366             }
367         } else if ( cname == "reference" ) {
368             SGPropertyNode *prop = child->getChild( "prop" );
369             if ( prop != NULL ) {
370                 r_n_prop = fgGetNode( prop->getStringValue(), true );
371             } else {
372                 prop = child->getChild( "value" );
373                 if ( prop != NULL ) {
374                     r_n = prop->getDoubleValue();
375                 }
376             }
377         } else if ( cname == "output" ) {
378             int i = 0;
379             SGPropertyNode *prop;
380             while ( (prop = child->getChild("prop", i)) != NULL ) {
381                 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
382                 output_list.push_back( tmp );
383                 i++;
384             }
385         } else if ( cname == "config" ) {
386             SGPropertyNode *prop;
387
388             prop = child->getChild( "Kp" );
389             if ( prop != NULL ) {
390                 Kp = prop->getDoubleValue();
391                 proportional = true;
392             }
393
394             prop = child->getChild( "Ki" );
395             if ( prop != NULL ) {
396                 Ki = prop->getDoubleValue();
397                 integral = true;
398             }
399
400             prop = child->getChild( "u_min" );
401             if ( prop != NULL ) {
402                 u_min = prop->getDoubleValue();
403                 clamp = true;
404             }
405
406             prop = child->getChild( "u_max" );
407             if ( prop != NULL ) {
408                 u_max = prop->getDoubleValue();
409                 clamp = true;
410             }
411         } else {
412             SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
413             if ( name.length() ) {
414                 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
415             }
416         }
417     }   
418 }
419
420
421 void FGPISimpleController::update( double dt ) {
422     if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
423         if ( !enabled ) {
424             // we have just been enabled, zero out int_sum
425             int_sum = 0.0;
426         }
427         enabled = true;
428     } else {
429         enabled = false;
430     }
431
432     if ( enabled ) {
433         if ( debug ) cout << "Updating " << name << endl;
434         double input = 0.0;
435         if ( input_prop != NULL ) {
436             input = input_prop->getDoubleValue();
437         }
438
439         double r_n = 0.0;
440         if ( r_n_prop != NULL ) {
441             r_n = r_n_prop->getDoubleValue();
442         } else {
443             r_n = r_n_value;
444         }
445                       
446         double error = r_n - input;
447         if ( debug ) cout << "input = " << input
448                           << " reference = " << r_n
449                           << " error = " << error
450                           << endl;
451
452         double prop_comp = 0.0;
453         double offset = 0.0;
454         if ( offset_prop != NULL ) {
455             offset = offset_prop->getDoubleValue();
456             if ( debug ) cout << "offset = " << offset << endl;
457         } else {
458             offset = offset_value;
459         }
460
461         if ( proportional ) {
462             prop_comp = error * Kp + offset;
463         }
464
465         if ( integral ) {
466             int_sum += error * Ki * dt;
467         } else {
468             int_sum = 0.0;
469         }
470
471         if ( debug ) cout << "prop_comp = " << prop_comp
472                           << " int_sum = " << int_sum << endl;
473
474         double output = prop_comp + int_sum;
475
476         if ( clamp ) {
477             if ( output < u_min ) {
478                 output = u_min;
479             }
480             if ( output > u_max ) {
481                 output = u_max;
482             }
483         }
484         if ( debug ) cout << "output = " << output << endl;
485
486         unsigned int i;
487         for ( i = 0; i < output_list.size(); ++i ) {
488             output_list[i]->setDoubleValue( output );
489         }
490     }
491 }
492
493
494 FGPredictor::FGPredictor ( SGPropertyNode *node ):
495     debug( false ),
496     ivalue( 0.0 ),
497     last_value ( 999999999.9 ),
498     average ( 0.0 ),
499     seconds( 0.0 ),
500     filter_gain( 0.0 )
501 {
502     int i;
503     for ( i = 0; i < node->nChildren(); ++i ) {
504         SGPropertyNode *child = node->getChild(i);
505         string cname = child->getName();
506         string cval = child->getStringValue();
507         if ( cname == "name" ) {
508             name = cval;
509         } else if ( cname == "debug" ) {
510             debug = child->getBoolValue();
511         } else if ( cname == "input" ) {
512             input_prop = fgGetNode( child->getStringValue(), true );
513         } else if ( cname == "seconds" ) {
514             seconds = child->getDoubleValue();
515         } else if ( cname == "filter-gain" ) {
516             filter_gain = child->getDoubleValue();
517         } else if ( cname == "output" ) {
518             SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
519             output_list.push_back( tmp );
520         }
521     }   
522 }
523
524 void FGPredictor::update( double dt ) {
525     /*
526        Simple moving average filter converts input value to predicted value "seconds".
527
528        Smoothing as described by Curt Olson:
529          gain would be valid in the range of 0 - 1.0
530          1.0 would mean no filtering.
531          0.0 would mean no input.
532          0.5 would mean (1 part past value + 1 part current value) / 2
533          0.1 would mean (9 parts past value + 1 part current value) / 10
534          0.25 would mean (3 parts past value + 1 part current value) / 4
535
536     */
537
538     if ( input_prop != NULL ) {
539         ivalue = input_prop->getDoubleValue();
540         // no sense if there isn't an input :-)
541         enabled = true;
542     } else {
543         enabled = false;
544     }
545
546     if ( enabled ) {
547
548         // first time initialize average
549         if (last_value >= 999999999.0) {
550            last_value = ivalue;
551         }
552
553         if ( dt > 0.0 ) {
554             double current = (ivalue - last_value)/dt; // calculate current error change (per second)
555             if ( dt < 1.0 ) {
556                 average = (1.0 - dt) * average + current * dt;
557             } else {
558                 average = current;
559             }
560
561             // calculate output with filter gain adjustment
562             double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
563
564             unsigned int i;
565             for ( i = 0; i < output_list.size(); ++i ) {
566                 output_list[i]->setDoubleValue( output );
567             }
568         }
569         last_value = ivalue;
570     }
571 }
572
573
574 FGXMLAutopilot::FGXMLAutopilot() {
575 }
576
577
578 FGXMLAutopilot::~FGXMLAutopilot() {
579 }
580
581  
582 void FGXMLAutopilot::init() {
583     config_props = fgGetNode( "/autopilot/new-config", true );
584
585     SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
586
587     if ( path_n ) {
588         SGPath config( globals->get_fg_root() );
589         config.append( path_n->getStringValue() );
590
591         SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
592                 << config.str() );
593         try {
594             readProperties( config.str(), config_props );
595
596             if ( ! build() ) {
597                 SG_LOG( SG_ALL, SG_ALERT,
598                         "Detected an internal inconsistancy in the autopilot");
599                 SG_LOG( SG_ALL, SG_ALERT,
600                         " configuration.  See earlier errors for" );
601                 SG_LOG( SG_ALL, SG_ALERT,
602                         " details.");
603                 exit(-1);
604             }        
605         } catch (const sg_exception& exc) {
606             SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
607                     << config.str() );
608         }
609
610     } else {
611         SG_LOG( SG_ALL, SG_WARN,
612                 "No autopilot configuration specified for this model!");
613     }
614 }
615
616
617 void FGXMLAutopilot::reinit() {
618     components.clear();
619     init();
620     build();
621 }
622
623
624 void FGXMLAutopilot::bind() {
625 }
626
627 void FGXMLAutopilot::unbind() {
628 }
629
630 bool FGXMLAutopilot::build() {
631     SGPropertyNode *node;
632     int i;
633
634     int count = config_props->nChildren();
635     for ( i = 0; i < count; ++i ) {
636         node = config_props->getChild(i);
637         string name = node->getName();
638         // cout << name << endl;
639         if ( name == "pid-controller" ) {
640             FGXMLAutoComponent *c = new FGPIDController( node );
641             components.push_back( c );
642         } else if ( name == "pi-simple-controller" ) {
643             FGXMLAutoComponent *c = new FGPISimpleController( node );
644             components.push_back( c );
645         } else if ( name == "predict-simple" ) {
646             FGXMLAutoComponent *c = new FGPredictor( node );
647             components.push_back( c );
648         } else {
649             SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: " 
650                     << name );
651             return false;
652         }
653     }
654
655     return true;
656 }
657
658
659 /*
660  * Update helper values
661  */
662 static void update_helper( double dt ) {
663     // Estimate speed in 5,10 seconds
664     static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
665     static SGPropertyNode *lookahead5
666         = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
667     static SGPropertyNode *lookahead10
668         = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
669
670     static double average = 0.0; // average/filtered prediction
671     static double v_last = 0.0;  // last velocity
672
673     double v = vel->getDoubleValue();
674     double a = 0.0;
675     if ( dt > 0.0 ) {
676         a = (v - v_last) / dt;
677
678         if ( dt < 1.0 ) {
679             average = (1.0 - dt) * average + dt * a;
680         } else {
681             average = a;
682         }
683
684         lookahead5->setDoubleValue( v + average * 5.0 );
685         lookahead10->setDoubleValue( v + average * 10.0 );
686         v_last = v;
687     }
688
689     // Calculate heading bug error normalized to +/- 180.0 (based on
690     // DG indicated heading)
691     static SGPropertyNode *bug
692         = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
693     static SGPropertyNode *ind_hdg
694         = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
695                      true );
696     static SGPropertyNode *ind_bug_error
697         = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
698
699     double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
700     if ( diff < -180.0 ) { diff += 360.0; }
701     if ( diff > 180.0 ) { diff -= 360.0; }
702     ind_bug_error->setDoubleValue( diff );
703
704     // Calculate heading bug error normalized to +/- 180.0 (based on
705     // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
706     // compass.)
707     static SGPropertyNode *mag_hdg
708         = fgGetNode( "/orientation/heading-magnetic-deg", true );
709     static SGPropertyNode *fdm_bug_error
710         = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
711
712     diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
713     if ( diff < -180.0 ) { diff += 360.0; }
714     if ( diff > 180.0 ) { diff -= 360.0; }
715     fdm_bug_error->setDoubleValue( diff );
716
717     // Calculate true heading error normalized to +/- 180.0
718     static SGPropertyNode *target_true
719         = fgGetNode( "/autopilot/settings/true-heading-deg", true );
720     static SGPropertyNode *true_hdg
721         = fgGetNode( "/orientation/heading-deg", true );
722     static SGPropertyNode *true_track
723         = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
724     static SGPropertyNode *true_error
725         = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
726
727     diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
728     if ( diff < -180.0 ) { diff += 360.0; }
729     if ( diff > 180.0 ) { diff -= 360.0; }
730     true_error->setDoubleValue( diff );
731
732     // Calculate nav1 target heading error normalized to +/- 180.0
733     static SGPropertyNode *target_nav1
734         = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
735     static SGPropertyNode *true_nav1
736         = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
737     static SGPropertyNode *true_track_nav1
738         = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
739
740     diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
741     if ( diff < -180.0 ) { diff += 360.0; }
742     if ( diff > 180.0 ) { diff -= 360.0; }
743     true_nav1->setDoubleValue( diff );
744
745     diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
746     if ( diff < -180.0 ) { diff += 360.0; }
747     if ( diff > 180.0 ) { diff -= 360.0; }
748     true_track_nav1->setDoubleValue( diff );
749
750     // Calculate vertical speed in fpm
751     static SGPropertyNode *vs_fps
752         = fgGetNode( "/velocities/vertical-speed-fps", true );
753     static SGPropertyNode *vs_fpm
754         = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
755
756     vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );  
757 }
758
759
760 /*
761  * Update the list of autopilot components
762  */
763
764 void FGXMLAutopilot::update( double dt ) {
765     update_helper( dt );
766
767     unsigned int i;
768     for ( i = 0; i < components.size(); ++i ) {
769         components[i]->update( dt );
770     }
771 }