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 } else if ( cname == "input" ) {
83 SGPropertyNode *prop = child->getChild( "prop" );
85 input_prop = fgGetNode( prop->getStringValue(), true );
87 prop = child->getChild( "scale" );
89 y_scale = prop->getDoubleValue();
91 prop = child->getChild( "offset" );
93 y_offset = prop->getDoubleValue();
95 } else if ( cname == "reference" ) {
96 SGPropertyNode *prop = child->getChild( "prop" );
98 r_n_prop = fgGetNode( prop->getStringValue(), true );
100 prop = child->getChild( "value" );
101 if ( prop != NULL ) {
102 r_n = prop->getDoubleValue();
105 prop = child->getChild( "scale" );
106 if ( prop != NULL ) {
107 r_scale = prop->getDoubleValue();
109 prop = child->getChild( "offset" );
110 if ( prop != NULL ) {
111 r_offset = prop->getDoubleValue();
113 } else if ( cname == "output" ) {
115 SGPropertyNode *prop;
116 while ( (prop = child->getChild("prop", i)) != NULL ) {
117 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
118 output_list.push_back( tmp );
121 } else if ( cname == "config" ) {
122 SGPropertyNode *prop;
124 prop = child->getChild( "Ts" );
125 if ( prop != NULL ) {
126 desiredTs = prop->getDoubleValue();
129 prop = child->getChild( "Kp" );
130 if ( prop != NULL ) {
131 Kp = prop->getDoubleValue();
134 prop = child->getChild( "beta" );
135 if ( prop != NULL ) {
136 beta = prop->getDoubleValue();
139 prop = child->getChild( "alpha" );
140 if ( prop != NULL ) {
141 alpha = prop->getDoubleValue();
144 prop = child->getChild( "gamma" );
145 if ( prop != NULL ) {
146 gamma = prop->getDoubleValue();
149 prop = child->getChild( "Ti" );
150 if ( prop != NULL ) {
151 Ti = prop->getDoubleValue();
154 prop = child->getChild( "Td" );
155 if ( prop != NULL ) {
156 Td = prop->getDoubleValue();
159 prop = child->getChild( "u_min" );
160 if ( prop != NULL ) {
161 u_min = prop->getDoubleValue();
164 prop = child->getChild( "u_max" );
165 if ( prop != NULL ) {
166 u_max = prop->getDoubleValue();
169 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
170 if ( name.length() ) {
171 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
181 * Ok! Here is the PID controller algorithm that I would like to see
184 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
185 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
187 * u_n = u_n-1 + delta_u_n
191 * delta_u : The incremental output
192 * Kp : Proportional gain
193 * ep : Proportional error with reference weighing
196 * beta : Weighing factor
197 * r : Reference (setpoint)
198 * y : Process value, measured
201 * Ts : Sampling interval
202 * Ti : Integrator time
203 * Td : Derivator time
204 * edf : Derivate error with reference weighing and filtering
205 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
208 * Tf = alpha * Td , where alpha usually is set to 0.1
209 * ed : Unfiltered derivate error with reference weighing
212 * gamma : Weighing factor
214 * u : absolute output
216 * Index n means the n'th value.
221 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
222 * Kp , Ti , Td , Ts (is the sampling time available?)
229 void FGPIDController::update( double dt ) {
230 double ep_n; // proportional error with reference weighing
232 double ed_n; // derivative error
233 double edf_n; // derivative error filter
234 double Tf; // filter time
235 double delta_u_n = 0.0; // incremental output
236 double u_n = 0.0; // absolute output
237 double Ts; // sampling interval (sec)
240 if ( elapsedTime <= desiredTs ) {
241 // do nothing if time step is not positive (i.e. no time has
248 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
250 // first time being enabled, seed u_n with current
251 // property tree value
252 u_n = output_list[0]->getDoubleValue();
254 if ( u_n < u_min ) { u_n = u_min; }
255 if ( u_n > u_max ) { u_n = u_max; }
263 if ( enabled && Ts > 0.0) {
264 if ( debug ) cout << "Updating " << name
265 << " Ts " << Ts << endl;
268 if ( input_prop != NULL ) {
269 y_n = input_prop->getDoubleValue() * y_scale + y_offset;
273 if ( r_n_prop != NULL ) {
274 r_n = r_n_prop->getDoubleValue() * r_scale + r_offset;
279 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
281 // Calculates proportional error:
282 ep_n = beta * r_n - y_n;
283 if ( debug ) cout << " ep_n = " << ep_n;
284 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
288 if ( debug ) cout << " e_n = " << e_n;
290 // Calculates derivate error:
291 ed_n = gamma * r_n - y_n;
292 if ( debug ) cout << " ed_n = " << ed_n;
295 // Calculates filter time:
297 if ( debug ) cout << " Tf = " << Tf;
299 // Filters the derivate error:
300 edf_n = edf_n_1 / (Ts/Tf + 1)
301 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
302 if ( debug ) cout << " edf_n = " << edf_n;
307 // Calculates the incremental output:
309 delta_u_n = Kp * ( (ep_n - ep_n_1)
311 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
315 cout << " delta_u_n = " << delta_u_n << endl;
316 cout << "P:" << Kp * (ep_n - ep_n_1)
317 << " I:" << Kp * ((Ts/Ti) * e_n)
318 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
322 // Integrator anti-windup logic:
323 if ( delta_u_n > (u_max - u_n_1) ) {
324 delta_u_n = u_max - u_n_1;
325 if ( debug ) cout << " max saturation " << endl;
326 } else if ( delta_u_n < (u_min - u_n_1) ) {
327 delta_u_n = u_min - u_n_1;
328 if ( debug ) cout << " min saturation " << endl;
331 // Calculates absolute output:
332 u_n = u_n_1 + delta_u_n;
333 if ( debug ) cout << " output = " << u_n << endl;
335 // Updates indexed values;
342 for ( i = 0; i < output_list.size(); ++i ) {
343 output_list[i]->setDoubleValue( u_n );
345 } else if ( !enabled ) {
348 // Updates indexed values;
357 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
358 proportional( false ),
375 for ( i = 0; i < node->nChildren(); ++i ) {
376 SGPropertyNode *child = node->getChild(i);
377 string cname = child->getName();
378 string cval = child->getStringValue();
379 if ( cname == "name" ) {
381 } else if ( cname == "debug" ) {
382 debug = child->getBoolValue();
383 } else if ( cname == "enable" ) {
384 // cout << "parsing enable" << endl;
385 SGPropertyNode *prop = child->getChild( "prop" );
386 if ( prop != NULL ) {
387 // cout << "prop = " << prop->getStringValue() << endl;
388 enable_prop = fgGetNode( prop->getStringValue(), true );
390 // cout << "no prop child" << endl;
392 SGPropertyNode *val = child->getChild( "value" );
394 enable_value = val->getStringValue();
396 } else if ( cname == "input" ) {
397 SGPropertyNode *prop = child->getChild( "prop" );
398 if ( prop != NULL ) {
399 input_prop = fgGetNode( prop->getStringValue(), true );
401 prop = child->getChild( "scale" );
402 if ( prop != NULL ) {
403 y_scale = prop->getDoubleValue();
405 } else if ( cname == "reference" ) {
406 SGPropertyNode *prop = child->getChild( "prop" );
407 if ( prop != NULL ) {
408 r_n_prop = fgGetNode( prop->getStringValue(), true );
410 prop = child->getChild( "value" );
411 if ( prop != NULL ) {
412 r_n = prop->getDoubleValue();
415 prop = child->getChild( "scale" );
416 if ( prop != NULL ) {
417 r_scale = prop->getDoubleValue();
419 } else if ( cname == "output" ) {
421 SGPropertyNode *prop;
422 while ( (prop = child->getChild("prop", i)) != NULL ) {
423 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
424 output_list.push_back( tmp );
427 } else if ( cname == "config" ) {
428 SGPropertyNode *prop;
430 prop = child->getChild( "Kp" );
431 if ( prop != NULL ) {
432 Kp = prop->getDoubleValue();
436 prop = child->getChild( "Ki" );
437 if ( prop != NULL ) {
438 Ki = prop->getDoubleValue();
442 prop = child->getChild( "u_min" );
443 if ( prop != NULL ) {
444 u_min = prop->getDoubleValue();
448 prop = child->getChild( "u_max" );
449 if ( prop != NULL ) {
450 u_max = prop->getDoubleValue();
454 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
455 if ( name.length() ) {
456 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
463 void FGPISimpleController::update( double dt ) {
464 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
466 // we have just been enabled, zero out int_sum
475 if ( debug ) cout << "Updating " << name << endl;
477 if ( input_prop != NULL ) {
478 input = input_prop->getDoubleValue() * y_scale;
482 if ( r_n_prop != NULL ) {
483 r_n = r_n_prop->getDoubleValue() * r_scale;
488 double error = r_n - input;
489 if ( debug ) cout << "input = " << input
490 << " reference = " << r_n
491 << " error = " << error
494 double prop_comp = 0.0;
496 if ( offset_prop != NULL ) {
497 offset = offset_prop->getDoubleValue();
498 if ( debug ) cout << "offset = " << offset << endl;
500 offset = offset_value;
503 if ( proportional ) {
504 prop_comp = error * Kp + offset;
508 int_sum += error * Ki * dt;
513 if ( debug ) cout << "prop_comp = " << prop_comp
514 << " int_sum = " << int_sum << endl;
516 double output = prop_comp + int_sum;
519 if ( output < u_min ) {
522 if ( output > u_max ) {
526 if ( debug ) cout << "output = " << output << endl;
529 for ( i = 0; i < output_list.size(); ++i ) {
530 output_list[i]->setDoubleValue( output );
536 FGPredictor::FGPredictor ( SGPropertyNode *node ):
537 last_value ( 999999999.9 ),
545 for ( i = 0; i < node->nChildren(); ++i ) {
546 SGPropertyNode *child = node->getChild(i);
547 string cname = child->getName();
548 string cval = child->getStringValue();
549 if ( cname == "name" ) {
551 } else if ( cname == "debug" ) {
552 debug = child->getBoolValue();
553 } else if ( cname == "input" ) {
554 input_prop = fgGetNode( child->getStringValue(), true );
555 } else if ( cname == "seconds" ) {
556 seconds = child->getDoubleValue();
557 } else if ( cname == "filter-gain" ) {
558 filter_gain = child->getDoubleValue();
559 } else if ( cname == "output" ) {
560 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
561 output_list.push_back( tmp );
566 void FGPredictor::update( double dt ) {
568 Simple moving average filter converts input value to predicted value "seconds".
570 Smoothing as described by Curt Olson:
571 gain would be valid in the range of 0 - 1.0
572 1.0 would mean no filtering.
573 0.0 would mean no input.
574 0.5 would mean (1 part past value + 1 part current value) / 2
575 0.1 would mean (9 parts past value + 1 part current value) / 10
576 0.25 would mean (3 parts past value + 1 part current value) / 4
580 if ( input_prop != NULL ) {
581 ivalue = input_prop->getDoubleValue();
582 // no sense if there isn't an input :-)
590 // first time initialize average
591 if (last_value >= 999999999.0) {
596 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
598 average = (1.0 - dt) * average + current * dt;
603 // calculate output with filter gain adjustment
604 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
607 for ( i = 0; i < output_list.size(); ++i ) {
608 output_list[i]->setDoubleValue( output );
616 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node)
621 for ( i = 0; i < node->nChildren(); ++i ) {
622 SGPropertyNode *child = node->getChild(i);
623 string cname = child->getName();
624 string cval = child->getStringValue();
625 if ( cname == "name" ) {
627 } else if ( cname == "debug" ) {
628 debug = child->getBoolValue();
629 } else if ( cname == "type" ) {
630 if ( cval == "exponential" ) {
631 filterType = exponential;
632 } else if (cval == "double-exponential") {
633 filterType = doubleExponential;
634 } else if (cval == "moving-average") {
635 filterType = movingAverage;
636 } else if (cval == "noise-spike") {
637 filterType = noiseSpike;
639 } else if ( cname == "input" ) {
640 input_prop = fgGetNode( child->getStringValue(), true );
641 } else if ( cname == "filter-time" ) {
642 Tf = child->getDoubleValue();
643 } else if ( cname == "samples" ) {
644 samples = child->getIntValue();
645 } else if ( cname == "max-rate-of-change" ) {
646 rateOfChange = child->getDoubleValue();
647 } else if ( cname == "output" ) {
648 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
649 output_list.push_back( tmp );
653 output.resize(2, 0.0);
654 input.resize(samples + 1, 0.0);
657 void FGDigitalFilter::update(double dt)
659 if ( input_prop != NULL ) {
660 input.push_front(input_prop->getDoubleValue());
661 input.resize(samples + 1, 0.0);
662 // no sense if there isn't an input :-)
668 if ( enabled && dt > 0.0 ) {
672 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
676 if (filterType == exponential)
678 double alpha = 1 / ((Tf/dt) + 1);
679 output.push_front(alpha * input[0] +
680 (1 - alpha) * output[0]);
682 for ( i = 0; i < output_list.size(); ++i ) {
683 output_list[i]->setDoubleValue( output[0] );
687 else if (filterType == doubleExponential)
689 double alpha = 1 / ((Tf/dt) + 1);
690 output.push_front(alpha * alpha * input[0] +
691 2 * (1 - alpha) * output[0] -
692 (1 - alpha) * (1 - alpha) * output[1]);
694 for ( i = 0; i < output_list.size(); ++i ) {
695 output_list[i]->setDoubleValue( output[0] );
699 else if (filterType == movingAverage)
701 output.push_front(output[0] +
702 (input[0] - input.back()) / samples);
704 for ( i = 0; i < output_list.size(); ++i ) {
705 output_list[i]->setDoubleValue( output[0] );
709 else if (filterType == noiseSpike)
711 double maxChange = rateOfChange * dt;
713 if ((output[0] - input[0]) > maxChange)
715 output.push_front(output[0] - maxChange);
717 else if ((output[0] - input[0]) < -maxChange)
719 output.push_front(output[0] + maxChange);
721 else if (fabs(input[0] - output[0]) <= maxChange)
723 output.push_front(input[0]);
727 for ( i = 0; i < output_list.size(); ++i ) {
728 output_list[i]->setDoubleValue( output[0] );
734 cout << "input:" << input[0]
735 << "\toutput:" << output[0] << endl;
741 FGXMLAutopilot::FGXMLAutopilot() {
745 FGXMLAutopilot::~FGXMLAutopilot() {
749 void FGXMLAutopilot::init() {
750 config_props = fgGetNode( "/autopilot/new-config", true );
752 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
755 SGPath config( globals->get_fg_root() );
756 config.append( path_n->getStringValue() );
758 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
761 readProperties( config.str(), config_props );
764 SG_LOG( SG_ALL, SG_ALERT,
765 "Detected an internal inconsistency in the autopilot");
766 SG_LOG( SG_ALL, SG_ALERT,
767 " configuration. See earlier errors for" );
768 SG_LOG( SG_ALL, SG_ALERT,
772 } catch (const sg_exception& exc) {
773 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
778 SG_LOG( SG_ALL, SG_WARN,
779 "No autopilot configuration specified for this model!");
784 void FGXMLAutopilot::reinit() {
791 void FGXMLAutopilot::bind() {
794 void FGXMLAutopilot::unbind() {
797 bool FGXMLAutopilot::build() {
798 SGPropertyNode *node;
801 int count = config_props->nChildren();
802 for ( i = 0; i < count; ++i ) {
803 node = config_props->getChild(i);
804 string name = node->getName();
805 // cout << name << endl;
806 if ( name == "pid-controller" ) {
807 FGXMLAutoComponent *c = new FGPIDController( node );
808 components.push_back( c );
809 } else if ( name == "pi-simple-controller" ) {
810 FGXMLAutoComponent *c = new FGPISimpleController( node );
811 components.push_back( c );
812 } else if ( name == "predict-simple" ) {
813 FGXMLAutoComponent *c = new FGPredictor( node );
814 components.push_back( c );
815 } else if ( name == "filter" ) {
816 FGXMLAutoComponent *c = new FGDigitalFilter( node );
817 components.push_back( c );
819 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
830 * Update helper values
832 static void update_helper( double dt ) {
833 // Estimate speed in 5,10 seconds
834 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
835 static SGPropertyNode *lookahead5
836 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
837 static SGPropertyNode *lookahead10
838 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
840 static double average = 0.0; // average/filtered prediction
841 static double v_last = 0.0; // last velocity
843 double v = vel->getDoubleValue();
846 a = (v - v_last) / dt;
849 average = (1.0 - dt) * average + dt * a;
854 lookahead5->setDoubleValue( v + average * 5.0 );
855 lookahead10->setDoubleValue( v + average * 10.0 );
859 // Calculate heading bug error normalized to +/- 180.0 (based on
860 // DG indicated heading)
861 static SGPropertyNode *bug
862 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
863 static SGPropertyNode *ind_hdg
864 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
866 static SGPropertyNode *ind_bug_error
867 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
869 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
870 if ( diff < -180.0 ) { diff += 360.0; }
871 if ( diff > 180.0 ) { diff -= 360.0; }
872 ind_bug_error->setDoubleValue( diff );
874 // Calculate heading bug error normalized to +/- 180.0 (based on
875 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
877 static SGPropertyNode *mag_hdg
878 = fgGetNode( "/orientation/heading-magnetic-deg", true );
879 static SGPropertyNode *fdm_bug_error
880 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
882 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
883 if ( diff < -180.0 ) { diff += 360.0; }
884 if ( diff > 180.0 ) { diff -= 360.0; }
885 fdm_bug_error->setDoubleValue( diff );
887 // Calculate true heading error normalized to +/- 180.0
888 static SGPropertyNode *target_true
889 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
890 static SGPropertyNode *true_hdg
891 = fgGetNode( "/orientation/heading-deg", true );
892 static SGPropertyNode *true_track
893 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
894 static SGPropertyNode *true_error
895 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
897 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
898 if ( diff < -180.0 ) { diff += 360.0; }
899 if ( diff > 180.0 ) { diff -= 360.0; }
900 true_error->setDoubleValue( diff );
902 // Calculate nav1 target heading error normalized to +/- 180.0
903 static SGPropertyNode *target_nav1
904 = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
905 static SGPropertyNode *true_nav1
906 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
907 static SGPropertyNode *true_track_nav1
908 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
910 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
911 if ( diff < -180.0 ) { diff += 360.0; }
912 if ( diff > 180.0 ) { diff -= 360.0; }
913 true_nav1->setDoubleValue( diff );
915 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
916 if ( diff < -180.0 ) { diff += 360.0; }
917 if ( diff > 180.0 ) { diff -= 360.0; }
918 true_track_nav1->setDoubleValue( diff );
920 // Calculate nav1 selected course error normalized to +/- 180.0
921 // (based on DG indicated heading)
922 static SGPropertyNode *nav1_course_error
923 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
924 static SGPropertyNode *nav1_selected_course
925 = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
927 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
928 // if ( diff < -180.0 ) { diff += 360.0; }
929 // if ( diff > 180.0 ) { diff -= 360.0; }
930 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
931 nav1_course_error->setDoubleValue( diff );
933 // Calculate vertical speed in fpm
934 static SGPropertyNode *vs_fps
935 = fgGetNode( "/velocities/vertical-speed-fps", true );
936 static SGPropertyNode *vs_fpm
937 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
939 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
942 // Calculate static port pressure rate in [inhg/s].
943 // Used to determine vertical speed.
944 static SGPropertyNode *static_pressure
945 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
946 static SGPropertyNode *pressure_rate
947 = fgGetNode( "/autopilot/internal/pressure-rate", true );
949 static double last_static_pressure = 0.0;
952 double current_static_pressure = static_pressure->getDoubleValue();
954 double current_pressure_rate =
955 ( current_static_pressure - last_static_pressure ) / dt;
957 pressure_rate->setDoubleValue(current_pressure_rate);
959 last_static_pressure = current_static_pressure;
966 * Update the list of autopilot components
969 void FGXMLAutopilot::update( double dt ) {
973 for ( i = 0; i < components.size(); ++i ) {
974 components[i]->update( dt );