Branch data Line data Source code
1 : : /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
2 : :
3 : : Header: FGRotor.h
4 : : Author: T. Kreitler
5 : : Date started: 08/24/00
6 : :
7 : : ------------- Copyright (C) 2010 T. Kreitler -------------
8 : :
9 : : This program is free software; you can redistribute it and/or modify it under
10 : : the terms of the GNU Lesser General Public License as published by the Free Software
11 : : Foundation; either version 2 of the License, or (at your option) any later
12 : : version.
13 : :
14 : : This program is distributed in the hope that it will be useful, but WITHOUT
15 : : ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
16 : : FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more
17 : : details.
18 : :
19 : : You should have received a copy of the GNU Lesser General Public License along with
20 : : this program; if not, write to the Free Software Foundation, Inc., 59 Temple
21 : : Place - Suite 330, Boston, MA 02111-1307, USA.
22 : :
23 : : Further information about the GNU Lesser General Public License can also be found on
24 : : the world wide web at http://www.gnu.org.
25 : :
26 : : HISTORY
27 : : --------------------------------------------------------------------------------
28 : : 01/01/10 T.Kreitler test implementation
29 : :
30 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
31 : : SENTRY
32 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
33 : :
34 : : #ifndef FGROTOR_H
35 : : #define FGROTOR_H
36 : :
37 : : /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
38 : : INCLUDES
39 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
40 : :
41 : : #include "FGThruster.h"
42 : : #include "math/FGTable.h"
43 : : #include "math/FGRungeKutta.h"
44 : :
45 : : /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
46 : : DEFINITIONS
47 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
48 : :
49 : : #define ID_ROTOR "$Id: FGRotor.h,v 1.6 2010/06/02 04:05:13 jberndt Exp $"
50 : :
51 : : /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
52 : : FORWARD DECLARATIONS
53 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
54 : :
55 : : namespace JSBSim {
56 : :
57 : : /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
58 : : CLASS DOCUMENTATION
59 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
60 : :
61 : : /** Models a rotor system. The default configuration consists of main and
62 : : tail rotor. A practical way to define the positions is to start with an
63 : : imaginary gear-box near the cg of the vehicle.
64 : :
65 : : In this case the location in the thruster definition should be
66 : : approximately equal to the cg defined in the <tt>fdm_config/mass_balance</tt>
67 : : section. If the default orientation (roll=pitch=yaw=0) is used the
68 : : positions of the rotor hubs are now defined relative to the location
69 : : of the thruster (i.e. the cg-centered body coordinate system).
70 : :
71 : :
72 : : <h3>Configuration File Format:</h3>
73 : : @code
74 : : <rotor name="{string}" variant="{string}">
75 : : <diameter unit="{LENGTH}"> {number} </diameter>
76 : : <numblades> {number} </numblades>
77 : : <xhub unit="{LENGTH}"> {number} </xhub>
78 : : <zhub unit="{LENGTH}"> {number} </zhub>
79 : : <nominalrpm> {number} </nominalrpm>
80 : : <minrpm> {number} </minrpm>
81 : : <chord unit="{LENGTH}"> {number} </chord>
82 : : <liftcurveslope Xunit="1/RAD"> {number} </liftcurveslope>
83 : : <flappingmoment unit="{MOMENT}"> {number} </flappingmoment>
84 : : <twist unit="{ANGLE}"> {number} </twist>
85 : : <massmoment Xunit="SLUG*FT"> {number} </massmoment>
86 : : <tiplossfactor> {number} </tiplossfactor>
87 : : <polarmoment unit="{MOMENT}"> {number}</polarmoment>
88 : : <inflowlag> {number} </inflowlag>
89 : : <shafttilt unit="{ANGLE}"> {number} </shafttilt>
90 : : <hingeoffset unit="{LENGTH}"> {number} </hingeoffset>
91 : : <tailrotor>
92 : : <diameter unit="{LENGTH}"> {number} </diameter>
93 : : <numblades> {number} </numblades>
94 : : <xhub unit="{LENGTH}">{number} </xhub>
95 : : <zhub unit="{LENGTH}">{number} </zhub>
96 : : <nominalrpm> {number} </nominalrpm>
97 : : <chord unit="{LENGTH}"> {number} </chord>
98 : : <liftcurveslope Xunit="1/RAD"> {number} </liftcurveslope>
99 : : <flappingmoment unit="{MOMENT}"> {number} </flappingmoment>
100 : : <twist unit="RAD"> {number} </twist>
101 : : <massmoment Xunit="SLUG*FT"> {number} </massmoment>
102 : : <tiplossfactor> {number} </tiplossfactor>
103 : : <inflowlag> {number} </inflowlag>
104 : : <hingeoffset unit="{LENGTH}"> {number} </hingeoffset>
105 : : <cantangle unit="{ANGLE}"> {number} </cantangle>
106 : : </tailrotor>
107 : : <cgroundeffect> {number} </cgroundeffect>
108 : : <groundeffectshift unit="{LENGTH}"> {number} </groundeffectshift>
109 : : </rotor>
110 : :
111 : : // LENGTH means any of the supported units, same for ANGLE and MOMENT.
112 : : // Xunit-attributes are a hint for currently unsupported units, so
113 : : // values must be provided accordingly.
114 : :
115 : : @endcode
116 : :
117 : : <h3>Configuration Parameters:</h3>
118 : :
119 : : Brief description and the symbol frequently found in the literature.
120 : :
121 : : <pre>
122 : : \<diameter> - Rotor disk diameter (R).
123 : : \<numblades> - Number of blades (b).
124 : : \<xhub> - Relative height in body coordinate system, thus usually negative.
125 : : \<zhub> - Relative distance in body coordinate system, close to zero
126 : : for main rotor, and usually negative for the tail rotor.
127 : : \<nominalrpm> - RPM at which the rotor usally operates.
128 : : \<minrpm> - Lowest RPM generated by the code, optional.
129 : : \<chord> - Blade chord, (c).
130 : : \<liftcurveslope> - Slope of curve of section lift against section angle of attack,
131 : : per rad (a).
132 : : \<flappingmoment> - Flapping moment of inertia (I_b).
133 : : \<twist> - Blade twist from root to tip, (theta_1).
134 : : \<massmoment> - Blade mass moment. (Biege/Widerstands-moment)
135 : : \<tiplossfactor> - Tip-loss factor. The Blade fraction that produces lift.
136 : : Value usually ranges between 0.95 - 1.0, optional (B).
137 : : \<polarmoment> - Moment of inertia for the whole rotor disk, optional.
138 : : \<inflowlag> - Rotor inflow time constant, sec.
139 : : \<shafttilt> - Orientation of the rotor shaft, negative angles define
140 : : a 'forward' tilt. Used by main rotor, optional.
141 : : \<hingeoffset> - Rotor flapping-hinge offset (e).
142 : :
143 : : Experimental properties
144 : :
145 : : \<cantangle> - Flapping hinge cantangle used by tail rotor, optional.
146 : : \<cgroundeffect> - Parameter for exponent in ground effect approximation. Value should
147 : : be in the range 0.2 - 0.35, 0.0 disables, optional.
148 : : \<groundeffectshift> - Further adjustment of ground effect.
149 : :
150 : : </pre>
151 : :
152 : : <h3>Notes:</h3>
153 : :
154 : : The behavior of the rotor is controlled/influenced by 5 inputs.<ul>
155 : : <li> The power provided by the engine. This is handled by the regular engine controls.</li>
156 : : <li> The collective control input. This is read from the <tt>fdm</tt> property
157 : : <tt>propulsion/engine[x]/collective-ctrl-rad</tt>.</li>
158 : : <li> The lateral cyclic input. Read from
159 : : <tt>propulsion/engine[x]/lateral-ctrl-rad</tt>.</li>
160 : : <li> The longitudinal cyclic input. Read from
161 : : <tt>propulsion/engine[x]/longitudinal-ctrl-rad</tt>.</li>
162 : : <li> The tail collective (aka antitorque, aka pedal) control input. Read from
163 : : <tt>propulsion/engine[x]/antitorque-ctrl-rad</tt>.</li>
164 : :
165 : : </ul>
166 : :
167 : : In order to keep the rotor speed constant, use of a RPM-Governor system is encouraged.
168 : :
169 : : It is possible to use different orientation/locations for the rotor system, but then xhub
170 : : and zhub are no longer aligned to the body frame and need proper recalculation.
171 : :
172 : : To model a standalone main rotor just omit the <tailrotor/> element. If you provide
173 : : a plain <tailrotor/> element all tail rotor parameters are estimated.
174 : :
175 : : The 'sense' parameter from the thruster is interpreted as follows, sense=1 means
176 : : counter clockwise rotation of the main rotor, as viewed from above. This is as a far
177 : : as I know more popular than clockwise rotation, which is defined by setting sense to
178 : : -1 (to be honest, I'm just 99.9% sure that the orientation is handled properly).
179 : :
180 : : Concerning coaxial designs: By providing the 'variant' attribute with value 'coaxial'
181 : : a Kamov-style rotor is modeled - i.e. the rotor produces no torque.
182 : :
183 : :
184 : : <h3>References:</h3>
185 : :
186 : : <dl>
187 : : <dt>/SH79/</dt><dd>Shaugnessy, J. D., Deaux, Thomas N., and Yenni, Kenneth R.,
188 : : "Development and Validation of a Piloted Simulation of a
189 : : Helicopter and External Sling Load", NASA TP-1285, 1979.</dd>
190 : : <dt>/BA41/</dt><dd>Bailey,F.J.,Jr., "A Simplified Theoretical Method of Determining
191 : : the Characteristics of a Lifting Rotor in Forward Flight", NACA Rep.716, 1941.</dd>
192 : : <dt>/AM50/</dt><dd>Amer, Kenneth B.,"Theory of Helicopter Damping in Pitch or Roll and a
193 : : Comparison With Flight Measurements", NACA TN-2136, 1950.</dd>
194 : : <dt>/TA77/</dt><dd>Talbot, Peter D., Corliss, Lloyd D., "A Mathematical Force and Moment
195 : : Model of a UH-1H Helicopter for Flight Dynamics Simulations", NASA TM-73,254, 1977.</dd>
196 : : </dl>
197 : :
198 : : @author Thomas Kreitler
199 : : @version $Id: FGRotor.h,v 1.6 2010/06/02 04:05:13 jberndt Exp $
200 : : */
201 : :
202 : : /*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
203 : : CLASS DECLARATION
204 : : %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
205 : :
206 : : class FGRotor : public FGThruster {
207 : :
208 : : enum eRotorFlags {eNone=0, eMain=1, eTail=2, eCoaxial=4, eRotCW=8} ;
209 : 0 : struct rotor {
210 : :
211 : : virtual ~rotor();
212 : : void zero();
213 : : void configure(int f, const rotor *xmain = NULL);
214 : :
215 : : // assist in parameter retrieval
216 : : double cnf_elem(const string& ename, double default_val=0.0, const string& unit = "", bool tell=false);
217 : : double cnf_elem(const string& ename, double default_val=0.0, bool tell=false);
218 : :
219 : : // rotor dynamics
220 : : void calc_flow_and_thrust(double dt, double rho, double theta_0, double Uw, double Ww, double flow_scale = 1.0);
221 : :
222 : : void calc_torque(double rho, double theta_0);
223 : : void calc_coning_angle(double rho, double theta_0);
224 : : void calc_flapping_angles(double rho, double theta_0, const FGColumnVector3 &pqr_fus_w);
225 : : void calc_drag_and_side_forces(double rho, double theta_0);
226 : :
227 : : // transformations
228 : : FGColumnVector3 hub_vel_body2ca( const FGColumnVector3 &uvw, const FGColumnVector3 &pqr,
229 : : double a_ic = 0.0 , double b_ic = 0.0 );
230 : : FGColumnVector3 fus_angvel_body2ca( const FGColumnVector3 &pqr);
231 : :
232 : : FGColumnVector3 body_forces(double a_ic = 0.0 , double b_ic = 0.0 );
233 : : FGColumnVector3 body_moments(FGColumnVector3 F_h, double a_ic = 0.0 , double b_ic = 0.0 );
234 : :
235 : : // bookkeeping
236 : : int flags ;
237 : : Element *parent ;
238 : :
239 : : // used in flow calculation
240 : : // FGRK4 rk ; // use this after checking
241 : : FGRKFehlberg rk ;
242 : : int reports ;
243 : :
244 : : // configuration parameters
245 : : double Radius ;
246 : : int BladeNum ;
247 : : double RelDistance_xhub ;
248 : : double RelShift_yhub ;
249 : : double RelHeight_zhub ;
250 : : double NominalRPM ;
251 : : double MinRPM ;
252 : : double BladeChord ;
253 : : double LiftCurveSlope ;
254 : : double BladeFlappingMoment ;
255 : : double BladeTwist ;
256 : : double BladeMassMoment ;
257 : : double TipLossB ;
258 : : double PolarMoment ;
259 : : double InflowLag ;
260 : : double ShaftTilt ;
261 : : double HingeOffset ;
262 : : double HingeOffset_hover ;
263 : : double CantAngleD3 ;
264 : :
265 : : double theta_shaft ;
266 : : double phi_shaft ;
267 : :
268 : : // derived parameters
269 : : double LockNumberByRho ;
270 : : double solidity ; // aka sigma
271 : : double RpmRatio ; // main_to_tail, hmm
272 : : double R[5] ; // Radius powers
273 : : double B[6] ; // TipLossB powers
274 : :
275 : : FGMatrix33 BodyToShaft ; // [S]T, see /SH79/ eqn(17,18)
276 : : FGMatrix33 ShaftToBody ; // [S]
277 : :
278 : : // dynamic values
279 : : double ActualRPM ;
280 : : double Omega ; // must be > 0
281 : : double beta_orient ;
282 : : double a0 ; // coning angle (rad)
283 : : double a_1, b_1, a_dw ;
284 : : double a1s, b1s ; // cyclic flapping relative to shaft axes, /SH79/ eqn(43)
285 : : double H_drag, J_side ;
286 : :
287 : : double Torque ;
288 : : double Thrust ;
289 : : double Ct ;
290 : : double lambda ; // inflow ratio
291 : : double mu ; // tip-speed ratio
292 : : double nu ; // induced inflow ratio
293 : : double v_induced ; // always positive [ft/s]
294 : :
295 : : // results
296 : : FGColumnVector3 force ;
297 : : FGColumnVector3 moment ;
298 : :
299 : :
300 : : // declare the problem function
301 : 0 : class dnuFunction : public FGRungeKuttaProblem {
302 : : public:
303 : : void update_params(rotor *r, double ct_t01, double fs, double w);
304 : : private:
305 : : double pFunc(double x, double y);
306 : : // some shortcuts
307 : : double k_sat, ct_lambda, k_wor, k_theta, mu2, k_flowscale;
308 : : } flowEquation;
309 : :
310 : :
311 : : };
312 : :
313 : :
314 : : public:
315 : : /** Constructor
316 : : @param exec pointer to executive structure
317 : : @param rotor_element pointer to XML element in the config file
318 : : @param num the number of this rotor */
319 : : FGRotor(FGFDMExec *exec, Element* rotor_element, int num);
320 : :
321 : : /// Destructor
322 : : ~FGRotor();
323 : :
324 : 0 : void SetRPM(double rpm) {RPM = rpm;}
325 : :
326 : : /** Calculates forces and moments created by the rotor(s) and updates
327 : : vFn,vMn state variables. RPM changes are handled inside, too.
328 : : The RPM change is based on estimating the torque provided by the engine.
329 : :
330 : : @param PowerAvailable here this is the thrust (not power) provided by a turbine
331 : : @return PowerAvailable */
332 : : double Calculate(double);
333 : :
334 : 0 : double GetRPM(void) const { return RPM; }
335 : : double GetDiameter(void) { return mr.Radius*2.0; }
336 : :
337 : : // Stubs. Right now this rotor-to-engine interface is just a hack.
338 : : double GetTorque(void) { return 0.0; /* return mr.Torque;*/ }
339 : : double GetPowerRequired(void);
340 : :
341 : : // Stubs. Only main rotor RPM is returned
342 : : string GetThrusterLabels(int id, string delimeter);
343 : : string GetThrusterValues(int id, string delimeter);
344 : :
345 : : private:
346 : :
347 : : bool bind(void);
348 : :
349 : : double RPM;
350 : : double Sense; // default is counter clockwise rotation of the main rotor (viewed from above)
351 : : bool tailRotorPresent;
352 : :
353 : : void Debug(int from);
354 : :
355 : : FGPropertyManager* PropertyManager;
356 : :
357 : : rotor mr;
358 : : rotor tr;
359 : :
360 : : Filter damp_hagl;
361 : :
362 : : double rho;
363 : :
364 : : double effective_tail_col; // /SH79/ eqn(47)
365 : :
366 : : double ground_effect_exp;
367 : : double ground_effect_shift;
368 : :
369 : : double hover_threshold;
370 : : double hover_scale;
371 : :
372 : : // fdm imported controls
373 : : FGPropertyManager* prop_collective_ctrl;
374 : : FGPropertyManager* prop_lateral_ctrl;
375 : : FGPropertyManager* prop_longitudinal_ctrl;
376 : : FGPropertyManager* prop_antitorque_ctrl;
377 : :
378 : : FGPropertyManager* prop_freewheel_factor;
379 : : FGPropertyManager* prop_rotorbrake;
380 : :
381 : : // fdm export ...
382 : : double prop_inflow_ratio_lambda;
383 : : double prop_advance_ratio_mu;
384 : : double prop_inflow_ratio_induced_nu;
385 : : double prop_mr_torque;
386 : : double prop_coning_angle;
387 : :
388 : : double prop_theta_downwash;
389 : : double prop_phi_downwash;
390 : :
391 : : double prop_thrust_coefficient;
392 : : double prop_lift_coefficient;
393 : :
394 : : double dt; // deltaT doesn't do the thing
395 : :
396 : : // devel/debug stuff
397 : : int prop_DumpFlag; // causes 1-time dump on stdout
398 : :
399 : : };
400 : : }
401 : : //%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
402 : : #endif
|