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 FGXMLAutoInput::FGXMLAutoInput( SGPropertyNode_ptr node, double value, double offset, double scale) :
53 parse( node, value, offset, scale );
57 void FGXMLAutoInput::parse( SGPropertyNode_ptr node, double aValue, double aOffset, double aScale )
71 if( (n = node->getChild("condition")) != NULL ) {
72 _condition = sgReadCondition(fgGetNode("/"), n);
75 if( (n = node->getChild( "scale" )) != NULL ) {
76 scale = new FGXMLAutoInput( n, aScale );
79 if( (n = node->getChild( "offset" )) != NULL ) {
80 offset = new FGXMLAutoInput( n, aOffset );
83 if( (n = node->getChild( "max" )) != NULL ) {
84 max = new FGXMLAutoInput( n );
87 if( (n = node->getChild( "min" )) != NULL ) {
88 min = new FGXMLAutoInput( n );
91 if( (n = node->getChild( "abs" )) != NULL ) {
92 abs = n->getBoolValue();
95 SGPropertyNode *valueNode = node->getChild( "value" );
96 if ( valueNode != NULL ) {
97 value = valueNode->getDoubleValue();
100 n = node->getChild( "property" );
101 // if no <property> element, check for <prop> element for backwards
104 n = node->getChild( "prop" );
107 property = fgGetNode( n->getStringValue(), true );
108 if ( valueNode != NULL ) {
109 // initialize property with given value
110 // if both <prop> and <value> exist
111 double s = get_scale();
113 property->setDoubleValue( (value - get_offset())/s );
115 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
119 if ( n == NULL && valueNode == NULL ) {
120 // no <value> element and no <prop> element, use text node
121 const char * textnode = node->getStringValue();
123 // try to convert to a double value. If the textnode does not start with a number
124 // endp will point to the beginning of the string. We assume this should be
126 value = strtod( textnode, &endp );
127 if( endp == textnode ) {
128 property = fgGetNode( textnode, true );
133 void FGXMLAutoInput::set_value( double aValue )
135 double s = get_scale();
137 property->setDoubleValue( (aValue - get_offset())/s );
139 property->setDoubleValue( 0 ); // if scale is zero, value*scale is zero
142 double FGXMLAutoInput::get_value()
144 if( property != NULL )
145 value = property->getDoubleValue();
148 value *= scale->get_value();
151 value += offset->get_value();
154 double m = min->get_value();
160 double m = max->get_value();
165 return abs ? fabs(value) : value;
168 FGXMLAutoComponent::FGXMLAutoComponent() :
171 enable_value( NULL ),
172 passive_mode( fgGetNode("/autopilot/locks/passive-mode", true) ),
173 honor_passive( false ),
175 feedback_if_disabled( false ),
181 FGXMLAutoComponent::~FGXMLAutoComponent()
186 void FGXMLAutoComponent::parseNode(SGPropertyNode* aNode)
188 SGPropertyNode *prop;
189 for (int i = 0; i < aNode->nChildren(); ++i ) {
190 SGPropertyNode *child = aNode->getChild(i);
191 string cname(child->getName());
193 if (parseNodeHook(cname, child)) {
194 // derived class handled it, fine
195 } else if ( cname == "name" ) {
196 name = child->getStringValue();
197 } else if ( cname == "feedback-if-disabled" ) {
198 feedback_if_disabled = child->getBoolValue();
199 } else if ( cname == "debug" ) {
200 debug = child->getBoolValue();
201 } else if ( cname == "enable" ) {
202 if( (prop = child->getChild("condition")) != NULL ) {
203 _condition = sgReadCondition(fgGetNode("/"), prop);
205 if ( (prop = child->getChild( "prop" )) != NULL ) {
206 enable_prop = fgGetNode( prop->getStringValue(), true );
209 if ( (prop = child->getChild( "value" )) != NULL ) {
211 enable_value = new string(prop->getStringValue());
214 if ( (prop = child->getChild( "honor-passive" )) != NULL ) {
215 honor_passive = prop->getBoolValue();
217 } else if ( cname == "input" ) {
218 valueInput.push_back( new FGXMLAutoInput( child ) );
219 } else if ( cname == "reference" ) {
220 referenceInput.push_back( new FGXMLAutoInput( child ) );
221 } else if ( cname == "output" ) {
222 // grab all <prop> and <property> childs
224 // backwards compatibility: allow <prop> elements
225 for( int i = 0; (prop = child->getChild("prop", i)) != NULL; i++ ) {
226 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
227 output_list.push_back( tmp );
230 for( int i = 0; (prop = child->getChild("property", i)) != NULL; i++ ) {
231 SGPropertyNode *tmp = fgGetNode( prop->getStringValue(), true );
232 output_list.push_back( tmp );
236 // no <prop> elements, text node of <output> is property name
238 output_list.push_back( fgGetNode(child->getStringValue(), true ) );
239 } else if ( cname == "config" ) {
241 } else if ( cname == "min" ) {
242 uminInput.push_back( new FGXMLAutoInput( child ) );
243 } else if ( cname == "u_min" ) {
244 uminInput.push_back( new FGXMLAutoInput( child ) );
245 } else if ( cname == "max" ) {
246 umaxInput.push_back( new FGXMLAutoInput( child ) );
247 } else if ( cname == "u_max" ) {
248 umaxInput.push_back( new FGXMLAutoInput( child ) );
250 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized node:"
251 << cname << " in section " << name);
252 throw sg_io_exception("XMLAuto: unrecognized component node:" + cname, "Section=" + name);
254 } // of top-level iteration
257 void FGXMLAutoComponent::parseConfig(SGPropertyNode* aConfig)
259 for (int i = 0; i < aConfig->nChildren(); ++i ) {
260 SGPropertyNode *child = aConfig->getChild(i);
261 string cname(child->getName());
263 if (parseConfigHook(cname, child)) {
264 // derived class handled it, fine
265 } else if ( cname == "min" ) {
266 uminInput.push_back( new FGXMLAutoInput( child ) );
267 } else if ( cname == "u_min" ) {
268 uminInput.push_back( new FGXMLAutoInput( child ) );
269 } else if ( cname == "max" ) {
270 umaxInput.push_back( new FGXMLAutoInput( child ) );
271 } else if ( cname == "u_max" ) {
272 umaxInput.push_back( new FGXMLAutoInput( child ) );
274 SG_LOG(SG_AUTOPILOT, SG_ALERT, "malformed autopilot definition - unrecognized config node:"
275 << cname << " in section " << name);
276 throw sg_io_exception("XMLAuto: unrecognized config node:" + cname, "Section=" + name);
278 } // of config iteration
281 bool FGXMLAutoComponent::parseNodeHook(const string& aName, SGPropertyNode* aNode)
286 bool FGXMLAutoComponent::parseConfigHook(const string& aName, SGPropertyNode* aNode)
291 bool FGXMLAutoComponent::isPropertyEnabled()
294 return _condition->test();
298 return *enable_value == enable_prop->getStringValue();
300 return enable_prop->getBoolValue();
306 void FGXMLAutoComponent::do_feedback_if_disabled()
308 if( output_list.size() > 0 ) {
309 FGXMLAutoInput * input = valueInput.get_active();
311 input->set_value( output_list[0]->getDoubleValue() );
315 double FGXMLAutoComponent::clamp( double value )
317 // clamp, if either min or max is defined
318 if( uminInput.size() + umaxInput.size() > 0 ) {
319 double d = umaxInput.get_value( 0.0 );
320 if( value > d ) value = d;
321 d = uminInput.get_value( 0.0 );
322 if( value < d ) value = d;
327 FGPIDController::FGPIDController( SGPropertyNode *node ):
328 FGXMLAutoComponent(),
342 bool FGPIDController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
345 desiredTs = aNode->getDoubleValue();
346 } else if (aName == "Kp") {
347 Kp.push_back( new FGXMLAutoInput(aNode) );
348 } else if (aName == "Ti") {
349 Ti.push_back( new FGXMLAutoInput(aNode) );
350 } else if (aName == "Td") {
351 Td.push_back( new FGXMLAutoInput(aNode) );
352 } else if (aName == "beta") {
353 beta = aNode->getDoubleValue();
354 } else if (aName == "alpha") {
355 alpha = aNode->getDoubleValue();
356 } else if (aName == "gamma") {
357 gamma = aNode->getDoubleValue();
359 // unhandled by us, let the base class try it
369 * Ok! Here is the PID controller algorithm that I would like to see
372 * delta_u_n = Kp * [ (ep_n - ep_n-1) + ((Ts/Ti)*e_n)
373 * + (Td/Ts)*(edf_n - 2*edf_n-1 + edf_n-2) ]
375 * u_n = u_n-1 + delta_u_n
379 * delta_u : The incremental output
380 * Kp : Proportional gain
381 * ep : Proportional error with reference weighing
384 * beta : Weighing factor
385 * r : Reference (setpoint)
386 * y : Process value, measured
389 * Ts : Sampling interval
390 * Ti : Integrator time
391 * Td : Derivator time
392 * edf : Derivate error with reference weighing and filtering
393 * edf_n = edf_n-1 / ((Ts/Tf) + 1) + ed_n * (Ts/Tf) / ((Ts/Tf) + 1)
396 * Tf = alpha * Td , where alpha usually is set to 0.1
397 * ed : Unfiltered derivate error with reference weighing
400 * gamma : Weighing factor
402 * u : absolute output
404 * Index n means the n'th value.
409 * y_n , r_n , beta=1 , gamma=0 , alpha=0.1 ,
410 * Kp , Ti , Td , Ts (is the sampling time available?)
417 void FGPIDController::update( double dt ) {
418 double ep_n; // proportional error with reference weighing
420 double ed_n; // derivative error
421 double edf_n; // derivative error filter
422 double Tf; // filter time
423 double delta_u_n = 0.0; // incremental output
424 double u_n = 0.0; // absolute output
425 double Ts; // sampling interval (sec)
427 double u_min = uminInput.get_value();
428 double u_max = umaxInput.get_value();
431 if ( elapsedTime <= desiredTs ) {
432 // do nothing if time step is not positive (i.e. no time has
439 if ( isPropertyEnabled() ) {
441 // first time being enabled, seed u_n with current
442 // property tree value
443 u_n = get_output_value();
452 if ( enabled && Ts > 0.0) {
453 if ( debug ) cout << "Updating " << get_name()
454 << " Ts " << Ts << endl;
456 double y_n = valueInput.get_value();
457 double r_n = referenceInput.get_value();
459 if ( debug ) cout << " input = " << y_n << " ref = " << r_n << endl;
461 // Calculates proportional error:
462 ep_n = beta * r_n - y_n;
463 if ( debug ) cout << " ep_n = " << ep_n;
464 if ( debug ) cout << " ep_n_1 = " << ep_n_1;
468 if ( debug ) cout << " e_n = " << e_n;
470 // Calculates derivate error:
471 ed_n = gamma * r_n - y_n;
472 if ( debug ) cout << " ed_n = " << ed_n;
474 double td = Td.get_value();
476 // Calculates filter time:
478 if ( debug ) cout << " Tf = " << Tf;
480 // Filters the derivate error:
481 edf_n = edf_n_1 / (Ts/Tf + 1)
482 + ed_n * (Ts/Tf) / (Ts/Tf + 1);
483 if ( debug ) cout << " edf_n = " << edf_n;
488 // Calculates the incremental output:
489 double ti = Ti.get_value();
491 delta_u_n = Kp.get_value() * ( (ep_n - ep_n_1)
493 + ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2)) );
497 cout << " delta_u_n = " << delta_u_n << endl;
498 cout << "P:" << Kp.get_value() * (ep_n - ep_n_1)
499 << " I:" << Kp.get_value() * ((Ts/ti) * e_n)
500 << " D:" << Kp.get_value() * ((td/Ts) * (edf_n - 2*edf_n_1 + edf_n_2))
504 // Integrator anti-windup logic:
505 if ( delta_u_n > (u_max - u_n_1) ) {
506 delta_u_n = u_max - u_n_1;
507 if ( debug ) cout << " max saturation " << endl;
508 } else if ( delta_u_n < (u_min - u_n_1) ) {
509 delta_u_n = u_min - u_n_1;
510 if ( debug ) cout << " min saturation " << endl;
513 // Calculates absolute output:
514 u_n = u_n_1 + delta_u_n;
515 if ( debug ) cout << " output = " << u_n << endl;
517 // Updates indexed values;
523 set_output_value( u_n );
524 } else if ( !enabled ) {
527 // Updates indexed values;
536 FGPISimpleController::FGPISimpleController( SGPropertyNode *node ):
537 FGXMLAutoComponent(),
543 bool FGPISimpleController::parseConfigHook(const string& aName, SGPropertyNode* aNode)
546 Kp.push_back( new FGXMLAutoInput(aNode) );
547 } else if (aName == "Ki") {
548 Ki.push_back( new FGXMLAutoInput(aNode) );
550 // unhandled by us, let the base class try it
557 void FGPISimpleController::update( double dt ) {
559 if ( isPropertyEnabled() ) {
561 // we have just been enabled, zero out int_sum
571 if ( debug ) cout << "Updating " << get_name() << endl;
572 double y_n = valueInput.get_value();
573 double r_n = referenceInput.get_value();
575 double error = r_n - y_n;
576 if ( debug ) cout << "input = " << y_n
577 << " reference = " << r_n
578 << " error = " << error
581 double prop_comp = error * Kp.get_value();
582 int_sum += error * Ki.get_value() * dt;
585 if ( debug ) cout << "prop_comp = " << prop_comp
586 << " int_sum = " << int_sum << endl;
588 double output = prop_comp + int_sum;
589 output = clamp( output );
590 set_output_value( output );
591 if ( debug ) cout << "output = " << output << endl;
596 FGPredictor::FGPredictor ( SGPropertyNode *node ):
597 FGXMLAutoComponent(),
603 bool FGPredictor::parseNodeHook(const string& aName, SGPropertyNode* aNode)
605 if (aName == "seconds") {
606 seconds.push_back( new FGXMLAutoInput( aNode, 0 ) );
607 } else if (aName == "filter-gain") {
608 filter_gain.push_back( new FGXMLAutoInput( aNode, 0 ) );
616 void FGPredictor::update( double dt ) {
618 Simple moving average filter converts input value to predicted value "seconds".
620 Smoothing as described by Curt Olson:
621 gain would be valid in the range of 0 - 1.0
622 1.0 would mean no filtering.
623 0.0 would mean no input.
624 0.5 would mean (1 part past value + 1 part current value) / 2
625 0.1 would mean (9 parts past value + 1 part current value) / 10
626 0.25 would mean (3 parts past value + 1 part current value) / 4
630 double ivalue = valueInput.get_value();
632 if ( isPropertyEnabled() ) {
634 // first time being enabled
646 double current = (ivalue - last_value)/dt; // calculate current error change (per second)
647 average = dt < 1.0 ? ((1.0 - dt) * average + current * dt) : current;
649 // calculate output with filter gain adjustment
650 double output = ivalue +
651 (1.0 - filter_gain.get_value()) * (average * seconds.get_value()) +
652 filter_gain.get_value() * (current * seconds.get_value());
653 output = clamp( output );
654 set_output_value( output );
661 FGDigitalFilter::FGDigitalFilter(SGPropertyNode *node):
662 FGXMLAutoComponent(),
667 output.resize(2, 0.0);
668 input.resize(samplesInput.get_value() + 1, 0.0);
672 bool FGDigitalFilter::parseNodeHook(const string& aName, SGPropertyNode* aNode)
674 if (aName == "type" ) {
675 string val(aNode->getStringValue());
676 if ( val == "exponential" ) {
677 filterType = exponential;
678 } else if (val == "double-exponential") {
679 filterType = doubleExponential;
680 } else if (val == "moving-average") {
681 filterType = movingAverage;
682 } else if (val == "noise-spike") {
683 filterType = noiseSpike;
684 } else if (val == "gain") {
686 } else if (val == "reciprocal") {
687 filterType = reciprocal;
689 } else if (aName == "filter-time" ) {
690 TfInput.push_back( new FGXMLAutoInput( aNode, 1.0 ) );
691 if( filterType == none ) filterType = exponential;
692 } else if (aName == "samples" ) {
693 samplesInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
694 if( filterType == none ) filterType = movingAverage;
695 } else if (aName == "max-rate-of-change" ) {
696 rateOfChangeInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
697 if( filterType == none ) filterType = noiseSpike;
698 } else if (aName == "gain" ) {
699 gainInput.push_back( new FGXMLAutoInput( aNode, 1 ) );
700 if( filterType == none ) filterType = gain;
702 return false; // not handled by us, let the base class try
708 void FGDigitalFilter::update(double dt)
710 if ( isPropertyEnabled() ) {
712 input.push_front(valueInput.get_value());
713 input.resize(samplesInput.get_value() + 1, 0.0);
716 // first time being enabled, initialize output to the
717 // value of the output property to avoid bumping.
718 output.push_front(get_output_value());
727 if ( enabled && dt > 0.0 ) {
731 * Output[n] = alpha*Input[n] + (1-alpha)*Output[n-1]
734 if( debug ) cout << "Updating " << get_name()
735 << " dt " << dt << endl;
737 if (filterType == exponential)
739 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
740 output.push_front(alpha * input[0] +
741 (1 - alpha) * output[0]);
743 else if (filterType == doubleExponential)
745 double alpha = 1 / ((TfInput.get_value()/dt) + 1);
746 output.push_front(alpha * alpha * input[0] +
747 2 * (1 - alpha) * output[0] -
748 (1 - alpha) * (1 - alpha) * output[1]);
750 else if (filterType == movingAverage)
752 output.push_front(output[0] +
753 (input[0] - input.back()) / samplesInput.get_value());
755 else if (filterType == noiseSpike)
757 double maxChange = rateOfChangeInput.get_value() * dt;
759 if ((output[0] - input[0]) > maxChange)
761 output.push_front(output[0] - maxChange);
763 else if ((output[0] - input[0]) < -maxChange)
765 output.push_front(output[0] + maxChange);
767 else if (fabs(input[0] - output[0]) <= maxChange)
769 output.push_front(input[0]);
772 else if (filterType == gain)
774 output[0] = gainInput.get_value() * input[0];
776 else if (filterType == reciprocal)
778 if (input[0] != 0.0) {
779 output[0] = gainInput.get_value() / input[0];
783 output[0] = clamp(output[0]) ;
784 set_output_value( output[0] );
790 cout << "input:" << input[0]
791 << "\toutput:" << output[0] << endl;
796 FGXMLAutopilotGroup::FGXMLAutopilotGroup()
800 void FGXMLAutopilotGroup::reinit()
802 for( vector<string>::size_type i = 0; i < _autopilotNames.size(); i++ ) {
803 FGXMLAutopilot * ap = (FGXMLAutopilot*)get_subsystem( _autopilotNames[i] );
804 if( ap == NULL ) continue; // ?
805 remove_subsystem( _autopilotNames[i] );
808 _autopilotNames.clear();
812 void FGXMLAutopilotGroup::init()
814 vector<SGPropertyNode_ptr> autopilotNodes = fgGetNode( "/sim/systems", true )->getChildren("autopilot");
815 if( autopilotNodes.size() == 0 ) {
816 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration specified for this model!");
820 for( vector<SGPropertyNode_ptr>::size_type i = 0; i < autopilotNodes.size(); i++ ) {
821 SGPropertyNode_ptr pathNode = autopilotNodes[i]->getNode( "path" );
822 if( pathNode == NULL ) {
823 SG_LOG( SG_ALL, SG_WARN, "No autopilot configuration file specified for this autopilot!");
828 SGPropertyNode_ptr nameNode = autopilotNodes[i]->getNode( "name" );
829 if( nameNode != NULL ) {
830 apName = nameNode->getStringValue();
832 std::ostringstream buf;
833 buf << "unnamed_autopilot_" << i;
837 if( get_subsystem( apName.c_str() ) != NULL ) {
838 SG_LOG( SG_ALL, SG_ALERT, "Duplicate autopilot configuration name " << apName << " ignored" );
842 SGPath config( globals->get_fg_root() );
843 config.append( pathNode->getStringValue() );
845 SG_LOG( SG_ALL, SG_INFO, "Reading autopilot configuration from " << config.str() );
847 FGXMLAutopilot * ap = new FGXMLAutopilot;
849 SGPropertyNode_ptr root = new SGPropertyNode();
850 readProperties( config.str(), root );
853 if ( ! ap->build( root ) ) {
854 SG_LOG( SG_ALL, SG_ALERT,
855 "Detected an internal inconsistency in the autopilot configuration." << endl << " See earlier errors for details." );
859 } catch (const sg_exception& e) {
860 SG_LOG( SG_ALL, SG_ALERT, "Failed to load autopilot configuration: "
861 << config.str() << ":" << e.getMessage() );
866 SG_LOG( SG_ALL, SG_INFO, "adding autopilot subsystem " << apName );
867 set_subsystem( apName, ap );
868 _autopilotNames.push_back( apName );
871 SGSubsystemGroup::init();
874 FGXMLAutopilot::FGXMLAutopilot() {
878 FGXMLAutopilot::~FGXMLAutopilot() {
882 /* read all /sim/systems/autopilot[n]/path properties, try to read the file specified therein
883 * and configure/add the digital filters specified in that file
885 void FGXMLAutopilot::init()
890 void FGXMLAutopilot::reinit() {
896 void FGXMLAutopilot::bind() {
899 void FGXMLAutopilot::unbind() {
902 bool FGXMLAutopilot::build( SGPropertyNode_ptr config_props ) {
903 SGPropertyNode *node;
906 int count = config_props->nChildren();
907 for ( i = 0; i < count; ++i ) {
908 node = config_props->getChild(i);
909 string name = node->getName();
910 // cout << name << endl;
911 SG_LOG( SG_ALL, SG_INFO, "adding autopilot component " << name );
912 if ( name == "pid-controller" ) {
913 components.push_back( new FGPIDController( node ) );
914 } else if ( name == "pi-simple-controller" ) {
915 components.push_back( new FGPISimpleController( node ) );
916 } else if ( name == "predict-simple" ) {
917 components.push_back( new FGPredictor( node ) );
918 } else if ( name == "filter" ) {
919 components.push_back( new FGDigitalFilter( node ) );
921 SG_LOG( SG_ALL, SG_ALERT, "Unknown top level section: "
932 * Update helper values
934 static void update_helper( double dt ) {
935 // Estimate speed in 5,10 seconds
936 static SGPropertyNode_ptr vel = fgGetNode( "/velocities/airspeed-kt", true );
937 static SGPropertyNode_ptr lookahead5
938 = fgGetNode( "/autopilot/internal/lookahead-5-sec-airspeed-kt", true );
939 static SGPropertyNode_ptr lookahead10
940 = fgGetNode( "/autopilot/internal/lookahead-10-sec-airspeed-kt", true );
942 static double average = 0.0; // average/filtered prediction
943 static double v_last = 0.0; // last velocity
945 double v = vel->getDoubleValue();
948 a = (v - v_last) / dt;
951 average = (1.0 - dt) * average + dt * a;
956 lookahead5->setDoubleValue( v + average * 5.0 );
957 lookahead10->setDoubleValue( v + average * 10.0 );
961 // Calculate heading bug error normalized to +/- 180.0 (based on
962 // DG indicated heading)
963 static SGPropertyNode_ptr bug
964 = fgGetNode( "/autopilot/settings/heading-bug-deg", true );
965 static SGPropertyNode_ptr ind_hdg
966 = fgGetNode( "/instrumentation/heading-indicator/indicated-heading-deg",
968 static SGPropertyNode_ptr ind_bug_error
969 = fgGetNode( "/autopilot/internal/heading-bug-error-deg", true );
971 double diff = bug->getDoubleValue() - ind_hdg->getDoubleValue();
972 if ( diff < -180.0 ) { diff += 360.0; }
973 if ( diff > 180.0 ) { diff -= 360.0; }
974 ind_bug_error->setDoubleValue( diff );
976 // Calculate heading bug error normalized to +/- 180.0 (based on
977 // actual/nodrift magnetic-heading, i.e. a DG slaved to magnetic
979 static SGPropertyNode_ptr mag_hdg
980 = fgGetNode( "/orientation/heading-magnetic-deg", true );
981 static SGPropertyNode_ptr fdm_bug_error
982 = fgGetNode( "/autopilot/internal/fdm-heading-bug-error-deg", true );
984 diff = bug->getDoubleValue() - mag_hdg->getDoubleValue();
985 if ( diff < -180.0 ) { diff += 360.0; }
986 if ( diff > 180.0 ) { diff -= 360.0; }
987 fdm_bug_error->setDoubleValue( diff );
989 // Calculate true heading error normalized to +/- 180.0
990 static SGPropertyNode_ptr target_true
991 = fgGetNode( "/autopilot/settings/true-heading-deg", true );
992 static SGPropertyNode_ptr true_hdg
993 = fgGetNode( "/orientation/heading-deg", true );
994 static SGPropertyNode_ptr true_track
995 = fgGetNode( "/instrumentation/gps/indicated-track-true-deg", true );
996 static SGPropertyNode_ptr true_error
997 = fgGetNode( "/autopilot/internal/true-heading-error-deg", true );
999 diff = target_true->getDoubleValue() - true_hdg->getDoubleValue();
1000 if ( diff < -180.0 ) { diff += 360.0; }
1001 if ( diff > 180.0 ) { diff -= 360.0; }
1002 true_error->setDoubleValue( diff );
1004 // Calculate nav1 target heading error normalized to +/- 180.0
1005 static SGPropertyNode_ptr target_nav1
1006 = fgGetNode( "/instrumentation/nav[0]/radials/target-auto-hdg-deg", true );
1007 static SGPropertyNode_ptr true_nav1
1008 = fgGetNode( "/autopilot/internal/nav1-heading-error-deg", true );
1009 static SGPropertyNode_ptr true_track_nav1
1010 = fgGetNode( "/autopilot/internal/nav1-track-error-deg", true );
1012 diff = target_nav1->getDoubleValue() - true_hdg->getDoubleValue();
1013 if ( diff < -180.0 ) { diff += 360.0; }
1014 if ( diff > 180.0 ) { diff -= 360.0; }
1015 true_nav1->setDoubleValue( diff );
1017 diff = target_nav1->getDoubleValue() - true_track->getDoubleValue();
1018 if ( diff < -180.0 ) { diff += 360.0; }
1019 if ( diff > 180.0 ) { diff -= 360.0; }
1020 true_track_nav1->setDoubleValue( diff );
1022 // Calculate nav1 selected course error normalized to +/- 180.0
1023 // (based on DG indicated heading)
1024 static SGPropertyNode_ptr nav1_course_error
1025 = fgGetNode( "/autopilot/internal/nav1-course-error", true );
1026 static SGPropertyNode_ptr nav1_selected_course
1027 = fgGetNode( "/instrumentation/nav[0]/radials/selected-deg", true );
1029 diff = nav1_selected_course->getDoubleValue() - ind_hdg->getDoubleValue();
1030 // if ( diff < -180.0 ) { diff += 360.0; }
1031 // if ( diff > 180.0 ) { diff -= 360.0; }
1032 SG_NORMALIZE_RANGE( diff, -180.0, 180.0 );
1033 nav1_course_error->setDoubleValue( diff );
1035 // Calculate vertical speed in fpm
1036 static SGPropertyNode_ptr vs_fps
1037 = fgGetNode( "/velocities/vertical-speed-fps", true );
1038 static SGPropertyNode_ptr vs_fpm
1039 = fgGetNode( "/autopilot/internal/vert-speed-fpm", true );
1041 vs_fpm->setDoubleValue( vs_fps->getDoubleValue() * 60.0 );
1044 // Calculate static port pressure rate in [inhg/s].
1045 // Used to determine vertical speed.
1046 static SGPropertyNode_ptr static_pressure
1047 = fgGetNode( "/systems/static[0]/pressure-inhg", true );
1048 static SGPropertyNode_ptr pressure_rate
1049 = fgGetNode( "/autopilot/internal/pressure-rate", true );
1051 static double last_static_pressure = 0.0;
1054 double current_static_pressure = static_pressure->getDoubleValue();
1056 double current_pressure_rate =
1057 ( current_static_pressure - last_static_pressure ) / dt;
1059 pressure_rate->setDoubleValue(current_pressure_rate);
1061 last_static_pressure = current_static_pressure;
1068 * Update the list of autopilot components
1071 void FGXMLAutopilot::update( double dt ) {
1072 update_helper( dt );
1075 for ( i = 0; i < components.size(); ++i ) {
1076 components[i]->update( dt );