1 // xmlauto.hxx - 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.
25 #define _XMLAUTO_HXX 1
29 I'd like to deprecate the so called autopilot helper function
30 (which is now part of the AutopilotGroup::update() method).
31 Every property calculated within this helper can be calculated
32 using filters defined in an external autopilot definition file.
33 The complete set of calculations may be extracted into a separate
34 configuration file. The current implementation is able to hande
35 multiple config files and autopilots. The helper doubles code
36 and writes properties used only by a few aircraft.
38 // FIXME: this should go into config.h and/or configure
39 // or removed along with the "helper" one day.
40 #define XMLAUTO_USEHELPER
42 #include <simgear/compiler.h>
48 #include <simgear/props/props.hxx>
49 #include <simgear/structure/subsystem_mgr.hxx>
50 #include <simgear/props/condition.hxx>
52 typedef SGSharedPtr<class FGXMLAutoInput> FGXMLAutoInput_ptr;
53 typedef SGSharedPtr<class FGPeriodicalValue> FGPeriodicalValue_ptr;
55 class FGPeriodicalValue : public SGReferenced {
57 FGXMLAutoInput_ptr minPeriod; // The minimum value of the period
58 FGXMLAutoInput_ptr maxPeriod; // The maximum value of the period
60 FGPeriodicalValue( SGPropertyNode_ptr node );
61 double normalize( double value );
64 class FGXMLAutoInput : public SGReferenced {
66 double value; // The value as a constant or initializer for the property
67 bool abs; // return absolute value
68 SGPropertyNode_ptr property; // The name of the property containing the value
69 FGXMLAutoInput_ptr offset; // A fixed offset, defaults to zero
70 FGXMLAutoInput_ptr scale; // A constant scaling factor defaults to one
71 FGXMLAutoInput_ptr min; // A minimum clip defaults to no clipping
72 FGXMLAutoInput_ptr max; // A maximum clip defaults to no clipping
73 FGPeriodicalValue_ptr periodical; //
74 SGSharedPtr<const SGCondition> _condition;
77 FGXMLAutoInput( SGPropertyNode_ptr node = NULL, double value = 0.0, double offset = 0.0, double scale = 1.0 );
79 void parse( SGPropertyNode_ptr, double value = 0.0, double offset = 0.0, double scale = 1.0 );
81 /* get the value of this input, apply scale and offset and clipping */
84 /* set the input value after applying offset and scale */
85 void set_value( double value );
87 inline double get_scale() {
88 return scale == NULL ? 1.0 : scale->get_value();
91 inline double get_offset() {
92 return offset == NULL ? 0.0 : offset->get_value();
95 inline bool is_enabled() {
96 return _condition == NULL ? true : _condition->test();
101 class FGXMLAutoInputList : public std::vector<FGXMLAutoInput_ptr> {
103 FGXMLAutoInput_ptr get_active() {
104 for (iterator it = begin(); it != end(); ++it) {
105 if( (*it)->is_enabled() )
111 double get_value( double def = 0.0 ) {
112 FGXMLAutoInput_ptr input = get_active();
113 return input == NULL ? def : input->get_value();
119 * Base class for other autopilot components
122 class FGXMLAutoComponent : public SGReferenced {
125 simgear::PropertyList output_list;
127 SGSharedPtr<const SGCondition> _condition;
128 SGPropertyNode_ptr enable_prop;
129 std::string * enable_value;
131 SGPropertyNode_ptr passive_mode;
136 /* Feed back output property to input property if
137 this filter is disabled. This is for multi-stage
138 filter where one filter sits behind a pid-controller
139 to provide changes of the overall output to the pid-
141 feedback is disabled by default.
143 bool feedback_if_disabled;
144 void do_feedback_if_disabled();
147 FGXMLAutoComponent();
150 * Parse a component specification read from a property-list.
151 * Calls the hook methods below to allow derived classes to
152 * specialise parsing bevaiour.
154 void parseNode(SGPropertyNode* aNode);
157 * Helper to parse the config section
159 void parseConfig(SGPropertyNode* aConfig);
162 * Over-rideable hook method to allow derived classes to refine top-level
163 * node parsing. Return true if the node was handled, false otherwise.
165 virtual bool parseNodeHook(const std::string& aName, SGPropertyNode* aNode);
168 * Over-rideable hook method to allow derived classes to refine config
169 * node parsing. Return true if the node was handled, false otherwise.
171 virtual bool parseConfigHook(const std::string& aName, SGPropertyNode* aNode);
173 FGXMLAutoInputList valueInput;
174 FGXMLAutoInputList referenceInput;
175 FGXMLAutoInputList uminInput;
176 FGXMLAutoInputList umaxInput;
177 FGPeriodicalValue_ptr periodical;
183 inline void do_feedback() {
184 if( feedback_if_disabled ) do_feedback_if_disabled();
189 virtual ~FGXMLAutoComponent();
191 virtual void update (double dt)=0;
193 inline const std::string& get_name() { return name; }
195 double clamp( double value );
197 inline void set_output_value( double value ) {
198 // passive_ignore == true means that we go through all the
199 // motions, but drive the outputs. This is analogous to
200 // running the autopilot with the "servos" off. This is
201 // helpful for things like flight directors which position
202 // their vbars from the autopilot computations.
203 if ( honor_passive && passive_mode->getBoolValue() ) return;
204 for( simgear::PropertyList::iterator it = output_list.begin();
205 it != output_list.end(); ++it)
206 (*it)->setDoubleValue( clamp( value ) );
209 inline void set_output_value( bool value ) {
210 // passive_ignore == true means that we go through all the
211 // motions, but drive the outputs. This is analogous to
212 // running the autopilot with the "servos" off. This is
213 // helpful for things like flight directors which position
214 // their vbars from the autopilot computations.
215 if ( honor_passive && passive_mode->getBoolValue() ) return;
216 for( simgear::PropertyList::iterator it = output_list.begin();
217 it != output_list.end(); ++it)
218 (*it)->setBoolValue( value ); // don't use clamp here, bool is clamped anyway
221 inline double get_output_value() {
222 return output_list.size() == 0 ? 0.0 : clamp(output_list[0]->getDoubleValue());
226 Returns true if the enable-condition is true.
228 If a <condition> is defined, this condition is evaluated,
229 <prop> and <value> tags are ignored.
231 If a <prop> is defined and no <value> is defined, the property
232 named in the <prop></prop> tags is evaluated as boolean.
234 If a <prop> is defined a a <value> is defined, the property named
235 in <prop></prop> is compared (as a string) to the value defined in
238 Returns true, if neither <condition> nor <prop> exists
241 Using a <condition> tag
244 <!-- any legal condition goes here and is evaluated -->
246 <prop>This is ignored</prop>
247 <value>This is also ignored</value>
250 Using a single boolean property
252 <prop>/some/property/that/is/evaluated/as/boolean</prop>
255 Using <prop> == <value>
256 This is the old style behaviour
258 <prop>/only/true/if/this/equals/true</prop>
262 bool isPropertyEnabled();
265 typedef SGSharedPtr<FGXMLAutoComponent> FGXMLAutoComponent_ptr;
269 * Roy Ovesen's PID controller
272 class FGPIDController : public FGXMLAutoComponent {
277 // Configuration values
278 FGXMLAutoInputList Kp; // proportional gain
279 FGXMLAutoInputList Ti; // Integrator time (sec)
280 FGXMLAutoInputList Td; // Derivator time (sec)
282 double alpha; // low pass filter weighing factor (usually 0.1)
283 double beta; // process value weighing factor for
284 // calculating proportional error
286 double gamma; // process value weighing factor for
287 // calculating derivative error
290 // Previous state tracking values
291 double ep_n_1; // ep[n-1] (prop error)
292 double edf_n_1; // edf[n-1] (derivative error)
293 double edf_n_2; // edf[n-2] (derivative error)
294 double u_n_1; // u[n-1] (output)
295 double desiredTs; // desired sampling interval (sec)
296 double elapsedTime; // elapsed time (sec)
300 bool parseConfigHook(const std::string& aName, SGPropertyNode* aNode);
304 FGPIDController( SGPropertyNode *node );
305 FGPIDController( SGPropertyNode *node, bool old );
306 ~FGPIDController() {}
308 void update( double dt );
313 * A simplistic P [ + I ] PID controller
316 class FGPISimpleController : public FGXMLAutoComponent {
320 // proportional component data
321 FGXMLAutoInputList Kp;
323 // integral component data
324 FGXMLAutoInputList Ki;
328 bool parseConfigHook(const std::string& aName, SGPropertyNode* aNode);
332 FGPISimpleController( SGPropertyNode *node );
333 ~FGPISimpleController() {}
335 void update( double dt );
340 * Predictor - calculates value in x seconds future.
343 class FGPredictor : public FGXMLAutoComponent {
348 FGXMLAutoInputList seconds;
349 FGXMLAutoInputList filter_gain;
352 bool parseNodeHook(const std::string& aName, SGPropertyNode* aNode);
355 FGPredictor( SGPropertyNode *node );
358 void update( double dt );
363 * FGDigitalFilter - a selection of digital filters
366 * Double exponential filter
367 * Moving average filter
370 * All these filters are low-pass filters.
374 class FGDigitalFilter : public FGXMLAutoComponent
377 FGXMLAutoInputList samplesInput; // Number of input samples to average
378 FGXMLAutoInputList rateOfChangeInput; // The maximum allowable rate of change [1/s]
379 FGXMLAutoInputList gainInput; //
380 FGXMLAutoInputList TfInput; // Filter time [s]
382 std::deque <double> output;
383 std::deque <double> input;
384 enum filterTypes { exponential, doubleExponential, movingAverage,
385 noiseSpike, gain, reciprocal, differential, none };
386 filterTypes filterType;
389 bool parseNodeHook(const std::string& aName, SGPropertyNode* aNode);
392 FGDigitalFilter(SGPropertyNode *node);
393 ~FGDigitalFilter() {}
395 void update(double dt);
398 class FGXMLAutoLogic : public FGXMLAutoComponent
401 SGSharedPtr<SGCondition> input;
405 bool parseNodeHook(const std::string& aName, SGPropertyNode* aNode);
408 FGXMLAutoLogic(SGPropertyNode * node );
411 void update(double dt);
415 * Model an autopilot system.
419 class FGXMLAutopilotGroup : public SGSubsystemGroup
422 FGXMLAutopilotGroup();
425 void update( double dt );
427 std::vector<std::string> _autopilotNames;
429 #ifdef XMLAUTO_USEHELPER
432 double last_static_pressure;
434 SGPropertyNode_ptr vel;
435 SGPropertyNode_ptr lookahead5;
436 SGPropertyNode_ptr lookahead10;
437 SGPropertyNode_ptr bug;
438 SGPropertyNode_ptr mag_hdg;
439 SGPropertyNode_ptr bug_error;
440 SGPropertyNode_ptr fdm_bug_error;
441 SGPropertyNode_ptr target_true;
442 SGPropertyNode_ptr true_hdg;
443 SGPropertyNode_ptr true_error;
444 SGPropertyNode_ptr target_nav1;
445 SGPropertyNode_ptr true_nav1;
446 SGPropertyNode_ptr true_track_nav1;
447 SGPropertyNode_ptr nav1_course_error;
448 SGPropertyNode_ptr nav1_selected_course;
449 SGPropertyNode_ptr vs_fps;
450 SGPropertyNode_ptr vs_fpm;
451 SGPropertyNode_ptr static_pressure;
452 SGPropertyNode_ptr pressure_rate;
453 SGPropertyNode_ptr track;
457 class FGXMLAutopilot : public SGSubsystem
469 void update( double dt );
472 bool build( SGPropertyNode_ptr );
474 typedef std::vector<FGXMLAutoComponent_ptr> comp_list;
478 comp_list components;
483 #endif // _XMLAUTO_HXX