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.
29 #include <simgear/structure/exception.hxx>
30 #include <simgear/misc/sg_path.hxx>
31 #include <simgear/sg_inlines.h>
32 #include <simgear/props/props_io.hxx>
34 #include <Main/fg_props.hxx>
35 #include <Main/globals.hxx>
36 #include <Main/util.hxx>
38 #include "xmlauto.hxx"
43 FGPIDController::FGPIDController( SGPropertyNode *node ):
67 for ( i = 0; i < node->nChildren(); ++i ) {
68 SGPropertyNode *child = node->getChild(i);
69 string cname = child->getName();
70 string cval = child->getStringValue();
71 if ( cname == "name" ) {
73 } else if ( cname == "debug" ) {
74 debug = child->getBoolValue();
75 } else if ( cname == "enable" ) {
76 // cout << "parsing enable" << endl;
77 SGPropertyNode *prop = child->getChild( "prop" );
79 // cout << "prop = " << prop->getStringValue() << endl;
80 enable_prop = fgGetNode( prop->getStringValue(), true );
82 // cout << "no prop child" << endl;
84 SGPropertyNode *val = child->getChild( "value" );
86 enable_value = val->getStringValue();
88 SGPropertyNode *pass = child->getChild( "honor-passive" );
90 honor_passive = pass->getBoolValue();
92 } else if ( cname == "input" ) {
93 SGPropertyNode *prop = child->getChild( "prop" );
95 input_prop = fgGetNode( prop->getStringValue(), true );
97 prop = child->getChild( "scale" );
99 y_scale = prop->getDoubleValue();
101 prop = child->getChild( "offset" );
102 if ( prop != NULL ) {
103 y_offset = prop->getDoubleValue();
105 } else if ( cname == "reference" ) {
106 SGPropertyNode *prop = child->getChild( "prop" );
107 if ( prop != NULL ) {
108 r_n_prop = fgGetNode( prop->getStringValue(), true );
110 prop = child->getChild( "value" );
111 if ( prop != NULL ) {
112 r_n_value = prop->getDoubleValue();
115 prop = child->getChild( "scale" );
116 if ( prop != NULL ) {
117 r_scale = prop->getDoubleValue();
119 prop = child->getChild( "offset" );
120 if ( prop != NULL ) {
121 r_offset = prop->getDoubleValue();
123 } else if ( cname == "output" ) {
125 SGPropertyNode *prop;
126 while ( (prop = child->getChild("prop", i)) != NULL ) {
127 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
128 output_list.push_back( tmp );
131 } else if ( cname == "config" ) {
132 SGPropertyNode *config;
134 config = child->getChild( "Ts" );
135 if ( config != NULL ) {
136 desiredTs = config->getDoubleValue();
139 config = child->getChild( "Kp" );
140 if ( config != NULL ) {
141 SGPropertyNode *val = config->getChild( "value" );
143 Kp = val->getDoubleValue();
146 SGPropertyNode *prop = config->getChild( "prop" );
147 if ( prop != NULL ) {
148 Kp_prop = fgGetNode( prop->getStringValue(), true );
150 Kp_prop->setDoubleValue(Kp);
154 // output deprecated usage warning
155 if (val == NULL && prop == NULL) {
156 Kp = config->getDoubleValue();
157 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Kp config. Please use <prop> and/or <value> tags." );
158 if ( name.length() ) {
159 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
164 config = child->getChild( "beta" );
165 if ( config != NULL ) {
166 beta = config->getDoubleValue();
169 config = child->getChild( "alpha" );
170 if ( config != NULL ) {
171 alpha = config->getDoubleValue();
174 config = child->getChild( "gamma" );
175 if ( config != NULL ) {
176 gamma = config->getDoubleValue();
179 config = child->getChild( "Ti" );
180 if ( config != NULL ) {
181 SGPropertyNode *val = config->getChild( "value" );
183 Ti = val->getDoubleValue();
186 SGPropertyNode *prop = config->getChild( "prop" );
187 if ( prop != NULL ) {
188 Ti_prop = fgGetNode( prop->getStringValue(), true );
190 Ti_prop->setDoubleValue(Kp);
194 // output deprecated usage warning
195 if (val == NULL && prop == NULL) {
196 Ti = config->getDoubleValue();
197 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Ti config. Please use <prop> and/or <value> tags." );
198 if ( name.length() ) {
199 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
204 config = child->getChild( "Td" );
205 if ( config != NULL ) {
206 SGPropertyNode *val = config->getChild( "value" );
208 Td = val->getDoubleValue();
211 SGPropertyNode *prop = config->getChild( "prop" );
212 if ( prop != NULL ) {
213 Td_prop = fgGetNode( prop->getStringValue(), true );
215 Td_prop->setDoubleValue(Kp);
219 // output deprecated usage warning
220 if (val == NULL && prop == NULL) {
221 Td = config->getDoubleValue();
222 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Td config. Please use <prop> and/or <value> tags." );
223 if ( name.length() ) {
224 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
229 config = child->getChild( "u_min" );
230 if ( config != NULL ) {
231 SGPropertyNode *val = config->getChild( "value" );
233 u_min = val->getDoubleValue();
236 SGPropertyNode *prop = config->getChild( "prop" );
237 if ( prop != NULL ) {
238 umin_prop = fgGetNode( prop->getStringValue(), true );
240 umin_prop->setDoubleValue(u_min);
244 // output deprecated usage warning
245 if (val == NULL && prop == NULL) {
246 u_min = config->getDoubleValue();
247 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_min config. Please use <prop> and/or <value> tags." );
248 if ( name.length() ) {
249 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
254 config = child->getChild( "u_max" );
255 if ( config != NULL ) {
256 SGPropertyNode *val = config->getChild( "value" );
258 u_max = val->getDoubleValue();
261 SGPropertyNode *prop = config->getChild( "prop" );
262 if ( prop != NULL ) {
263 umax_prop = fgGetNode( prop->getStringValue(), true );
265 umax_prop->setDoubleValue(u_max);
269 // output deprecated usage warning
270 if (val == NULL && prop == NULL) {
271 u_max = config->getDoubleValue();
272 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_max config. Please use <prop> and/or <value> tags." );
273 if ( name.length() ) {
274 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
279 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
280 if ( name.length() ) {
281 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
291 * Ok! Here is the PID controller algorithm that I would like to see
294 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
295 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
297 * u_n = u_n-1 + delta_u_n
301 * delta_u : The incremental output
302 * Kp : Proportional gain
303 * ep : Proportional error with reference weighing
306 * beta : Weighing factor
307 * r : Reference (setpoint)
308 * y : Process value, measured
311 * Ts : Sampling interval
312 * Ti : Integrator time
313 * Td : Derivator time
314 * edf : Derivate error with reference weighing and filtering
315 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
318 * Tf = alpha * Td , where alpha usually is set to 0.1
319 * ed : Unfiltered derivate error with reference weighing
322 * gamma : Weighing factor
324 * u : absolute output
326 * Index n means the n'th value.
331 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
332 * Kp , Ti , Td , Ts (is the sampling time available?)
339 void FGPIDController::update( double dt ) {
340 double ep_n; // proportional error with reference weighing
342 double ed_n; // derivative error
343 double edf_n; // derivative error filter
344 double Tf; // filter time
345 double delta_u_n = 0.0; // incremental output
346 double u_n = 0.0; // absolute output
347 double Ts; // sampling interval (sec)
348 if (umin_prop != NULL)u_min = umin_prop->getDoubleValue();
349 if (umax_prop != NULL)u_max = umax_prop->getDoubleValue();
350 if (Ti_prop != NULL)Ti = Ti_prop->getDoubleValue();
351 if (Td_prop != NULL)Td = Td_prop->getDoubleValue();
354 if ( elapsedTime <= desiredTs ) {
355 // do nothing if time step is not positive (i.e. no time has
362 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
364 // first time being enabled, seed u_n with current
365 // property tree value
366 u_n = output_list[0]->getDoubleValue();
368 if ( u_n < u_min ) { u_n = u_min; }
369 if ( u_n > u_max ) { u_n = u_max; }
377 if ( enabled && Ts > 0.0) {
378 if ( debug ) cout << "Updating " << name
379 << " Ts " << Ts << endl;
382 if ( input_prop != NULL ) {
383 y_n = input_prop->getDoubleValue() * y_scale + y_offset;
387 if ( r_n_prop != NULL ) {
388 r_n = r_n_prop->getDoubleValue() * r_scale + r_offset;
393 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
395 // Calculates proportional error:
396 ep_n = beta * r_n - y_n;
397 if ( debug ) cout << " ep_n = " << ep_n;
398 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
402 if ( debug ) cout << " e_n = " << e_n;
404 // Calculates derivate error:
405 ed_n = gamma * r_n - y_n;
406 if ( debug ) cout << " ed_n = " << ed_n;
409 // Calculates filter time:
411 if ( debug ) cout << " Tf = " << Tf;
413 // Filters the derivate error:
414 edf_n = edf_n_1 / (Ts/Tf + 1)
415 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
416 if ( debug ) cout << " edf_n = " << edf_n;
421 // Calculates the incremental output:
423 if (Kp_prop != NULL) {
424 Kp = Kp_prop->getDoubleValue();
426 delta_u_n = Kp * ( (ep_n - ep_n_1)
428 + ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
432 cout << " delta_u_n = " << delta_u_n << endl;
433 cout << "P:" << Kp * (ep_n - ep_n_1)
434 << " I:" << Kp * ((Ts/Ti) * e_n)
435 << " D:" << Kp * ((Td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
439 // Integrator anti-windup logic:
440 if ( delta_u_n > (u_max - u_n_1) ) {
441 delta_u_n = u_max - u_n_1;
442 if ( debug ) cout << " max saturation " << endl;
443 } else if ( delta_u_n < (u_min - u_n_1) ) {
444 delta_u_n = u_min - u_n_1;
445 if ( debug ) cout << " min saturation " << endl;
448 // Calculates absolute output:
449 u_n = u_n_1 + delta_u_n;
450 if ( debug ) cout << " output = " << u_n << endl;
452 // Updates indexed values;
458 // passive_ignore == true means that we go through all the
459 // motions, but drive the outputs. This is analogous to
460 // running the autopilot with the "servos" off. This is
461 // helpful for things like flight directors which position
462 // their vbars from the autopilot computations.
463 if ( passive_mode->getBoolValue() && honor_passive ) {
467 for ( i = 0; i < output_list.size(); ++i ) {
468 output_list[i]->setDoubleValue( u_n );
471 } else if ( !enabled ) {
474 // Updates indexed values;
483 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
484 proportional( false ),
501 for ( i = 0; i < node->nChildren(); ++i ) {
502 SGPropertyNode *child = node->getChild(i);
503 string cname = child->getName();
504 string cval = child->getStringValue();
505 if ( cname == "name" ) {
507 } else if ( cname == "debug" ) {
508 debug = child->getBoolValue();
509 } else if ( cname == "enable" ) {
510 // cout << "parsing enable" << endl;
511 SGPropertyNode *prop = child->getChild( "prop" );
512 if ( prop != NULL ) {
513 // cout << "prop = " << prop->getStringValue() << endl;
514 enable_prop = fgGetNode( prop->getStringValue(), true );
516 // cout << "no prop child" << endl;
518 SGPropertyNode *val = child->getChild( "value" );
520 enable_value = val->getStringValue();
522 } else if ( cname == "input" ) {
523 SGPropertyNode *prop = child->getChild( "prop" );
524 if ( prop != NULL ) {
525 input_prop = fgGetNode( prop->getStringValue(), true );
527 prop = child->getChild( "scale" );
528 if ( prop != NULL ) {
529 y_scale = prop->getDoubleValue();
531 } else if ( cname == "reference" ) {
532 SGPropertyNode *prop = child->getChild( "prop" );
533 if ( prop != NULL ) {
534 r_n_prop = fgGetNode( prop->getStringValue(), true );
536 prop = child->getChild( "value" );
537 if ( prop != NULL ) {
538 r_n_value = prop->getDoubleValue();
541 prop = child->getChild( "scale" );
542 if ( prop != NULL ) {
543 r_scale = prop->getDoubleValue();
545 } else if ( cname == "output" ) {
547 SGPropertyNode *prop;
548 while ( (prop = child->getChild("prop", i)) != NULL ) {
549 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
550 output_list.push_back( tmp );
553 } else if ( cname == "config" ) {
554 SGPropertyNode *prop;
556 prop = child->getChild( "Kp" );
557 if ( prop != NULL ) {
558 SGPropertyNode *val = prop->getChild( "value" );
560 Kp = val->getDoubleValue();
563 SGPropertyNode *prop1 = prop->getChild( "prop" );
564 if ( prop1 != NULL ) {
565 Kp_prop = fgGetNode( prop1->getStringValue(), true );
567 Kp_prop->setDoubleValue(Kp);
571 // output deprecated usage warning
572 if (val == NULL && prop1 == NULL) {
573 Kp = prop->getDoubleValue();
574 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated Kp config. Please use <prop> and/or <value> tags." );
579 prop = child->getChild( "Ki" );
580 if ( prop != NULL ) {
581 Ki = prop->getDoubleValue();
585 prop = child->getChild( "u_min" );
586 if ( prop != NULL ) {
587 SGPropertyNode *val = prop->getChild( "value" );
589 u_min = val->getDoubleValue();
592 SGPropertyNode *prop1 = prop->getChild( "prop" );
593 if ( prop1 != NULL ) {
594 umin_prop = fgGetNode( prop1->getStringValue(), true );
596 umin_prop->setDoubleValue(u_min);
600 // output deprecated usage warning
601 if (val == NULL && prop1 == NULL) {
602 u_min = prop->getDoubleValue();
603 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_min config. Please use <prop> and/or <value> tags." );
608 prop = child->getChild( "u_max" );
609 if ( prop != NULL ) {
610 SGPropertyNode *val = prop->getChild( "value" );
612 u_max = val->getDoubleValue();
615 SGPropertyNode *prop1 = prop->getChild( "prop" );
616 if ( prop1 != NULL ) {
617 umax_prop = fgGetNode( prop1->getStringValue(), true );
619 umax_prop->setDoubleValue(u_max);
623 // output deprecated usage warning
624 if (val == NULL && prop1 == NULL) {
625 u_max = prop->getDoubleValue();
626 SG_LOG( SG_AUTOPILOT, SG_WARN, "Deprecated u_max config. Please use <prop> and/or <value> tags." );
631 SG_LOG( SG_AUTOPILOT, SG_WARN, "Error in autopilot config logic" );
632 if ( name.length() ) {
633 SG_LOG( SG_AUTOPILOT, SG_WARN, "Section = " << name );
640 void FGPISimpleController::update( double dt ) {
641 if (umin_prop != NULL)u_min = umin_prop->getDoubleValue();
642 if (umax_prop != NULL)u_max = umax_prop->getDoubleValue();
643 if (Kp_prop != NULL)Kp = Kp_prop->getDoubleValue();
645 if (enable_prop != NULL && enable_prop->getStringValue() == enable_value) {
647 // we have just been enabled, zero out int_sum
656 if ( debug ) cout << "Updating " << name << endl;
658 if ( input_prop != NULL ) {
659 input = input_prop->getDoubleValue() * y_scale;
663 if ( r_n_prop != NULL ) {
664 r_n = r_n_prop->getDoubleValue() * r_scale;
669 double error = r_n - input;
670 if ( debug ) cout << "input = " << input
671 << " reference = " << r_n
672 << " error = " << error
675 double prop_comp = 0.0;
677 if ( offset_prop != NULL ) {
678 offset = offset_prop->getDoubleValue();
679 if ( debug ) cout << "offset = " << offset << endl;
681 offset = offset_value;
684 if ( proportional ) {
685 prop_comp = error * Kp + offset;
689 int_sum += error * Ki * dt;
694 if ( debug ) cout << "prop_comp = " << prop_comp
695 << " int_sum = " << int_sum << endl;
697 double output = prop_comp + int_sum;
700 if ( output < u_min ) {
703 if ( output > u_max ) {
707 if ( debug ) cout << "output = " << output << endl;
710 for ( i = 0; i < output_list.size(); ++i ) {
711 output_list[i]->setDoubleValue( output );
717 FGPredictor::FGPredictor ( SGPropertyNode *node ):
718 last_value ( 999999999.9 ),
726 for ( i = 0; i < node->nChildren(); ++i ) {
727 SGPropertyNode *child = node->getChild(i);
728 string cname = child->getName();
729 string cval = child->getStringValue();
730 if ( cname == "name" ) {
732 } else if ( cname == "debug" ) {
733 debug = child->getBoolValue();
734 } else if ( cname == "input" ) {
735 input_prop = fgGetNode( child->getStringValue(), true );
736 } else if ( cname == "seconds" ) {
737 seconds = child->getDoubleValue();
738 } else if ( cname == "filter-gain" ) {
739 filter_gain = child->getDoubleValue();
740 } else if ( cname == "output" ) {
741 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
742 output_list.push_back( tmp );
747 void FGPredictor::update( double dt ) {
749 Simple moving average filter converts input value to predicted value "seconds".
751 Smoothing as described by Curt Olson:
752 gain would be valid in the range of 0 - 1.0
753 1.0 would mean no filtering.
754 0.0 would mean no input.
755 0.5 would mean (1 part past value + 1 part current value) / 2
756 0.1 would mean (9 parts past value + 1 part current value) / 10
757 0.25 would mean (3 parts past value + 1 part current value) / 4
761 if ( input_prop != NULL ) {
762 ivalue = input_prop->getDoubleValue();
763 // no sense if there isn't an input :-)
771 // first time initialize average
772 if (last_value >= 999999999.0) {
777 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
779 average = (1.0 - dt) * average + current * dt;
784 // calculate output with filter gain adjustment
785 double output = ivalue + (1.0 - filter_gain) * (average * seconds) + filter_gain * (current * seconds);
788 for ( i = 0; i < output_list.size(); ++i ) {
789 output_list[i]->setDoubleValue( output );
797 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
803 output_min_clamp( -std::numeric_limits<double>::max() ),
804 output_max_clamp( std::numeric_limits<double>::max() )
807 for ( i = 0; i < node->nChildren(); ++i ) {
808 SGPropertyNode *child = node->getChild(i);
809 string cname = child->getName();
810 string cval = child->getStringValue();
811 if ( cname == "name" ) {
813 } else if ( cname == "debug" ) {
814 debug = child->getBoolValue();
815 } else if ( cname == "enable" ) {
816 SGPropertyNode *prop = child->getChild( "prop" );
817 if ( prop != NULL ) {
818 enable_prop = fgGetNode( prop->getStringValue(), true );
820 SGPropertyNode *val = child->getChild( "value" );
822 enable_value = val->getStringValue();
824 SGPropertyNode *pass = child->getChild( "honor-passive" );
825 if ( pass != NULL ) {
826 honor_passive = pass->getBoolValue();
828 } else if ( cname == "type" ) {
829 if ( cval == "exponential" ) {
830 filterType = exponential;
831 } else if (cval == "double-exponential") {
832 filterType = doubleExponential;
833 } else if (cval == "moving-average") {
834 filterType = movingAverage;
835 } else if (cval == "noise-spike") {
836 filterType = noiseSpike;
837 } else if (cval == "gain") {
839 } else if (cval == "reciprocal") {
840 filterType = reciprocal;
842 } else if ( cname == "input" ) {
843 input_prop = fgGetNode( child->getStringValue(), true );
844 } else if ( cname == "filter-time" ) {
845 Tf = child->getDoubleValue();
846 } else if ( cname == "samples" ) {
847 samples = child->getIntValue();
848 } else if ( cname == "max-rate-of-change" ) {
849 rateOfChange = child->getDoubleValue();
850 } else if ( cname == "gain" ) {
851 SGPropertyNode *val = child->getChild( "value" );
853 gainFactor = val->getDoubleValue();
855 SGPropertyNode *prop = child->getChild( "prop" );
856 if ( prop != NULL ) {
857 gain_prop = fgGetNode( prop->getStringValue(), true );
858 gain_prop->setDoubleValue(gainFactor);
860 } else if ( cname == "u_min" ) {
861 output_min_clamp = child->getDoubleValue();
862 } else if ( cname == "u_max" ) {
863 output_max_clamp = child->getDoubleValue();
864 } else if ( cname == "output" ) {
865 SGPropertyNode *tmp = fgGetNode( child->getStringValue(), true );
866 output_list.push_back( tmp );
870 output.resize(2, 0.0);
871 input.resize(samples + 1, 0.0);
874 void FGDigitalFilter::update(double dt)
876 if ( (input_prop != NULL &&
877 enable_prop != NULL &&
878 enable_prop->getStringValue() == enable_value) ||
879 (enable_prop == NULL &&
880 input_prop != NULL) ) {
882 input.push_front(input_prop->getDoubleValue());
883 input.resize(samples + 1, 0.0);
886 // first time being enabled, initialize output to the
887 // value of the output property to avoid bumping.
888 output.push_front(output_list[0]->getDoubleValue());
896 if ( enabled && dt > 0.0 ) {
900 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
904 if (filterType == exponential)
906 double alpha = 1 / ((Tf/dt) + 1);
907 output.push_front(alpha * input[0] +
908 (1 - alpha) * output[0]);
910 else if (filterType == doubleExponential)
912 double alpha = 1 / ((Tf/dt) + 1);
913 output.push_front(alpha * alpha * input[0] +
914 2 * (1 - alpha) * output[0] -
915 (1 - alpha) * (1 - alpha) * output[1]);
917 else if (filterType == movingAverage)
919 output.push_front(output[0] +
920 (input[0] - input.back()) / samples);
922 else if (filterType == noiseSpike)
924 double maxChange = rateOfChange * dt;
926 if ((output[0] - input[0]) > maxChange)
928 output.push_front(output[0] - maxChange);
930 else if ((output[0] - input[0]) < -maxChange)
932 output.push_front(output[0] + maxChange);
934 else if (fabs(input[0] - output[0]) <= maxChange)
936 output.push_front(input[0]);
939 else if (filterType == gain)
941 if (gain_prop != NULL) {
942 gainFactor = gain_prop->getDoubleValue();
944 output[0] = gainFactor * input[0];
946 else if (filterType == reciprocal)
948 if (gain_prop != NULL) {
949 gainFactor = gain_prop->getDoubleValue();
951 if (input[0] != 0.0) {
952 output[0] = gainFactor / input[0];
956 if (output[0] < output_min_clamp) {
957 output[0] = output_min_clamp;
959 else if (output[0] > output_max_clamp) {
960 output[0] = output_max_clamp;
964 for ( i = 0; i < output_list.size(); ++i ) {
965 output_list[i]->setDoubleValue( output[0] );
971 cout << "input:" << input[0]
972 << "\toutput:" << output[0] << endl;
978 FGXMLAutopilot::FGXMLAutopilot() {
982 FGXMLAutopilot::~FGXMLAutopilot() {
986 void FGXMLAutopilot::init() {
987 config_props = fgGetNode( "/autopilot/new-config", true );
989 SGPropertyNode *path_n = fgGetNode("/sim/systems/autopilot/path");
992 SGPath config( globals->get_fg_root() );
993 config.append( path_n->getStringValue() );
995 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from "
998 readProperties( config.str(), config_props );
1001 SG_LOG( SG_ALL, SG_ALERT,
1002 "Detected an internal inconsistency in the autopilot");
1003 SG_LOG( SG_ALL, SG_ALERT,
1004 " configuration. See earlier errors for" );
1005 SG_LOG( SG_ALL, SG_ALERT,
1009 } catch (const sg_exception& exc) {
1010 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
1015 SG_LOG( SG_ALL, SG_WARN,
1016 "No autopilot configuration specified for this model!");
1021 void FGXMLAutopilot::reinit() {
1027 void FGXMLAutopilot::bind() {
1030 void FGXMLAutopilot::unbind() {
1033 bool FGXMLAutopilot::build() {
1034 SGPropertyNode *node;
1037 int count = config_props->nChildren();
1038 for ( i = 0; i < count; ++i ) {
1039 node = config_props->getChild(i);
1040 string name = node->getName();
1041 // cout << name << endl;
1042 if ( name == "pid-controller" ) {
1043 components.push_back( new FGPIDController( node ) );
1044 } else if ( name == "pi-simple-controller" ) {
1045 components.push_back( new FGPISimpleController( node ) );
1046 } else if ( name == "predict-simple" ) {
1047 components.push_back( new FGPredictor( node ) );
1048 } else if ( name == "filter" ) {
1049 components.push_back( new FGDigitalFilter( node ) );
1051 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
1062 * Update helper values
1064 static void update_helper( double dt ) {
1065 // Estimate speed in 5,10 seconds
1066 static SGPropertyNode *vel = fgGetNode( "/velocities/airspeed-kt", true );
1067 static SGPropertyNode *lookahead5
1068 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
1069 static SGPropertyNode *lookahead10
1070 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
1072 static double average = 0.0; // average/filtered prediction
1073 static double v_last = 0.0; // last velocity
1075 double v = vel->getDoubleValue();
1078 a = (v - v_last) / dt;
1081 average = (1.0 - dt) * average + dt * a;
1086 lookahead5->setDoubleValue( v + average * 5.0 );
1087 lookahead10->setDoubleValue( v + average * 10.0 );
1091 // Calculate heading bug error normalized to +/- 180.0 (based on
1092 // DG indicated heading)
1093 static SGPropertyNode *bug
1094 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
1095 static SGPropertyNode *ind_hdg
1096 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
1098 static SGPropertyNode *ind_bug_error
1099 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
1101 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
1102 if ( diff < -180.0 ) { diff += 360.0; }
1103 if ( diff > 180.0 ) { diff -= 360.0; }
1104 ind_bug_error->setDoubleValue( diff );
1106 // Calculate heading bug error normalized to +/- 180.0 (based on
1107 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
1109 static SGPropertyNode *mag_hdg
1110 = fgGetNode( "/orientation/heading-magnetic-deg", true );
1111 static SGPropertyNode *fdm_bug_error
1112 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
1114 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
1115 if ( diff < -180.0 ) { diff += 360.0; }
1116 if ( diff > 180.0 ) { diff -= 360.0; }
1117 fdm_bug_error->setDoubleValue( diff );
1119 // Calculate true heading error normalized to +/- 180.0
1120 static SGPropertyNode *target_true
1121 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
1122 static SGPropertyNode *true_hdg
1123 = fgGetNode( "/orientation/heading-deg", true );
1124 static SGPropertyNode *true_track
1125 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
1126 static SGPropertyNode *true_error
1127 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
1129 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
1130 if ( diff < -180.0 ) { diff += 360.0; }
1131 if ( diff > 180.0 ) { diff -= 360.0; }
1132 true_error->setDoubleValue( diff );
1134 // Calculate nav1 target heading error normalized to +/- 180.0
1135 static SGPropertyNode *target_nav1
1136 = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
1137 static SGPropertyNode *true_nav1
1138 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
1139 static SGPropertyNode *true_track_nav1
1140 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
1142 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
1143 if ( diff < -180.0 ) { diff += 360.0; }
1144 if ( diff > 180.0 ) { diff -= 360.0; }
1145 true_nav1->setDoubleValue( diff );
1147 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
1148 if ( diff < -180.0 ) { diff += 360.0; }
1149 if ( diff > 180.0 ) { diff -= 360.0; }
1150 true_track_nav1->setDoubleValue( diff );
1152 // Calculate nav1 selected course error normalized to +/- 180.0
1153 // (based on DG indicated heading)
1154 static SGPropertyNode *nav1_course_error
1155 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
1156 static SGPropertyNode *nav1_selected_course
1157 = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
1159 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
1160 // if ( diff < -180.0 ) { diff += 360.0; }
1161 // if ( diff > 180.0 ) { diff -= 360.0; }
1162 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
1163 nav1_course_error->setDoubleValue( diff );
1165 // Calculate vertical speed in fpm
1166 static SGPropertyNode *vs_fps
1167 = fgGetNode( "/velocities/vertical-speed-fps", true );
1168 static SGPropertyNode *vs_fpm
1169 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
1171 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
1174 // Calculate static port pressure rate in [inhg/s].
1175 // Used to determine vertical speed.
1176 static SGPropertyNode *static_pressure
1177 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
1178 static SGPropertyNode *pressure_rate
1179 = fgGetNode( "/autopilot/internal/pressure-rate", true );
1181 static double last_static_pressure = 0.0;
1184 double current_static_pressure = static_pressure->getDoubleValue();
1186 double current_pressure_rate =
1187 ( current_static_pressure - last_static_pressure ) / dt;
1189 pressure_rate->setDoubleValue(current_pressure_rate);
1191 last_static_pressure = current_static_pressure;
1198 * Update the list of autopilot components
1201 void FGXMLAutopilot::update( double dt ) {
1202 update_helper( dt );
1205 for ( i = 0; i < components.size(); ++i ) {
1206 components[i]->update( dt );