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., 675 Mass Ave, Cambridge, MA 02139, USA.
24 #include <simgear/structure/exception.hxx>
25 #include <simgear/misc/sg_path.hxx>
26 #include <simgear/sg_inlines.h>
28 #include <Main/fg_props.hxx>
29 #include <Main/globals.hxx>
30 #include <Main/util.hxx>
32 #include "xmlauto.hxx"
35 FGPIDController::FGPIDController( SGPropertyNode *node ):
55 for ( i = 0; i < node->nChildren(); ++i ) {
56 SGPropertyNode *child = node->getChild(i);
57 string cname = child->getName();
58 string cval = child->getStringValue();
59 if ( cname == "name" ) {
61 } else if ( cname == "debug" ) {
62 debug = child->getBoolValue();
63 } else if ( cname == "enable" ) {
64 // cout << "parsing enable" << endl;
65 SGPropertyNode *prop = child->getChild( "prop" );
67 // cout << "prop = " << prop->getStringValue() << endl;
68 enable_prop = fgGetNode( prop->getStringValue(), true );
70 // cout << "no prop child" << endl;
72 SGPropertyNode *val = child->getChild( "value" );
74 enable_value = val->getStringValue();
76 } else if ( cname == "input" ) {
77 SGPropertyNode *prop = child->getChild( "prop" );
79 input_prop = fgGetNode( prop->getStringValue(), true );
81 prop = child->getChild( "scale" );
83 y_scale = prop->getDoubleValue();
85 } else if ( cname == "reference" ) {
86 SGPropertyNode *prop = child->getChild( "prop" );
88 r_n_prop = fgGetNode( prop->getStringValue(), true );
90 prop = child->getChild( "value" );
92 r_n = prop->getDoubleValue();
95 prop = child->getChild( "scale" );
97 r_scale = prop->getDoubleValue();
99 } else if ( cname == "output" ) {
101 SGPropertyNode *prop;
102 while ( (prop = child->getChild("prop", i)) != NULL ) {
103 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
104 output_list.push_back( tmp );
107 } else if ( cname == "config" ) {
108 SGPropertyNode *prop;
110 prop = child->getChild( "Kp" );
111 if ( prop != NULL ) {
112 Kp = prop->getDoubleValue();
115 prop = child->getChild( "beta" );
116 if ( prop != NULL ) {
117 beta = prop->getDoubleValue();
120 prop = child->getChild( "alpha" );
121 if ( prop != NULL ) {
122 alpha = prop->getDoubleValue();
125 prop = child->getChild( "gamma" );
126 if ( prop != NULL ) {
127 gamma = prop->getDoubleValue();
130 prop = child->getChild( "Ti" );
131 if ( prop != NULL ) {
132 Ti = prop->getDoubleValue();
135 prop = child->getChild( "Td" );
136 if ( prop != NULL ) {
137 Td = prop->getDoubleValue();
140 prop = child->getChild( "u_min" );
141 if ( prop != NULL ) {
142 u_min = prop->getDoubleValue();
145 prop = child->getChild( "u_max" );
146 if ( prop != NULL ) {
147 u_max = prop->getDoubleValue();
150 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
151 if ( name.length() ) {
152 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
162 * Ok! Here is the PID controller algorithm that I would like to see
165 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
166 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
168 * u_n = u_n-1 + delta_u_n
172 * delta_u : The incremental output
173 * Kp : Proportional gain
174 * ep : Proportional error with reference weighing
177 * beta : Weighing factor
178 * r : Reference (setpoint)
179 * y : Process value, measured
182 * Ts : Sampling interval
183 * Ti : Integrator time
184 * Td : Derivator time
185 * edf : Derivate error with reference weighing and filtering
186 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
189 * Tf = alpha * Td , where alpha usually is set to 0.1
190 * ed : Unfiltered derivate error with reference weighing
193 * gamma : Weighing factor
195 * u : absolute output
197 * Index n means the n'th value.
202 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
203 * Kp , Ti , Td , Ts (is the sampling time available?)
210 void FGPIDController::update( double dt ) {
211 double ep_n; // proportional error with reference weighing
213 double ed_n; // derivative error
214 double edf_n; // derivative error filter
215 double Tf; // filter time
216 double delta_u_n = 0.0; // incremental output
217 double u_n = 0.0; // absolute output
218 double Ts = dt; // Sampling interval (sec)
221 // do nothing if time step is not positive (i.e. no time has
226 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
228 // first time being enabled, seed u_n with current
229 // property tree value
230 u_n = output_list[0]->getDoubleValue();
232 if ( u_n < u_min ) { u_n = u_min; }
233 if ( u_n > u_max ) { u_n = u_max; }
241 if ( enabled && Ts > 0.0) {
242 if ( debug ) cout << "Updating " << name << endl;
245 if ( input_prop != NULL ) {
246 y_n = input_prop->getDoubleValue() * y_scale;
250 if ( r_n_prop != NULL ) {
251 r_n = r_n_prop->getDoubleValue() * r_scale;
256 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
258 // Calculates proportional error:
259 ep_n = beta * r_n - y_n;
260 if ( debug ) cout << " ep_n = " << ep_n;
261 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
265 if ( debug ) cout << " e_n = " << e_n;
267 // Calculates derivate error:
268 ed_n = gamma * r_n - y_n;
269 if ( debug ) cout << " ed_n = " << ed_n;
272 // Calculates filter time:
274 if ( debug ) cout << " Tf = " << Tf;
276 // Filters the derivate error:
277 edf_n = edf_n_1 / (Ts/Tf + 1)
278 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
279 if ( debug ) cout << " edf_n = " << edf_n;
284 // Calculates the incremental output:
286 delta_u_n = Kp * ( (ep_n - ep_n_1)
288 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
289 } else if ( Ti <= 0.0 ) {
290 delta_u_n = Kp * ( (ep_n - ep_n_1)
291 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
295 cout << " delta_u_n = " << delta_u_n << endl;
296 cout << "P:" << Kp * (ep_n - ep_n_1)
297 << " I:" << Kp * ((Ts/Ti) * e_n)
298 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
302 // Integrator anti-windup logic:
303 if ( delta_u_n > (u_max - u_n_1) ) {
305 if ( debug ) cout << " max saturation " << endl;
306 } else if ( delta_u_n < (u_min - u_n_1) ) {
308 if ( debug ) cout << " min saturation " << endl;
311 // Calculates absolute output:
312 u_n = u_n_1 + delta_u_n;
313 if ( debug ) cout << " output = " << u_n << endl;
315 // Updates indexed values;
322 for ( i = 0; i < output_list.size(); ++i ) {
323 output_list[i]->setDoubleValue( u_n );
325 } else if ( !enabled ) {
328 // Updates indexed values;
337 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
338 proportional( false ),
355 for ( i = 0; i < node->nChildren(); ++i ) {
356 SGPropertyNode *child = node->getChild(i);
357 string cname = child->getName();
358 string cval = child->getStringValue();
359 if ( cname == "name" ) {
361 } else if ( cname == "debug" ) {
362 debug = child->getBoolValue();
363 } else if ( cname == "enable" ) {
364 // cout << "parsing enable" << endl;
365 SGPropertyNode *prop = child->getChild( "prop" );
366 if ( prop != NULL ) {
367 // cout << "prop = " << prop->getStringValue() << endl;
368 enable_prop = fgGetNode( prop->getStringValue(), true );
370 // cout << "no prop child" << endl;
372 SGPropertyNode *val = child->getChild( "value" );
374 enable_value = val->getStringValue();
376 } else if ( cname == "input" ) {
377 SGPropertyNode *prop = child->getChild( "prop" );
378 if ( prop != NULL ) {
379 input_prop = fgGetNode( prop->getStringValue(), true );
381 prop = child->getChild( "scale" );
382 if ( prop != NULL ) {
383 y_scale = prop->getDoubleValue();
385 } else if ( cname == "reference" ) {
386 SGPropertyNode *prop = child->getChild( "prop" );
387 if ( prop != NULL ) {
388 r_n_prop = fgGetNode( prop->getStringValue(), true );
390 prop = child->getChild( "value" );
391 if ( prop != NULL ) {
392 r_n = prop->getDoubleValue();
395 prop = child->getChild( "scale" );
396 if ( prop != NULL ) {
397 r_scale = prop->getDoubleValue();
399 } else if ( cname == "output" ) {
401 SGPropertyNode *prop;
402 while ( (prop = child->getChild("prop", i)) != NULL ) {
403 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
404 output_list.push_back( tmp );
407 } else if ( cname == "config" ) {
408 SGPropertyNode *prop;
410 prop = child->getChild( "Kp" );
411 if ( prop != NULL ) {
412 Kp = prop->getDoubleValue();
416 prop = child->getChild( "Ki" );
417 if ( prop != NULL ) {
418 Ki = prop->getDoubleValue();
422 prop = child->getChild( "u_min" );
423 if ( prop != NULL ) {
424 u_min = prop->getDoubleValue();
428 prop = child->getChild( "u_max" );
429 if ( prop != NULL ) {
430 u_max = prop->getDoubleValue();
434 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
435 if ( name.length() ) {
436 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
443 void FGPISimpleController::update( double dt ) {
444 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
446 // we have just been enabled, zero out int_sum
455 if ( debug ) cout << "Updating " << name << endl;
457 if ( input_prop != NULL ) {
458 input = input_prop->getDoubleValue() * y_scale;
462 if ( r_n_prop != NULL ) {
463 r_n = r_n_prop->getDoubleValue() * r_scale;
468 double error = r_n - input;
469 if ( debug ) cout << "input = " << input
470 << " reference = " << r_n
471 << " error = " << error
474 double prop_comp = 0.0;
476 if ( offset_prop != NULL ) {
477 offset = offset_prop->getDoubleValue();
478 if ( debug ) cout << "offset = " << offset << endl;
480 offset = offset_value;
483 if ( proportional ) {
484 prop_comp = error * Kp + offset;
488 int_sum += error * Ki * dt;
493 if ( debug ) cout << "prop_comp = " << prop_comp
494 << " int_sum = " << int_sum << endl;
496 double output = prop_comp + int_sum;
499 if ( output < u_min ) {
502 if ( output > u_max ) {
506 if ( debug ) cout << "output = " << output << endl;
509 for ( i = 0; i < output_list.size(); ++i ) {
510 output_list[i]->setDoubleValue( output );
516 FGPredictor::FGPredictor ( SGPropertyNode *node ):
517 last_value ( 999999999.9 ),
525 for ( i = 0; i < node->nChildren(); ++i ) {
526 SGPropertyNode *child = node->getChild(i);
527 string cname = child->getName();
528 string cval = child->getStringValue();
529 if ( cname == "name" ) {
531 } else if ( cname == "debug" ) {
532 debug = child->getBoolValue();
533 } else if ( cname == "input" ) {
534 input_prop = fgGetNode( child->getStringValue(), true );
535 } else if ( cname == "seconds" ) {
536 seconds = child->getDoubleValue();
537 } else if ( cname == "filter-gain" ) {
538 filter_gain = child->getDoubleValue();
539 } else if ( cname == "output" ) {
540 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
541 output_list.push_back( tmp );
546 void FGPredictor::update( double dt ) {
548 Simple moving average filter converts input value to predicted value "seconds".
550 Smoothing as described by Curt Olson:
551 gain would be valid in the range of 0 - 1.0
552 1.0 would mean no filtering.
553 0.0 would mean no input.
554 0.5 would mean (1 part past value + 1 part current value) / 2
555 0.1 would mean (9 parts past value + 1 part current value) / 10
556 0.25 would mean (3 parts past value + 1 part current value) / 4
560 if ( input_prop != NULL ) {
561 ivalue = input_prop->getDoubleValue();
562 // no sense if there isn't an input :-)
570 // first time initialize average
571 if (last_value >= 999999999.0) {
576 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
578 average = (1.0 - dt) * average + current * dt;
583 // calculate output with filter gain adjustment
584 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
587 for ( i = 0; i < output_list.size(); ++i ) {
588 output_list[i]->setDoubleValue( output );
596 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node)
601 for ( i = 0; i < node->nChildren(); ++i ) {
602 SGPropertyNode *child = node->getChild(i);
603 string cname = child->getName();
604 string cval = child->getStringValue();
605 if ( cname == "name" ) {
607 } else if ( cname == "debug" ) {
608 debug = child->getBoolValue();
609 } else if ( cname == "type" ) {
611 } else if ( cname == "input" ) {
612 input_prop = fgGetNode( child->getStringValue(), true );
613 } else if ( cname == "filter-time" ) {
614 Tf = child->getDoubleValue();
615 } else if ( cname == "samples" ) {
616 samples = child->getIntValue();
617 } else if ( cname == "max-rate-of-change" ) {
618 rateOfChange = child->getDoubleValue();
619 } else if ( cname == "output" ) {
620 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
621 output_list.push_back( tmp );
625 output.resize(2, 0.0);
626 input.resize(samples, 0.0);
629 void FGDigitalFilter::update(double dt)
631 if ( input_prop != NULL ) {
632 input.push_front(input_prop->getDoubleValue());
633 input.resize(samples, 0.0);
634 // no sense if there isn't an input :-)
640 if ( enabled && dt > 0.0 ) {
644 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
648 if (filterType == "exponential")
650 double alpha = 1 / ((Tf/dt) + 1);
651 output.push_front(alpha * input[0] +
652 (1 - alpha) * output[0]);
654 for ( i = 0; i < output_list.size(); ++i ) {
655 output_list[i]->setDoubleValue( output[0] );
659 else if (filterType == "double-exponential")
661 double alpha = 1 / ((Tf/dt) + 1);
662 output.push_front(alpha * alpha * input[0] +
663 2 * (1 - alpha) * output[0] -
664 (1 - alpha) * (1 - alpha) * output[1]);
666 for ( i = 0; i < output_list.size(); ++i ) {
667 output_list[i]->setDoubleValue( output[0] );
671 else if (filterType == "moving-average")
673 output.push_front(output[0] +
674 (input[0] - input.back()) / samples);
676 for ( i = 0; i < output_list.size(); ++i ) {
677 output_list[i]->setDoubleValue( output[0] );
681 else if (filterType == "noise-spike")
683 double maxChange = rateOfChange * dt;
685 if ((output[0] - input[0]) > maxChange)
687 output.push_front(output[0] - maxChange);
689 else if ((output[0] - input[0]) < -maxChange)
691 output.push_front(output[0] + maxChange);
693 else if (fabs(input[0] - output[0]) <= maxChange)
695 output.push_front(input[0]);
699 for ( i = 0; i < output_list.size(); ++i ) {
700 output_list[i]->setDoubleValue( output[0] );
706 cout << "input:" << input[0]
707 << "\toutput:" << output[0] << endl;
713 FGXMLAutopilot::FGXMLAutopilot() {
717 FGXMLAutopilot::~FGXMLAutopilot() {
721 void FGXMLAutopilot::init() {
722 config_props = fgGetNode( "/autopilot/new-config", true );
724 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
727 SGPath config( globals->get_fg_root() );
728 config.append( path_n->getStringValue() );
730 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
733 readProperties( config.str(), config_props );
736 SG_LOG( SG_ALL, SG_ALERT,
737 "Detected an internal inconsistancy in the autopilot");
738 SG_LOG( SG_ALL, SG_ALERT,
739 " configuration. See earlier errors for" );
740 SG_LOG( SG_ALL, SG_ALERT,
744 } catch (const sg_exception& exc) {
745 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
750 SG_LOG( SG_ALL, SG_WARN,
751 "No autopilot configuration specified for this model!");
756 void FGXMLAutopilot::reinit() {
763 void FGXMLAutopilot::bind() {
766 void FGXMLAutopilot::unbind() {
769 bool FGXMLAutopilot::build() {
770 SGPropertyNode *node;
773 int count = config_props->nChildren();
774 for ( i = 0; i < count; ++i ) {
775 node = config_props->getChild(i);
776 string name = node->getName();
777 // cout << name << endl;
778 if ( name == "pid-controller" ) {
779 FGXMLAutoComponent *c = new FGPIDController( node );
780 components.push_back( c );
781 } else if ( name == "pi-simple-controller" ) {
782 FGXMLAutoComponent *c = new FGPISimpleController( node );
783 components.push_back( c );
784 } else if ( name == "predict-simple" ) {
785 FGXMLAutoComponent *c = new FGPredictor( node );
786 components.push_back( c );
787 } else if ( name == "filter" ) {
788 FGXMLAutoComponent *c = new FGDigitalFilter( node );
789 components.push_back( c );
791 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
802 * Update helper values
804 static void update_helper( double dt ) {
805 // Estimate speed in 5,10 seconds
806 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
807 static SGPropertyNode *lookahead5
808 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
809 static SGPropertyNode *lookahead10
810 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
812 static double average = 0.0; // average/filtered prediction
813 static double v_last = 0.0; // last velocity
815 double v = vel->getDoubleValue();
818 a = (v - v_last) / dt;
821 average = (1.0 - dt) * average + dt * a;
826 lookahead5->setDoubleValue( v + average * 5.0 );
827 lookahead10->setDoubleValue( v + average * 10.0 );
831 // Calculate heading bug error normalized to +/- 180.0 (based on
832 // DG indicated heading)
833 static SGPropertyNode *bug
834 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
835 static SGPropertyNode *ind_hdg
836 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
838 static SGPropertyNode *ind_bug_error
839 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
841 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
842 if ( diff < -180.0 ) { diff += 360.0; }
843 if ( diff > 180.0 ) { diff -= 360.0; }
844 ind_bug_error->setDoubleValue( diff );
846 // Calculate heading bug error normalized to +/- 180.0 (based on
847 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
849 static SGPropertyNode *mag_hdg
850 = fgGetNode( "/orientation/heading-magnetic-deg", true );
851 static SGPropertyNode *fdm_bug_error
852 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
854 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
855 if ( diff < -180.0 ) { diff += 360.0; }
856 if ( diff > 180.0 ) { diff -= 360.0; }
857 fdm_bug_error->setDoubleValue( diff );
859 // Calculate true heading error normalized to +/- 180.0
860 static SGPropertyNode *target_true
861 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
862 static SGPropertyNode *true_hdg
863 = fgGetNode( "/orientation/heading-deg", true );
864 static SGPropertyNode *true_track
865 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
866 static SGPropertyNode *true_error
867 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
869 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
870 if ( diff < -180.0 ) { diff += 360.0; }
871 if ( diff > 180.0 ) { diff -= 360.0; }
872 true_error->setDoubleValue( diff );
874 // Calculate nav1 target heading error normalized to +/- 180.0
875 static SGPropertyNode *target_nav1
876 = fgGetNode( "/radios/nav[0]/radials/target-auto-hdg-deg", true );
877 static SGPropertyNode *true_nav1
878 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
879 static SGPropertyNode *true_track_nav1
880 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
882 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
883 if ( diff < -180.0 ) { diff += 360.0; }
884 if ( diff > 180.0 ) { diff -= 360.0; }
885 true_nav1->setDoubleValue( diff );
887 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
888 if ( diff < -180.0 ) { diff += 360.0; }
889 if ( diff > 180.0 ) { diff -= 360.0; }
890 true_track_nav1->setDoubleValue( diff );
892 // Calculate nav1 selected course error normalized to +/- 180.0
893 // (based on DG indicated heading)
894 static SGPropertyNode *nav1_course_error
895 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
896 static SGPropertyNode *nav1_selected_course
897 = fgGetNode( "/radios/nav[0]/radials/selected-deg", true );
899 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
900 // if ( diff < -180.0 ) { diff += 360.0; }
901 // if ( diff > 180.0 ) { diff -= 360.0; }
902 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
903 nav1_course_error->setDoubleValue( diff );
905 // Calculate vertical speed in fpm
906 static SGPropertyNode *vs_fps
907 = fgGetNode( "/velocities/vertical-speed-fps", true );
908 static SGPropertyNode *vs_fpm
909 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
911 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
914 // Calculate static port pressure rate in [inhg/s].
915 // Used to determine vertical speed.
916 static SGPropertyNode *static_pressure
917 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
918 static SGPropertyNode *pressure_rate
919 = fgGetNode( "/autopilot/internal/pressure-rate", true );
921 static double last_static_pressure = 0.0;
924 double current_static_pressure = static_pressure->getDoubleValue();
926 double current_pressure_rate =
927 ( current_static_pressure - last_static_pressure ) / dt;
929 pressure_rate->setDoubleValue(current_pressure_rate);
931 last_static_pressure = current_static_pressure;
938 * Update the list of autopilot components
941 void FGXMLAutopilot::update( double dt ) {
945 for ( i = 0; i < components.size(); ++i ) {
946 components[i]->update( dt );