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 ):
62 for ( i = 0; i < node->nChildren(); ++i ) {
63 SGPropertyNode *child = node->getChild(i);
64 string cname = child->getName();
65 string cval = child->getStringValue();
66 if ( cname == "name" ) {
68 } else if ( cname == "debug" ) {
69 debug = child->getBoolValue();
70 } else if ( cname == "enable" ) {
71 // cout << "parsing enable" << endl;
72 SGPropertyNode *prop = child->getChild( "prop" );
74 // cout << "prop = " << prop->getStringValue() << endl;
75 enable_prop = fgGetNode( prop->getStringValue(), true );
77 // cout << "no prop child" << endl;
79 SGPropertyNode *val = child->getChild( "value" );
81 enable_value = val->getStringValue();
83 SGPropertyNode *pass = child->getChild( "honor-passive" );
85 honor_passive = pass->getBoolValue();
87 } else if ( cname == "input" ) {
88 SGPropertyNode *prop = child->getChild( "prop" );
90 input_prop = fgGetNode( prop->getStringValue(), true );
92 prop = child->getChild( "scale" );
94 y_scale = prop->getDoubleValue();
96 prop = child->getChild( "offset" );
98 y_offset = prop->getDoubleValue();
100 } else if ( cname == "reference" ) {
101 SGPropertyNode *prop = child->getChild( "prop" );
102 if ( prop != NULL ) {
103 r_n_prop = fgGetNode( prop->getStringValue(), true );
105 prop = child->getChild( "value" );
106 if ( prop != NULL ) {
107 r_n_value = prop->getDoubleValue();
110 prop = child->getChild( "scale" );
111 if ( prop != NULL ) {
112 r_scale = prop->getDoubleValue();
114 prop = child->getChild( "offset" );
115 if ( prop != NULL ) {
116 r_offset = prop->getDoubleValue();
118 } else if ( cname == "output" ) {
120 SGPropertyNode *prop;
121 while ( (prop = child->getChild("prop", i)) != NULL ) {
122 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
123 output_list.push_back( tmp );
126 } else if ( cname == "config" ) {
127 SGPropertyNode *prop;
129 prop = child->getChild( "Ts" );
130 if ( prop != NULL ) {
131 desiredTs = prop->getDoubleValue();
134 prop = child->getChild( "Kp" );
135 if ( prop != NULL ) {
136 Kp = prop->getDoubleValue();
139 prop = child->getChild( "beta" );
140 if ( prop != NULL ) {
141 beta = prop->getDoubleValue();
144 prop = child->getChild( "alpha" );
145 if ( prop != NULL ) {
146 alpha = prop->getDoubleValue();
149 prop = child->getChild( "gamma" );
150 if ( prop != NULL ) {
151 gamma = prop->getDoubleValue();
154 prop = child->getChild( "Ti" );
155 if ( prop != NULL ) {
156 Ti = prop->getDoubleValue();
159 prop = child->getChild( "Td" );
160 if ( prop != NULL ) {
161 Td = prop->getDoubleValue();
164 prop = child->getChild( "u_min" );
165 if ( prop != NULL ) {
166 u_min = prop->getDoubleValue();
169 prop = child->getChild( "u_max" );
170 if ( prop != NULL ) {
171 u_max = prop->getDoubleValue();
174 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
175 if ( name.length() ) {
176 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
186 * Ok! Here is the PID controller algorithm that I would like to see
189 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
190 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
192 * u_n = u_n-1 + delta_u_n
196 * delta_u : The incremental output
197 * Kp : Proportional gain
198 * ep : Proportional error with reference weighing
201 * beta : Weighing factor
202 * r : Reference (setpoint)
203 * y : Process value, measured
206 * Ts : Sampling interval
207 * Ti : Integrator time
208 * Td : Derivator time
209 * edf : Derivate error with reference weighing and filtering
210 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
213 * Tf = alpha * Td , where alpha usually is set to 0.1
214 * ed : Unfiltered derivate error with reference weighing
217 * gamma : Weighing factor
219 * u : absolute output
221 * Index n means the n'th value.
226 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
227 * Kp , Ti , Td , Ts (is the sampling time available?)
234 void FGPIDController::update( double dt ) {
235 double ep_n; // proportional error with reference weighing
237 double ed_n; // derivative error
238 double edf_n; // derivative error filter
239 double Tf; // filter time
240 double delta_u_n = 0.0; // incremental output
241 double u_n = 0.0; // absolute output
242 double Ts; // sampling interval (sec)
245 if ( elapsedTime <= desiredTs ) {
246 // do nothing if time step is not positive (i.e. no time has
253 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
255 // first time being enabled, seed u_n with current
256 // property tree value
257 u_n = output_list[0]->getDoubleValue();
259 if ( u_n < u_min ) { u_n = u_min; }
260 if ( u_n > u_max ) { u_n = u_max; }
268 if ( enabled && Ts > 0.0) {
269 if ( debug ) cout << "Updating " << name
270 << " Ts " << Ts << endl;
273 if ( input_prop != NULL ) {
274 y_n = input_prop->getDoubleValue() * y_scale + y_offset;
278 if ( r_n_prop != NULL ) {
279 r_n = r_n_prop->getDoubleValue() * r_scale + r_offset;
284 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
286 // Calculates proportional error:
287 ep_n = beta * r_n - y_n;
288 if ( debug ) cout << " ep_n = " << ep_n;
289 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
293 if ( debug ) cout << " e_n = " << e_n;
295 // Calculates derivate error:
296 ed_n = gamma * r_n - y_n;
297 if ( debug ) cout << " ed_n = " << ed_n;
300 // Calculates filter time:
302 if ( debug ) cout << " Tf = " << Tf;
304 // Filters the derivate error:
305 edf_n = edf_n_1 / (Ts/Tf + 1)
306 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
307 if ( debug ) cout << " edf_n = " << edf_n;
312 // Calculates the incremental output:
314 delta_u_n = Kp * ( (ep_n - ep_n_1)
316 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
320 cout << " delta_u_n = " << delta_u_n << endl;
321 cout << "P:" << Kp * (ep_n - ep_n_1)
322 << " I:" << Kp * ((Ts/Ti) * e_n)
323 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
327 // Integrator anti-windup logic:
328 if ( delta_u_n > (u_max - u_n_1) ) {
329 delta_u_n = u_max - u_n_1;
330 if ( debug ) cout << " max saturation " << endl;
331 } else if ( delta_u_n < (u_min - u_n_1) ) {
332 delta_u_n = u_min - u_n_1;
333 if ( debug ) cout << " min saturation " << endl;
336 // Calculates absolute output:
337 u_n = u_n_1 + delta_u_n;
338 if ( debug ) cout << " output = " << u_n << endl;
340 // Updates indexed values;
346 // passive_ignore == true means that we go through all the
347 // motions, but drive the outputs. This is analogous to
348 // running the autopilot with the "servos" off. This is
349 // helpful for things like flight directors which position
350 // their vbars from the autopilot computations.
351 if ( passive_mode->getBoolValue() && honor_passive ) {
355 for ( i = 0; i < output_list.size(); ++i ) {
356 output_list[i]->setDoubleValue( u_n );
359 } else if ( !enabled ) {
362 // Updates indexed values;
371 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
372 proportional( false ),
389 for ( i = 0; i < node->nChildren(); ++i ) {
390 SGPropertyNode *child = node->getChild(i);
391 string cname = child->getName();
392 string cval = child->getStringValue();
393 if ( cname == "name" ) {
395 } else if ( cname == "debug" ) {
396 debug = child->getBoolValue();
397 } else if ( cname == "enable" ) {
398 // cout << "parsing enable" << endl;
399 SGPropertyNode *prop = child->getChild( "prop" );
400 if ( prop != NULL ) {
401 // cout << "prop = " << prop->getStringValue() << endl;
402 enable_prop = fgGetNode( prop->getStringValue(), true );
404 // cout << "no prop child" << endl;
406 SGPropertyNode *val = child->getChild( "value" );
408 enable_value = val->getStringValue();
410 } else if ( cname == "input" ) {
411 SGPropertyNode *prop = child->getChild( "prop" );
412 if ( prop != NULL ) {
413 input_prop = fgGetNode( prop->getStringValue(), true );
415 prop = child->getChild( "scale" );
416 if ( prop != NULL ) {
417 y_scale = prop->getDoubleValue();
419 } else if ( cname == "reference" ) {
420 SGPropertyNode *prop = child->getChild( "prop" );
421 if ( prop != NULL ) {
422 r_n_prop = fgGetNode( prop->getStringValue(), true );
424 prop = child->getChild( "value" );
425 if ( prop != NULL ) {
426 r_n_value = prop->getDoubleValue();
429 prop = child->getChild( "scale" );
430 if ( prop != NULL ) {
431 r_scale = prop->getDoubleValue();
433 } else if ( cname == "output" ) {
435 SGPropertyNode *prop;
436 while ( (prop = child->getChild("prop", i)) != NULL ) {
437 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
438 output_list.push_back( tmp );
441 } else if ( cname == "config" ) {
442 SGPropertyNode *prop;
444 prop = child->getChild( "Kp" );
445 if ( prop != NULL ) {
446 Kp = prop->getDoubleValue();
450 prop = child->getChild( "Ki" );
451 if ( prop != NULL ) {
452 Ki = prop->getDoubleValue();
456 prop = child->getChild( "u_min" );
457 if ( prop != NULL ) {
458 u_min = prop->getDoubleValue();
462 prop = child->getChild( "u_max" );
463 if ( prop != NULL ) {
464 u_max = prop->getDoubleValue();
468 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
469 if ( name.length() ) {
470 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
477 void FGPISimpleController::update( double dt ) {
478 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
480 // we have just been enabled, zero out int_sum
489 if ( debug ) cout << "Updating " << name << endl;
491 if ( input_prop != NULL ) {
492 input = input_prop->getDoubleValue() * y_scale;
496 if ( r_n_prop != NULL ) {
497 r_n = r_n_prop->getDoubleValue() * r_scale;
502 double error = r_n - input;
503 if ( debug ) cout << "input = " << input
504 << " reference = " << r_n
505 << " error = " << error
508 double prop_comp = 0.0;
510 if ( offset_prop != NULL ) {
511 offset = offset_prop->getDoubleValue();
512 if ( debug ) cout << "offset = " << offset << endl;
514 offset = offset_value;
517 if ( proportional ) {
518 prop_comp = error * Kp + offset;
522 int_sum += error * Ki * dt;
527 if ( debug ) cout << "prop_comp = " << prop_comp
528 << " int_sum = " << int_sum << endl;
530 double output = prop_comp + int_sum;
533 if ( output < u_min ) {
536 if ( output > u_max ) {
540 if ( debug ) cout << "output = " << output << endl;
543 for ( i = 0; i < output_list.size(); ++i ) {
544 output_list[i]->setDoubleValue( output );
550 FGPredictor::FGPredictor ( SGPropertyNode *node ):
551 last_value ( 999999999.9 ),
559 for ( i = 0; i < node->nChildren(); ++i ) {
560 SGPropertyNode *child = node->getChild(i);
561 string cname = child->getName();
562 string cval = child->getStringValue();
563 if ( cname == "name" ) {
565 } else if ( cname == "debug" ) {
566 debug = child->getBoolValue();
567 } else if ( cname == "input" ) {
568 input_prop = fgGetNode( child->getStringValue(), true );
569 } else if ( cname == "seconds" ) {
570 seconds = child->getDoubleValue();
571 } else if ( cname == "filter-gain" ) {
572 filter_gain = child->getDoubleValue();
573 } else if ( cname == "output" ) {
574 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
575 output_list.push_back( tmp );
580 void FGPredictor::update( double dt ) {
582 Simple moving average filter converts input value to predicted value "seconds".
584 Smoothing as described by Curt Olson:
585 gain would be valid in the range of 0 - 1.0
586 1.0 would mean no filtering.
587 0.0 would mean no input.
588 0.5 would mean (1 part past value + 1 part current value) / 2
589 0.1 would mean (9 parts past value + 1 part current value) / 10
590 0.25 would mean (3 parts past value + 1 part current value) / 4
594 if ( input_prop != NULL ) {
595 ivalue = input_prop->getDoubleValue();
596 // no sense if there isn't an input :-)
604 // first time initialize average
605 if (last_value >= 999999999.0) {
610 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
612 average = (1.0 - dt) * average + current * dt;
617 // calculate output with filter gain adjustment
618 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
621 for ( i = 0; i < output_list.size(); ++i ) {
622 output_list[i]->setDoubleValue( output );
630 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node)
635 for ( i = 0; i < node->nChildren(); ++i ) {
636 SGPropertyNode *child = node->getChild(i);
637 string cname = child->getName();
638 string cval = child->getStringValue();
639 if ( cname == "name" ) {
641 } else if ( cname == "debug" ) {
642 debug = child->getBoolValue();
643 } else if ( cname == "type" ) {
644 if ( cval == "exponential" ) {
645 filterType = exponential;
646 } else if (cval == "double-exponential") {
647 filterType = doubleExponential;
648 } else if (cval == "moving-average") {
649 filterType = movingAverage;
650 } else if (cval == "noise-spike") {
651 filterType = noiseSpike;
653 } else if ( cname == "input" ) {
654 input_prop = fgGetNode( child->getStringValue(), true );
655 } else if ( cname == "filter-time" ) {
656 Tf = child->getDoubleValue();
657 } else if ( cname == "samples" ) {
658 samples = child->getIntValue();
659 } else if ( cname == "max-rate-of-change" ) {
660 rateOfChange = child->getDoubleValue();
661 } else if ( cname == "output" ) {
662 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
663 output_list.push_back( tmp );
667 output.resize(2, 0.0);
668 input.resize(samples + 1, 0.0);
671 void FGDigitalFilter::update(double dt)
673 if ( input_prop != NULL ) {
674 input.push_front(input_prop->getDoubleValue());
675 input.resize(samples + 1, 0.0);
676 // no sense if there isn't an input :-)
682 if ( enabled && dt > 0.0 ) {
686 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
690 if (filterType == exponential)
692 double alpha = 1 / ((Tf/dt) + 1);
693 output.push_front(alpha * input[0] +
694 (1 - alpha) * output[0]);
696 for ( i = 0; i < output_list.size(); ++i ) {
697 output_list[i]->setDoubleValue( output[0] );
701 else if (filterType == doubleExponential)
703 double alpha = 1 / ((Tf/dt) + 1);
704 output.push_front(alpha * alpha * input[0] +
705 2 * (1 - alpha) * output[0] -
706 (1 - alpha) * (1 - alpha) * output[1]);
708 for ( i = 0; i < output_list.size(); ++i ) {
709 output_list[i]->setDoubleValue( output[0] );
713 else if (filterType == movingAverage)
715 output.push_front(output[0] +
716 (input[0] - input.back()) / samples);
718 for ( i = 0; i < output_list.size(); ++i ) {
719 output_list[i]->setDoubleValue( output[0] );
723 else if (filterType == noiseSpike)
725 double maxChange = rateOfChange * dt;
727 if ((output[0] - input[0]) > maxChange)
729 output.push_front(output[0] - maxChange);
731 else if ((output[0] - input[0]) < -maxChange)
733 output.push_front(output[0] + maxChange);
735 else if (fabs(input[0] - output[0]) <= maxChange)
737 output.push_front(input[0]);
741 for ( i = 0; i < output_list.size(); ++i ) {
742 output_list[i]->setDoubleValue( output[0] );
748 cout << "input:" << input[0]
749 << "\toutput:" << output[0] << endl;
755 FGXMLAutopilot::FGXMLAutopilot() {
759 FGXMLAutopilot::~FGXMLAutopilot() {
763 void FGXMLAutopilot::init() {
764 config_props = fgGetNode( "/autopilot/new-config", true );
766 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
769 SGPath config( globals->get_fg_root() );
770 config.append( path_n->getStringValue() );
772 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
775 readProperties( config.str(), config_props );
778 SG_LOG( SG_ALL, SG_ALERT,
779 "Detected an internal inconsistency in the autopilot");
780 SG_LOG( SG_ALL, SG_ALERT,
781 " configuration. See earlier errors for" );
782 SG_LOG( SG_ALL, SG_ALERT,
786 } catch (const sg_exception& exc) {
787 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
792 SG_LOG( SG_ALL, SG_WARN,
793 "No autopilot configuration specified for this model!");
798 void FGXMLAutopilot::reinit() {
805 void FGXMLAutopilot::bind() {
808 void FGXMLAutopilot::unbind() {
811 bool FGXMLAutopilot::build() {
812 SGPropertyNode *node;
815 int count = config_props->nChildren();
816 for ( i = 0; i < count; ++i ) {
817 node = config_props->getChild(i);
818 string name = node->getName();
819 // cout << name << endl;
820 if ( name == "pid-controller" ) {
821 FGXMLAutoComponent *c = new FGPIDController( node );
822 components.push_back( c );
823 } else if ( name == "pi-simple-controller" ) {
824 FGXMLAutoComponent *c = new FGPISimpleController( node );
825 components.push_back( c );
826 } else if ( name == "predict-simple" ) {
827 FGXMLAutoComponent *c = new FGPredictor( node );
828 components.push_back( c );
829 } else if ( name == "filter" ) {
830 FGXMLAutoComponent *c = new FGDigitalFilter( node );
831 components.push_back( c );
833 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
844 * Update helper values
846 static void update_helper( double dt ) {
847 // Estimate speed in 5,10 seconds
848 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
849 static SGPropertyNode *lookahead5
850 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
851 static SGPropertyNode *lookahead10
852 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
854 static double average = 0.0; // average/filtered prediction
855 static double v_last = 0.0; // last velocity
857 double v = vel->getDoubleValue();
860 a = (v - v_last) / dt;
863 average = (1.0 - dt) * average + dt * a;
868 lookahead5->setDoubleValue( v + average * 5.0 );
869 lookahead10->setDoubleValue( v + average * 10.0 );
873 // Calculate heading bug error normalized to +/- 180.0 (based on
874 // DG indicated heading)
875 static SGPropertyNode *bug
876 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
877 static SGPropertyNode *ind_hdg
878 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
880 static SGPropertyNode *ind_bug_error
881 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
883 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
884 if ( diff < -180.0 ) { diff += 360.0; }
885 if ( diff > 180.0 ) { diff -= 360.0; }
886 ind_bug_error->setDoubleValue( diff );
888 // Calculate heading bug error normalized to +/- 180.0 (based on
889 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
891 static SGPropertyNode *mag_hdg
892 = fgGetNode( "/orientation/heading-magnetic-deg", true );
893 static SGPropertyNode *fdm_bug_error
894 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
896 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
897 if ( diff < -180.0 ) { diff += 360.0; }
898 if ( diff > 180.0 ) { diff -= 360.0; }
899 fdm_bug_error->setDoubleValue( diff );
901 // Calculate true heading error normalized to +/- 180.0
902 static SGPropertyNode *target_true
903 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
904 static SGPropertyNode *true_hdg
905 = fgGetNode( "/orientation/heading-deg", true );
906 static SGPropertyNode *true_track
907 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
908 static SGPropertyNode *true_error
909 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
911 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
912 if ( diff < -180.0 ) { diff += 360.0; }
913 if ( diff > 180.0 ) { diff -= 360.0; }
914 true_error->setDoubleValue( diff );
916 // Calculate nav1 target heading error normalized to +/- 180.0
917 static SGPropertyNode *target_nav1
918 = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
919 static SGPropertyNode *true_nav1
920 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
921 static SGPropertyNode *true_track_nav1
922 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
924 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
925 if ( diff < -180.0 ) { diff += 360.0; }
926 if ( diff > 180.0 ) { diff -= 360.0; }
927 true_nav1->setDoubleValue( diff );
929 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
930 if ( diff < -180.0 ) { diff += 360.0; }
931 if ( diff > 180.0 ) { diff -= 360.0; }
932 true_track_nav1->setDoubleValue( diff );
934 // Calculate nav1 selected course error normalized to +/- 180.0
935 // (based on DG indicated heading)
936 static SGPropertyNode *nav1_course_error
937 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
938 static SGPropertyNode *nav1_selected_course
939 = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
941 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
942 // if ( diff < -180.0 ) { diff += 360.0; }
943 // if ( diff > 180.0 ) { diff -= 360.0; }
944 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
945 nav1_course_error->setDoubleValue( diff );
947 // Calculate vertical speed in fpm
948 static SGPropertyNode *vs_fps
949 = fgGetNode( "/velocities/vertical-speed-fps", true );
950 static SGPropertyNode *vs_fpm
951 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
953 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
956 // Calculate static port pressure rate in [inhg/s].
957 // Used to determine vertical speed.
958 static SGPropertyNode *static_pressure
959 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
960 static SGPropertyNode *pressure_rate
961 = fgGetNode( "/autopilot/internal/pressure-rate", true );
963 static double last_static_pressure = 0.0;
966 double current_static_pressure = static_pressure->getDoubleValue();
968 double current_pressure_rate =
969 ( current_static_pressure - last_static_pressure ) / dt;
971 pressure_rate->setDoubleValue(current_pressure_rate);
973 last_static_pressure = current_static_pressure;
980 * Update the list of autopilot components
983 void FGXMLAutopilot::update( double dt ) {
987 for ( i = 0; i < components.size(); ++i ) {
988 components[i]->update( dt );