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 - http://www.flightgear.org/~curt
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., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
27 #include <simgear/structure/exception.hxx>
28 #include <simgear/misc/sg_path.hxx>
29 #include <simgear/sg_inlines.h>
31 #include <Main/fg_props.hxx>
32 #include <Main/globals.hxx>
33 #include <Main/util.hxx>
35 #include "xmlauto.hxx"
38 FGPIDController::FGPIDController( SGPropertyNode *node ):
61 for ( i = 0; i < node->nChildren(); ++i ) {
62 SGPropertyNode *child = node->getChild(i);
63 string cname = child->getName();
64 string cval = child->getStringValue();
65 if ( cname == "name" ) {
67 } else if ( cname == "debug" ) {
68 debug = child->getBoolValue();
69 } else if ( cname == "enable" ) {
70 // cout << "parsing enable" << endl;
71 SGPropertyNode *prop = child->getChild( "prop" );
73 // cout << "prop = " << prop->getStringValue() << endl;
74 enable_prop = fgGetNode( prop->getStringValue(), true );
76 // cout << "no prop child" << endl;
78 SGPropertyNode *val = child->getChild( "value" );
80 enable_value = val->getStringValue();
82 SGPropertyNode *pass = child->getChild( "honor-passive" );
84 honor_passive = pass->getBoolValue();
86 } else if ( cname == "input" ) {
87 SGPropertyNode *prop = child->getChild( "prop" );
89 input_prop = fgGetNode( prop->getStringValue(), true );
91 prop = child->getChild( "scale" );
93 y_scale = prop->getDoubleValue();
95 prop = child->getChild( "offset" );
97 y_offset = prop->getDoubleValue();
99 } else if ( cname == "reference" ) {
100 SGPropertyNode *prop = child->getChild( "prop" );
101 if ( prop != NULL ) {
102 r_n_prop = fgGetNode( prop->getStringValue(), true );
104 prop = child->getChild( "value" );
105 if ( prop != NULL ) {
106 r_n = prop->getDoubleValue();
109 prop = child->getChild( "scale" );
110 if ( prop != NULL ) {
111 r_scale = prop->getDoubleValue();
113 prop = child->getChild( "offset" );
114 if ( prop != NULL ) {
115 r_offset = prop->getDoubleValue();
117 } else if ( cname == "output" ) {
119 SGPropertyNode *prop;
120 while ( (prop = child->getChild("prop", i)) != NULL ) {
121 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
122 output_list.push_back( tmp );
125 } else if ( cname == "config" ) {
126 SGPropertyNode *prop;
128 prop = child->getChild( "Ts" );
129 if ( prop != NULL ) {
130 desiredTs = prop->getDoubleValue();
133 prop = child->getChild( "Kp" );
134 if ( prop != NULL ) {
135 Kp = prop->getDoubleValue();
138 prop = child->getChild( "beta" );
139 if ( prop != NULL ) {
140 beta = prop->getDoubleValue();
143 prop = child->getChild( "alpha" );
144 if ( prop != NULL ) {
145 alpha = prop->getDoubleValue();
148 prop = child->getChild( "gamma" );
149 if ( prop != NULL ) {
150 gamma = prop->getDoubleValue();
153 prop = child->getChild( "Ti" );
154 if ( prop != NULL ) {
155 Ti = prop->getDoubleValue();
158 prop = child->getChild( "Td" );
159 if ( prop != NULL ) {
160 Td = prop->getDoubleValue();
163 prop = child->getChild( "u_min" );
164 if ( prop != NULL ) {
165 u_min = prop->getDoubleValue();
168 prop = child->getChild( "u_max" );
169 if ( prop != NULL ) {
170 u_max = prop->getDoubleValue();
173 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
174 if ( name.length() ) {
175 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
185 * Ok! Here is the PID controller algorithm that I would like to see
188 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
189 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
191 * u_n = u_n-1 + delta_u_n
195 * delta_u : The incremental output
196 * Kp : Proportional gain
197 * ep : Proportional error with reference weighing
200 * beta : Weighing factor
201 * r : Reference (setpoint)
202 * y : Process value, measured
205 * Ts : Sampling interval
206 * Ti : Integrator time
207 * Td : Derivator time
208 * edf : Derivate error with reference weighing and filtering
209 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
212 * Tf = alpha * Td , where alpha usually is set to 0.1
213 * ed : Unfiltered derivate error with reference weighing
216 * gamma : Weighing factor
218 * u : absolute output
220 * Index n means the n'th value.
225 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
226 * Kp , Ti , Td , Ts (is the sampling time available?)
233 void FGPIDController::update( double dt ) {
234 double ep_n; // proportional error with reference weighing
236 double ed_n; // derivative error
237 double edf_n; // derivative error filter
238 double Tf; // filter time
239 double delta_u_n = 0.0; // incremental output
240 double u_n = 0.0; // absolute output
241 double Ts; // sampling interval (sec)
244 if ( elapsedTime <= desiredTs ) {
245 // do nothing if time step is not positive (i.e. no time has
252 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
254 // first time being enabled, seed u_n with current
255 // property tree value
256 u_n = output_list[0]->getDoubleValue();
258 if ( u_n < u_min ) { u_n = u_min; }
259 if ( u_n > u_max ) { u_n = u_max; }
267 if ( enabled && Ts > 0.0) {
268 if ( debug ) cout << "Updating " << name
269 << " Ts " << Ts << endl;
272 if ( input_prop != NULL ) {
273 y_n = input_prop->getDoubleValue() * y_scale + y_offset;
277 if ( r_n_prop != NULL ) {
278 r_n = r_n_prop->getDoubleValue() * r_scale + r_offset;
283 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
285 // Calculates proportional error:
286 ep_n = beta * r_n - y_n;
287 if ( debug ) cout << " ep_n = " << ep_n;
288 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
292 if ( debug ) cout << " e_n = " << e_n;
294 // Calculates derivate error:
295 ed_n = gamma * r_n - y_n;
296 if ( debug ) cout << " ed_n = " << ed_n;
299 // Calculates filter time:
301 if ( debug ) cout << " Tf = " << Tf;
303 // Filters the derivate error:
304 edf_n = edf_n_1 / (Ts/Tf + 1)
305 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
306 if ( debug ) cout << " edf_n = " << edf_n;
311 // Calculates the incremental output:
313 delta_u_n = Kp * ( (ep_n - ep_n_1)
315 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
319 cout << " delta_u_n = " << delta_u_n << endl;
320 cout << "P:" << Kp * (ep_n - ep_n_1)
321 << " I:" << Kp * ((Ts/Ti) * e_n)
322 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
326 // Integrator anti-windup logic:
327 if ( delta_u_n > (u_max - u_n_1) ) {
328 delta_u_n = u_max - u_n_1;
329 if ( debug ) cout << " max saturation " << endl;
330 } else if ( delta_u_n < (u_min - u_n_1) ) {
331 delta_u_n = u_min - u_n_1;
332 if ( debug ) cout << " min saturation " << endl;
335 // Calculates absolute output:
336 u_n = u_n_1 + delta_u_n;
337 if ( debug ) cout << " output = " << u_n << endl;
339 // Updates indexed values;
345 // passive_ignore == true means that we go through all the
346 // motions, but drive the outputs. This is analogous to
347 // running the autopilot with the "servos" off. This is
348 // helpful for things like flight directors which position
349 // their vbars from the autopilot computations.
350 if ( passive_mode->getBoolValue() && honor_passive ) {
354 for ( i = 0; i < output_list.size(); ++i ) {
355 output_list[i]->setDoubleValue( u_n );
358 } else if ( !enabled ) {
361 // Updates indexed values;
370 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
371 proportional( false ),
388 for ( i = 0; i < node->nChildren(); ++i ) {
389 SGPropertyNode *child = node->getChild(i);
390 string cname = child->getName();
391 string cval = child->getStringValue();
392 if ( cname == "name" ) {
394 } else if ( cname == "debug" ) {
395 debug = child->getBoolValue();
396 } else if ( cname == "enable" ) {
397 // cout << "parsing enable" << endl;
398 SGPropertyNode *prop = child->getChild( "prop" );
399 if ( prop != NULL ) {
400 // cout << "prop = " << prop->getStringValue() << endl;
401 enable_prop = fgGetNode( prop->getStringValue(), true );
403 // cout << "no prop child" << endl;
405 SGPropertyNode *val = child->getChild( "value" );
407 enable_value = val->getStringValue();
409 } else if ( cname == "input" ) {
410 SGPropertyNode *prop = child->getChild( "prop" );
411 if ( prop != NULL ) {
412 input_prop = fgGetNode( prop->getStringValue(), true );
414 prop = child->getChild( "scale" );
415 if ( prop != NULL ) {
416 y_scale = prop->getDoubleValue();
418 } else if ( cname == "reference" ) {
419 SGPropertyNode *prop = child->getChild( "prop" );
420 if ( prop != NULL ) {
421 r_n_prop = fgGetNode( prop->getStringValue(), true );
423 prop = child->getChild( "value" );
424 if ( prop != NULL ) {
425 r_n = prop->getDoubleValue();
428 prop = child->getChild( "scale" );
429 if ( prop != NULL ) {
430 r_scale = prop->getDoubleValue();
432 } else if ( cname == "output" ) {
434 SGPropertyNode *prop;
435 while ( (prop = child->getChild("prop", i)) != NULL ) {
436 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
437 output_list.push_back( tmp );
440 } else if ( cname == "config" ) {
441 SGPropertyNode *prop;
443 prop = child->getChild( "Kp" );
444 if ( prop != NULL ) {
445 Kp = prop->getDoubleValue();
449 prop = child->getChild( "Ki" );
450 if ( prop != NULL ) {
451 Ki = prop->getDoubleValue();
455 prop = child->getChild( "u_min" );
456 if ( prop != NULL ) {
457 u_min = prop->getDoubleValue();
461 prop = child->getChild( "u_max" );
462 if ( prop != NULL ) {
463 u_max = prop->getDoubleValue();
467 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
468 if ( name.length() ) {
469 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
476 void FGPISimpleController::update( double dt ) {
477 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
479 // we have just been enabled, zero out int_sum
488 if ( debug ) cout << "Updating " << name << endl;
490 if ( input_prop != NULL ) {
491 input = input_prop->getDoubleValue() * y_scale;
495 if ( r_n_prop != NULL ) {
496 r_n = r_n_prop->getDoubleValue() * r_scale;
501 double error = r_n - input;
502 if ( debug ) cout << "input = " << input
503 << " reference = " << r_n
504 << " error = " << error
507 double prop_comp = 0.0;
509 if ( offset_prop != NULL ) {
510 offset = offset_prop->getDoubleValue();
511 if ( debug ) cout << "offset = " << offset << endl;
513 offset = offset_value;
516 if ( proportional ) {
517 prop_comp = error * Kp + offset;
521 int_sum += error * Ki * dt;
526 if ( debug ) cout << "prop_comp = " << prop_comp
527 << " int_sum = " << int_sum << endl;
529 double output = prop_comp + int_sum;
532 if ( output < u_min ) {
535 if ( output > u_max ) {
539 if ( debug ) cout << "output = " << output << endl;
542 for ( i = 0; i < output_list.size(); ++i ) {
543 output_list[i]->setDoubleValue( output );
549 FGPredictor::FGPredictor ( SGPropertyNode *node ):
550 last_value ( 999999999.9 ),
558 for ( i = 0; i < node->nChildren(); ++i ) {
559 SGPropertyNode *child = node->getChild(i);
560 string cname = child->getName();
561 string cval = child->getStringValue();
562 if ( cname == "name" ) {
564 } else if ( cname == "debug" ) {
565 debug = child->getBoolValue();
566 } else if ( cname == "input" ) {
567 input_prop = fgGetNode( child->getStringValue(), true );
568 } else if ( cname == "seconds" ) {
569 seconds = child->getDoubleValue();
570 } else if ( cname == "filter-gain" ) {
571 filter_gain = child->getDoubleValue();
572 } else if ( cname == "output" ) {
573 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
574 output_list.push_back( tmp );
579 void FGPredictor::update( double dt ) {
581 Simple moving average filter converts input value to predicted value "seconds".
583 Smoothing as described by Curt Olson:
584 gain would be valid in the range of 0 - 1.0
585 1.0 would mean no filtering.
586 0.0 would mean no input.
587 0.5 would mean (1 part past value + 1 part current value) / 2
588 0.1 would mean (9 parts past value + 1 part current value) / 10
589 0.25 would mean (3 parts past value + 1 part current value) / 4
593 if ( input_prop != NULL ) {
594 ivalue = input_prop->getDoubleValue();
595 // no sense if there isn't an input :-)
603 // first time initialize average
604 if (last_value >= 999999999.0) {
609 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
611 average = (1.0 - dt) * average + current * dt;
616 // calculate output with filter gain adjustment
617 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
620 for ( i = 0; i < output_list.size(); ++i ) {
621 output_list[i]->setDoubleValue( output );
629 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node)
634 for ( i = 0; i < node->nChildren(); ++i ) {
635 SGPropertyNode *child = node->getChild(i);
636 string cname = child->getName();
637 string cval = child->getStringValue();
638 if ( cname == "name" ) {
640 } else if ( cname == "debug" ) {
641 debug = child->getBoolValue();
642 } else if ( cname == "type" ) {
643 if ( cval == "exponential" ) {
644 filterType = exponential;
645 } else if (cval == "double-exponential") {
646 filterType = doubleExponential;
647 } else if (cval == "moving-average") {
648 filterType = movingAverage;
649 } else if (cval == "noise-spike") {
650 filterType = noiseSpike;
652 } else if ( cname == "input" ) {
653 input_prop = fgGetNode( child->getStringValue(), true );
654 } else if ( cname == "filter-time" ) {
655 Tf = child->getDoubleValue();
656 } else if ( cname == "samples" ) {
657 samples = child->getIntValue();
658 } else if ( cname == "max-rate-of-change" ) {
659 rateOfChange = child->getDoubleValue();
660 } else if ( cname == "output" ) {
661 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
662 output_list.push_back( tmp );
666 output.resize(2, 0.0);
667 input.resize(samples + 1, 0.0);
670 void FGDigitalFilter::update(double dt)
672 if ( input_prop != NULL ) {
673 input.push_front(input_prop->getDoubleValue());
674 input.resize(samples + 1, 0.0);
675 // no sense if there isn't an input :-)
681 if ( enabled && dt > 0.0 ) {
685 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
689 if (filterType == exponential)
691 double alpha = 1 / ((Tf/dt) + 1);
692 output.push_front(alpha * input[0] +
693 (1 - alpha) * output[0]);
695 for ( i = 0; i < output_list.size(); ++i ) {
696 output_list[i]->setDoubleValue( output[0] );
700 else if (filterType == doubleExponential)
702 double alpha = 1 / ((Tf/dt) + 1);
703 output.push_front(alpha * alpha * input[0] +
704 2 * (1 - alpha) * output[0] -
705 (1 - alpha) * (1 - alpha) * output[1]);
707 for ( i = 0; i < output_list.size(); ++i ) {
708 output_list[i]->setDoubleValue( output[0] );
712 else if (filterType == movingAverage)
714 output.push_front(output[0] +
715 (input[0] - input.back()) / samples);
717 for ( i = 0; i < output_list.size(); ++i ) {
718 output_list[i]->setDoubleValue( output[0] );
722 else if (filterType == noiseSpike)
724 double maxChange = rateOfChange * dt;
726 if ((output[0] - input[0]) > maxChange)
728 output.push_front(output[0] - maxChange);
730 else if ((output[0] - input[0]) < -maxChange)
732 output.push_front(output[0] + maxChange);
734 else if (fabs(input[0] - output[0]) <= maxChange)
736 output.push_front(input[0]);
740 for ( i = 0; i < output_list.size(); ++i ) {
741 output_list[i]->setDoubleValue( output[0] );
747 cout << "input:" << input[0]
748 << "\toutput:" << output[0] << endl;
754 FGXMLAutopilot::FGXMLAutopilot() {
758 FGXMLAutopilot::~FGXMLAutopilot() {
762 void FGXMLAutopilot::init() {
763 config_props = fgGetNode( "/autopilot/new-config", true );
765 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
768 SGPath config( globals->get_fg_root() );
769 config.append( path_n->getStringValue() );
771 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
774 readProperties( config.str(), config_props );
777 SG_LOG( SG_ALL, SG_ALERT,
778 "Detected an internal inconsistency in the autopilot");
779 SG_LOG( SG_ALL, SG_ALERT,
780 " configuration. See earlier errors for" );
781 SG_LOG( SG_ALL, SG_ALERT,
785 } catch (const sg_exception& exc) {
786 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
791 SG_LOG( SG_ALL, SG_WARN,
792 "No autopilot configuration specified for this model!");
797 void FGXMLAutopilot::reinit() {
804 void FGXMLAutopilot::bind() {
807 void FGXMLAutopilot::unbind() {
810 bool FGXMLAutopilot::build() {
811 SGPropertyNode *node;
814 int count = config_props->nChildren();
815 for ( i = 0; i < count; ++i ) {
816 node = config_props->getChild(i);
817 string name = node->getName();
818 // cout << name << endl;
819 if ( name == "pid-controller" ) {
820 FGXMLAutoComponent *c = new FGPIDController( node );
821 components.push_back( c );
822 } else if ( name == "pi-simple-controller" ) {
823 FGXMLAutoComponent *c = new FGPISimpleController( node );
824 components.push_back( c );
825 } else if ( name == "predict-simple" ) {
826 FGXMLAutoComponent *c = new FGPredictor( node );
827 components.push_back( c );
828 } else if ( name == "filter" ) {
829 FGXMLAutoComponent *c = new FGDigitalFilter( node );
830 components.push_back( c );
832 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
843 * Update helper values
845 static void update_helper( double dt ) {
846 // Estimate speed in 5,10 seconds
847 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
848 static SGPropertyNode *lookahead5
849 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
850 static SGPropertyNode *lookahead10
851 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
853 static double average = 0.0; // average/filtered prediction
854 static double v_last = 0.0; // last velocity
856 double v = vel->getDoubleValue();
859 a = (v - v_last) / dt;
862 average = (1.0 - dt) * average + dt * a;
867 lookahead5->setDoubleValue( v + average * 5.0 );
868 lookahead10->setDoubleValue( v + average * 10.0 );
872 // Calculate heading bug error normalized to +/- 180.0 (based on
873 // DG indicated heading)
874 static SGPropertyNode *bug
875 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
876 static SGPropertyNode *ind_hdg
877 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
879 static SGPropertyNode *ind_bug_error
880 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
882 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
883 if ( diff < -180.0 ) { diff += 360.0; }
884 if ( diff > 180.0 ) { diff -= 360.0; }
885 ind_bug_error->setDoubleValue( diff );
887 // Calculate heading bug error normalized to +/- 180.0 (based on
888 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
890 static SGPropertyNode *mag_hdg
891 = fgGetNode( "/orientation/heading-magnetic-deg", true );
892 static SGPropertyNode *fdm_bug_error
893 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
895 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
896 if ( diff < -180.0 ) { diff += 360.0; }
897 if ( diff > 180.0 ) { diff -= 360.0; }
898 fdm_bug_error->setDoubleValue( diff );
900 // Calculate true heading error normalized to +/- 180.0
901 static SGPropertyNode *target_true
902 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
903 static SGPropertyNode *true_hdg
904 = fgGetNode( "/orientation/heading-deg", true );
905 static SGPropertyNode *true_track
906 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
907 static SGPropertyNode *true_error
908 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
910 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
911 if ( diff < -180.0 ) { diff += 360.0; }
912 if ( diff > 180.0 ) { diff -= 360.0; }
913 true_error->setDoubleValue( diff );
915 // Calculate nav1 target heading error normalized to +/- 180.0
916 static SGPropertyNode *target_nav1
917 = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
918 static SGPropertyNode *true_nav1
919 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
920 static SGPropertyNode *true_track_nav1
921 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
923 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
924 if ( diff < -180.0 ) { diff += 360.0; }
925 if ( diff > 180.0 ) { diff -= 360.0; }
926 true_nav1->setDoubleValue( diff );
928 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
929 if ( diff < -180.0 ) { diff += 360.0; }
930 if ( diff > 180.0 ) { diff -= 360.0; }
931 true_track_nav1->setDoubleValue( diff );
933 // Calculate nav1 selected course error normalized to +/- 180.0
934 // (based on DG indicated heading)
935 static SGPropertyNode *nav1_course_error
936 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
937 static SGPropertyNode *nav1_selected_course
938 = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
940 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
941 // if ( diff < -180.0 ) { diff += 360.0; }
942 // if ( diff > 180.0 ) { diff -= 360.0; }
943 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
944 nav1_course_error->setDoubleValue( diff );
946 // Calculate vertical speed in fpm
947 static SGPropertyNode *vs_fps
948 = fgGetNode( "/velocities/vertical-speed-fps", true );
949 static SGPropertyNode *vs_fpm
950 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
952 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
955 // Calculate static port pressure rate in [inhg/s].
956 // Used to determine vertical speed.
957 static SGPropertyNode *static_pressure
958 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
959 static SGPropertyNode *pressure_rate
960 = fgGetNode( "/autopilot/internal/pressure-rate", true );
962 static double last_static_pressure = 0.0;
965 double current_static_pressure = static_pressure->getDoubleValue();
967 double current_pressure_rate =
968 ( current_static_pressure - last_static_pressure ) / dt;
970 pressure_rate->setDoubleValue(current_pressure_rate);
972 last_static_pressure = current_static_pressure;
979 * Update the list of autopilot components
982 void FGXMLAutopilot::update( double dt ) {
986 for ( i = 0; i < components.size(); ++i ) {
987 components[i]->update( dt );