1 /*****************************************************************************
2  * $LastChangedDate: 2011-08-20 12:07:38 -0400 (Sat, 20 Aug 2011) $
3  * @file
4  * @author  Jim E. Brooks  http://www.palomino3d.org
5  * @brief   Physics model (Aircraft).
6  *//*
7  * LEGAL:   COPYRIGHT (C) 2007 JIM E. BROOKS
8  *          THIS SOURCE CODE IS RELEASED UNDER THE TERMS
9  *          OF THE GNU GENERAL PUBLIC LICENSE VERSION 2 (GPL 2).
10  *****************************************************************************/
11 
12 #define PHYSICS_AIRCRAFT_PHYSICS_CC 1
13 #include "base/module.hh"
14 #include "base/conf.hh"
15 #include "base/stream.hh"
16 using namespace base;
17 #include "math/module.hh"
18 #include "math/funcs_trig.hh"
19 #include "math/funcs_vector.hh"
20 using namespace math;
21 #include "object/module.hh"
22 #include "object/aircraft.hh"
23 using namespace object;
24 #include "world/module.hh"
25 using namespace world;
26 #include "physics/module.hh"
27 #include "physics/defs.hh"
28 #include "physics/conf.hh"
29 #include "physics/aircraft_specs.hh"
30 #include "physics/physics_aircraft.hh"
31 #include "physics/physics_control.hh"
32 
33 namespace physics {
34 
35 INTERN const fp AIR_BRAKES_DRAG_FACTOR   = 0.25f;  // added to drag factor
36 INTERN const fp WHEEL_BRAKES_DRAG_FACTOR = 1.00f;  // added to drag factor
37 
38 ////////////////////////////////////////////////////////////////////////////////
39 ////////////////////////////  AircraftPhysics  /////////////////////////////////
40 ////////////////////////////////////////////////////////////////////////////////
41 
42 /*****************************************************************************
43  * ctor/dtor.
44  *****************************************************************************/
AircraftPhysics(SafePtr<Aircraft> aircraft,const AircraftSpecs & specs)45 AircraftPhysics::AircraftPhysics( SafePtr<Aircraft> aircraft, const AircraftSpecs& specs )
46 :   mEnable(true),
47     mAircraft(aircraft),  // cannot be a shptr else Aircraft would have a reference to itself
48     mSpecs(specs),
49     mPrevTick(0),
50     mWorld(),
51     mThrustMag(0),
52     mBrakes(false)
53 {
54     SET_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
55     Reset();
56 }
57 
~AircraftPhysics()58 AircraftPhysics::~AircraftPhysics()
59 {
60     INVALIDATE_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
61 }
62 
63 ////////////////////////////////////////////////////////////////////////////////
64 ///////////////////  AircraftPhysics : enablement, reset  //////////////////////
65 ////////////////////////////////////////////////////////////////////////////////
66 
67 /*****************************************************************************
68  * Enable physics.
69  *****************************************************************************/
70 void
Enable(bool enable)71 AircraftPhysics::Enable( bool enable )
72 {
73 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
74 
75     mEnable = enable;  // this instance
76 }
77 
78 /*****************************************************************************
79  * If physics is enabled.
80  *****************************************************************************/
81 bool
IfEnabled(void)82 AircraftPhysics::IfEnabled( void )
83 {
84 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
85 
86     return mEnable and PhysicsControl::IfEnabled();
87 }
88 
89 /*****************************************************************************
90  * Called when Aircraft is reset.
91  *****************************************************************************/
92 void
Reset(void)93 AircraftPhysics::Reset( void )
94 {
95 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
96 
97     mPrevTick = Milliseconds(0);  // force re-measuring time segment
98     mWorld.Reset();  // reset MotionSpace
99 }
100 
101 ////////////////////////////////////////////////////////////////////////////////
102 ////////////////////  AircraftPhysics : Object animation  //////////////////////
103 ////////////////////////////////////////////////////////////////////////////////
104 
105 /*****************************************************************************
106  * Main method of physics computations.
107  *****************************************************************************/
108 void
Tick(const Milliseconds timeElapsed)109 AircraftPhysics::Tick( const Milliseconds timeElapsed )
110 {
111 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
112 
113     // Do general physics computation.
114     // Then do specific physics computation according to state of Aircraft.
115     // AnimateAircraft() returns false if no animation should be done.
116     const bool doAnimation = AnimateAircraft( timeElapsed );
117     if ( EX( doAnimation ) )
118     {
119         switch ( mAircraft->GetState() )
120         {
121             case Aircraft::eState_LANDING:
122             {
123                 AnimateAircraftLanding( timeElapsed );
124             }
125             break;
126 
127             default:
128             break;  // NOP
129         }
130     }
131 }
132 
133 /*****************************************************************************
134  * This is the core of physics computations.
135  *
136  * Move an Object in World Space according to net force vectors.
137  * Manipulates Object using Object interface.
138  * Computations are done in World Space.
139  *
140  * Note: Axises of an Object different from World (esp. up/down).
141  * Use AircraftAxis*() to produce an appropriate vector.
142  * Axises in a Aircraft's local space:
143  * X : left/right
144  * Y : up/down
145  * Z : for/backward
146  *
147  * @param   millisecElapsed
148  *          Total milliseconds between now and when program was started.
149  * @return  False if animation wasn't done (physics disabled etc).
150  *****************************************************************************/
151 bool
AnimateAircraft(const Milliseconds millisecElapsed)152 AircraftPhysics::AnimateAircraft( const Milliseconds millisecElapsed )
153 {
154 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
155 
156     // Wait until time-segment can be measured.
157     if ( mPrevTick == Milliseconds(0) )
158     {
159         mPrevTick = millisecElapsed;
160         return false;
161     }
162 
163     // NOP?
164     if ( UX( (not IfEnabled()) or mAircraft->IfCollisionFatal() ) )
165         return false;
166 
167     //..........................................................................
168     // Track time between now and the previous tick.
169 
170     const fpx timeRatio = (millisecElapsed.FPX() - mPrevTick.FPX()) / 1000.0;
171 
172     ASSERT( FP_GE(timeRatio,0.0) );  // shouldn't be negative
173   //ASSERT( timeRatio < 10.0 );      // catch large values
174     if ( UX( timeRatio > 10.0 ) )    // large values do occur on slow systems
175     {
176         CERROR << "AircraftPhysics::AnimateAircraft: timeRatio too large (slow system?)" << std::endl;
177         mPrevTick = millisecElapsed;  // erase time delay
178         return false;
179     }
180 
181     // Wait for next tick if elapsed time is too short.
182     if ( timeRatio < 0.00005 )
183         return false;
184     mPrevTick = millisecElapsed;
185 
186     //..........................................................................
187     // Pre-compute variables:
188     //
189     // SI units are in seconds but this function is called in terms of milliseconds.
190 
191           Matrix       matrix            = mAircraft->GetMatrix();
192     const SphereVertex spherePosition    = world::conv::WorldVertex2SphereVertex( mAircraft->GetPosition() );
193     const bool         ifVelocity        = IfVelocity();
194     const bool         ifForwardVelocity = IfForwardVelocity( matrix );
195     const bool         ifOnRunway        = mAircraft->IfCollisionRunway();
196     const Degree       angleOfAttack     = ComputeAngleOfAttack( ifVelocity );
197     const Speed        speed             = ComputeSpeed();
198     const SpeedKPH     speedKph          = physics::conv::Speed2KPH( speed );  // speed (any direction)
199     const SpeedKPH     speedKphWings     = speedKph;
200     Vector3            normVelocity( 0.0f, 0.0f, 0.0f );
201     try { normVelocity = Normalize( mWorld.mVelocity ); } catch(...) { }  // exception if zero velocity (ok)
202 
203     //..........................................................................
204     // Compute thrust:
205     //
206     // Magnitude of thrust is a given variable.
207     // Convert magnitude to a 3D vector.
208     // A = F / M : m/s/s = (kg*m/s/s) / kg
209 
210 ASSERT( mSpecs.mMass.FP() > 0 );
211     mWorld.mThrustForce = AircraftAxisThrust(matrix) * mThrustMag.FP();  // Vector3 * fp
212     mWorld.mThrustAccel = mWorld.mThrustForce / mSpecs.mMass.FP();
213 
214     //..........................................................................
215     // Compute drag:
216     //
217     // Drag is a function of speed, lift, AofA.
218     // Direction of drag is opposite of velocity.
219 
220     if ( EX( ifVelocity ) )
221     {
222         // Factor in drag caused by speed.
223         ASSERT( mSpecs.mMaxSpeed.FP() > 0 );
224         fp dragFactor = speed.FP() / mSpecs.mMaxSpeed.FP();
225 
226         // Factor in drag caused by angle-of-attack of wings.
227         // Let small AofA be negligible.
228         ASSERT( mSpecs.mDragAofALimit > 0 );
229         ASSERT( mSpecs.mDragAofADegree > 0 );
230         dragFactor += Min<fp>( mSpecs.mDragAofALimit, ABS(angleOfAttack) / mSpecs.mDragAofADegree );
231 
232         // Factor in drag caused by brakes.
233         // Prevent brakes causing backward movement.
234         // Wheel brakes produce stronger drag force than air brakes (flaps).
235         if ( IfBrakes() )
236         {
237             if ( ifForwardVelocity )
238             {
239                 dragFactor += IfWheelBrakes() ? WHEEL_BRAKES_DRAG_FACTOR :
240                                                 AIR_BRAKES_DRAG_FACTOR;
241             }
242             else  // stopped or moving backwards
243             {
244                 // Stop reverse movement on runway caused by brakes.
245                 // If drag was computed better, this wouldn't be needed.
246                 if ( ifOnRunway )
247                 {
248                     dragFactor = 0.0f;
249                     mWorld.mVelocity.set( 0.0f, 0.0f, 0.0f );
250                 }
251             }
252         }
253 
254         // Multiply drag factor by max thrust.
255         // At max speed, drag factor would be 1.0 to counteract max thrust.
256         ASSERT( mSpecs.mMaxThrustMag.FP() > 0 );
257         ASSERT( mSpecs.mMass.FP() > 0 );
258         const fp dragForceMag = mSpecs.mMaxThrustMag.FP() * dragFactor;
259 
260         // Compute 3D vector of drag force in opposite direction of velocity.
261         ASSERT( Distance(normVelocity) > 0.0 );
262         ASSERT( Distance(normVelocity) < 1.000001f );
263         const Vector3 normDragForceDir = -normVelocity;  // opposite direction
264         mWorld.mDragForce[XX] = normDragForceDir[XX] * dragForceMag;  // Vector3 * fp
265         mWorld.mDragForce[YY] = normDragForceDir[YY] * dragForceMag;
266         mWorld.mDragForce[ZZ] = normDragForceDir[ZZ] * dragForceMag;
267         mWorld.mDragAccel = mWorld.mDragForce / mSpecs.mMass.FP();  // A = F / M : m/s/s = (kg*m/s/s) / kg
268     }
269 
270     //..........................................................................
271     // Compute lift:
272     //
273     // Lift is a function of speed-over-wings and angle-of-attack.
274 
275     if ( EX( ifVelocity ) )
276     {
277         // Compute factor of lift from speed-over-wings.
278         ASSERT( mSpecs.mLiftoffSpeed.FP() > 0 );
279         ASSERT( mSpecs.mRangeOfLiftFactorSpeed > 0 );
280         fp liftFactorSpeed = Min( 1.5f,
281                                   ABS(speedKphWings.FP()) / mSpecs.mLiftoffSpeed.FP() );
282            liftFactorSpeed = Range( liftFactorSpeed,
283                                    -mSpecs.mRangeOfLiftFactorSpeed,
284                                     mSpecs.mRangeOfLiftFactorSpeed );
285 
286         // Compute factor of lift caused by angle-of-attack.
287         ASSERT( mSpecs.mMaxAofA > 0 );
288         ASSERT( mSpecs.mRangeOfLiftFactorAofA > 0 );
289         fp liftFactorAofA = angleOfAttack / mSpecs.mMaxAofA;
290            liftFactorAofA = Range( liftFactorAofA,
291                                   -mSpecs.mRangeOfLiftFactorAofA,
292                                    mSpecs.mRangeOfLiftFactorAofA );
293 
294         // Combine lift factors.
295         ASSERT( mSpecs.mRangeOfLiftFactor > 0 );
296         fp liftFactor = liftFactorSpeed * (1.0f + liftFactorAofA);
297            liftFactor = Range( liftFactor,
298                               -mSpecs.mRangeOfLiftFactor,
299                                mSpecs.mRangeOfLiftFactor );
300 
301         // Compute lift force and acceleration as 3D vectors.
302         const fp liftForceMag = liftFactor * (mSpecs.mMass.FP() * defs::ACCELERATION_GRAVITY_SCALAR);
303         mWorld.mLiftForce = AircraftAxisLift(matrix) * liftForceMag;   // Vector3 * fp
304         mWorld.mLiftAccel = mWorld.mLiftForce / mSpecs.mMass.FP();  // A = F / M : m/s/s = (kg*m/s/s) / kg
305     }
306 
307     //..........................................................................
308     // Compute weight:
309 
310     // Rotate force of gravity thru an "up vector" from point on world.
311     const WorldVertex gravityDir     = GET_WORLD().ComputeUpVector( spherePosition );  // normalize
312     const fp          weightForceMag = mSpecs.mMass.FP() * -defs::ACCELERATION_GRAVITY_SCALAR;
313     ASSERT( Distance(gravityDir) < 1.000001f );  // should be normalized
314     mWorld.mWeightForce = gravityDir * weightForceMag;  // Vector3 * fp
315     mWorld.mWeightAccel = mWorld.mWeightForce / mSpecs.mMass.FP();  // A = F / M : m/s/s = (kg*m/s/s) / kg
316 
317     //..........................................................................
318     // Add the net accelerations to velocity.
319 
320     mWorld.mNetAccel = mWorld.mThrustAccel
321                      + mWorld.mDragAccel
322                      + mWorld.mLiftAccel
323                      + mWorld.mWeightAccel;
324 
325     // Divide net acceleration to account for this tick being < 1 second.
326     mWorld.mNetAccel = mWorld.mNetAccel * timeRatio;
327 
328     // Add to velocity.
329     mWorld.mVelocity += mWorld.mNetAccel;
330 
331     //..........................................................................
332     // Contact force from this Aircraft being above another object.
333     //
334     // Do this after computing net acceleration but before commiting motion.
335     // A more realistic way is to compute momentum then an opposing contact force,
336     // but this simpler way of clearing vertical velocity in local,world spaces
337     // produces equivalent results.
338 
339     if ( ifOnRunway )
340     {
341         // LIMITATION/ASSUMPTION:
342         // This is limited to handling the contact force from a level runway.
343         //
344         // Cancel downward velocity and acceleration (not force which remains in effect).
345         // Downward is aligned with force of gravity.
346         // If downward velocity is too high, indicate crash.
347         if ( IfDownwardVelocity() )
348         {
349             const SpeedKPH downwardSpeedKPH( physics::conv::Speed2KPH(Speed(ABS(mWorld.mVelocity[ALT]))) );
350 
351             mWorld.mVelocity[ALT] = 0.0f;
352             mWorld.mNetAccel[ALT] = 0.0f;
353 
354             // At this point, velocity is definitely downward (IfDownwardVelocity() was true).
355             // Ignore if aircraft is parked.
356             if ( mAircraft->GetState() != Aircraft::eState_PARKED
357              and downwardSpeedKPH > PHYSICS_CONF.mMaxLandingSpeedVertical )
358             {
359                 mAircraft->SetCollision( Object::COLLISION_FATAL );
360             }
361         }
362     }
363 
364     //..........................................................................
365     // Commit change in motion.
366     //
367     // Velocity is in meters/second.
368     // Convert meters to simulation distance.
369     // And convert seconds to simulation time (elapsed ticks).
370 
371     if ( EX( physics::conv::Speed2KPH(ComputeSpeed()) > SpeedKPH(SPEED_KPH_MINIMAL) ) )
372     {
373         Vector3 velocitySim( world::conv::Meters2Sim(Meter(mWorld.mVelocity[XX])) * timeRatio,
374                              world::conv::Meters2Sim(Meter(mWorld.mVelocity[YY])) * timeRatio,
375                              world::conv::Meters2Sim(Meter(mWorld.mVelocity[ZZ])) * timeRatio );
376         // Appy simulation speed (-speed arg).
377         const fp simulationSpeed = PhysicsControl::GetSimulationSpeed();
378         matrix[Ox] += velocitySim[XX] * simulationSpeed;
379         matrix[Oy] += velocitySim[YY] * simulationSpeed;
380         matrix[Oz] += velocitySim[ZZ] * simulationSpeed;
381         mAircraft->SetMatrix( matrix, Aircraft::TRANSLATION );  // SetMatrix() called for translation
382     }
383     else
384     {
385         // Speed is extremely low.  For numerical stability, zero all forces/accelerations.
386         mWorld.Reset();
387     }
388 
389     return true;
390 }
391 
392 /*****************************************************************************
393  * Gradually cause a pitch up/down rotation while a Aircraft is landing.
394  *
395  * @param   millisecElapsed
396  *          Total milliseconds between now and when program was started.
397  * @return  False if animation wasn't done (physics disabled etc).
398  *****************************************************************************/
399 bool
AnimateAircraftLanding(const Milliseconds millisecElapsed)400 AircraftPhysics::AnimateAircraftLanding( const Milliseconds millisecElapsed )
401 {
402 // TODO
403     return true;
404 }
405 
406 ////////////////////////////////////////////////////////////////////////////////
407 /////////////////////////  AircraftPhysics : speed  ////////////////////////////
408 ////////////////////////////////////////////////////////////////////////////////
409 
410 /*****************************************************************************
411  * Set speed.
412  *****************************************************************************/
413 void
SetSpeed(const Speed speed)414 AircraftPhysics::SetSpeed( const Speed speed )
415 {
416 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
417 
418     // Velocity is [Speed,Speed,Speed].  Speed is meter/sec.
419     mWorld.mVelocity = AircraftAxisThrust(mAircraft->GetMatrix()) * speed.FP();  // Vector3 * fp
420 }
421 
422 /*****************************************************************************
423  * Compute speed.
424  *****************************************************************************/
425 Speed
ComputeSpeed(void)426 AircraftPhysics::ComputeSpeed( void )
427 {
428 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
429 
430     // Velocity is [Speed,Speed,Speed].  Speed is meter/sec.
431     return Speed( Distance( mWorld.mVelocity ) );  // convert to scalar (magnitude)
432 }
433 
434 /*****************************************************************************
435  * Compute maximum speed of aircraft at current altitude.
436  *****************************************************************************/
437 Speed
ComputeMaxSpeed(void)438 AircraftPhysics::ComputeMaxSpeed( void )
439 {
440 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
441 
442     // Altitude should be a factor (unimplemented).
443     ASSERT( mSpecs.mMaxSpeed.FP() > 0 );
444     return physics::conv::KPH2Speed( mSpecs.mMaxSpeed );
445 }
446 
447 /*****************************************************************************
448  * @return If Aircraft is moving.
449  *****************************************************************************/
450 bool
IfVelocity(void)451 AircraftPhysics::IfVelocity( void )
452 {
453 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
454 
455     const fp speed = Distance(mWorld.mVelocity);
456     return physics::conv::Speed2KPH(Speed(speed)) > SPEED_KPH_MINIMAL;
457 }
458 
459 /*****************************************************************************
460  * @return If Aircraft is moving forward.
461  *****************************************************************************/
462 bool
IfForwardVelocity(const Matrix & aircraftMatrix)463 AircraftPhysics::IfForwardVelocity( const Matrix& aircraftMatrix )
464 {
465 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
466 
467     if ( IfVelocity() )
468     {
469         // In world space, compute angle between aircraft's thrust vector
470         // and aircraft's velocity.
471         return DotProduct3( AircraftAxisThrust(aircraftMatrix), mWorld.mVelocity ) > 0.0f;
472     }
473     else
474     {
475         // Isn't moving.
476         return false;
477     }
478 }
479 
480 /*****************************************************************************
481  * @return If Aircraft is moving downward.
482  *****************************************************************************/
483 bool
IfDownwardVelocity(void)484 AircraftPhysics::IfDownwardVelocity( void )
485 {
486 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
487 
488     return GET_WORLD().IfDownward( mWorld.mVelocity[ALT] );
489 }
490 
491 ////////////////////////////////////////////////////////////////////////////////
492 ///////////////////////  AircraftPhysics : thrust  /////////////////////////////
493 ////////////////////////////////////////////////////////////////////////////////
494 
495 /*****************************************************************************
496  * Set current thrust (magnitude).
497  *****************************************************************************/
498 void
SetThrust(const Newton1 thrustMag)499 AircraftPhysics::SetThrust( const Newton1 thrustMag )
500 {
501 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
502 
503     mThrustMag = thrustMag;
504 }
505 
506 ////////////////////////////////////////////////////////////////////////////////
507 /////////////////////////  AircraftPhysics : drag  /////////////////////////////
508 ////////////////////////////////////////////////////////////////////////////////
509 
510 /*****************************************************************************
511  * @return True if wheel brakes.
512  *****************************************************************************/
513 bool
IfWheelBrakes(void)514 AircraftPhysics::IfWheelBrakes( void )
515 {
516 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
517 
518     // Cannot be inline because of Aircraft class is forward-declared.
519     return mBrakes and mAircraft->IfCollisionRunway();
520 }
521 
522 ////////////////////////////////////////////////////////////////////////////////
523 /////////////////  AircraftPhysics : fundamental forces  ///////////////////////
524 ////////////////////////////////////////////////////////////////////////////////
525 
526 /*****************************************************************************
527  * Return a normalized vector of an Aircraft's matrix.
528  * Vector3 is produced from matrix elements in transposed order (vertical).
529  * Normalized in case matrix is scaled.
530  * Drag and weight are omitted since they aren't aligned with a aircraft.
531  *****************************************************************************/
532 Vector3
AircraftAxisThrust(const Matrix & m)533 AircraftPhysics::AircraftAxisThrust( const Matrix& m )
534 {
535     return Normalize<Vector3,fp>( m[Xz], m[Yz], m[Zz] ) * fp(THRUST_DIR);
536 }
537 
538 Vector3
AircraftAxisLift(const Matrix & m)539 AircraftPhysics::AircraftAxisLift( const Matrix& m )
540 {
541     return Normalize<Vector3,fp>( m[Xy], m[Yy], m[Zy] ) * fp(LIFT_DIR);
542 }
543 
544 ////////////////////////////////////////////////////////////////////////////////
545 ///////////////////  AircraftPhysics : angle-of-attack  ////////////////////////
546 ////////////////////////////////////////////////////////////////////////////////
547 
548 /*****************************************************************************
549  * @return Angle-of-attack of wings.
550  *****************************************************************************/
551 Degree
ComputeAngleOfAttack(const bool ifVelocity)552 AircraftPhysics::ComputeAngleOfAttack( const bool ifVelocity )
553 {
554 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
555 
556     // If velocity vector is zero, angle is undefined (return zero).
557     if ( EX( ifVelocity ) )
558     {
559         // Compute angle between Aircraft's Y axis and velocity.
560         // If AoA is 0 then this angle will be 90 degrees so subtract 90 degrees.
561         const Matrix m = mAircraft->GetMatrix();
562         const Vector3 axis_y( m[Xy], m[Yy], m[Zy] );
563         Radian rad = Angle3( axis_y, Vector3(mWorld.mVelocity) );
564         return Rad2Deg( rad - math::RADIAN_90 );
565     }
566     else
567     {
568         return Degree(0.0f);
569     }
570 }
571 
572 /*****************************************************************************
573  * When aircraft is moving slowly, control surfaces barely work.
574  * Known deficiency:
575  * Airspeed's direction, not just magnitude, should be a factor.
576  *****************************************************************************/
577 fp
ComputeRotationFactor(void)578 AircraftPhysics::ComputeRotationFactor( void )
579 {
580 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
581 
582     SpeedKPH speed     = physics::conv::Speed2KPH( ComputeSpeed() );
583     SpeedKPH speedLow  = SpeedKPH(0);
584     SpeedKPH speedHigh = SpeedKPH(60);
585 ASSERT( speedLow < speedHigh );
586 
587     if ( speed < SpeedKPH(10) )
588     {
589         return 0.0f;  // below formula may produce NaN if speed=0
590     }
591     else if ( speed >= speedHigh )
592     {
593         return 1.0f;
594     }
595     else
596     {
597         // Limit rotation until at a range near the stall/liftoff speed.
598         // Allow minimal rotation even at very low speeds.
599         // No rotation if aircraft is in contact with runway.
600         fp rotationFactor = FractionInRange( speed.FP(), speedLow.FP(), speedHigh.FP() );
601         return rotationFactor;
602     }
603 }
604 
605 /*****************************************************************************
606  * Compute rate of roll,pitch,yaw.
607  * Rate is affected by speed.
608  *****************************************************************************/
609 Degree
ComputeRollRate(void)610 AircraftPhysics::ComputeRollRate( void )
611 {
612 ASSERT( mSpecs.mRollRate > 0 );
613 
614     return mSpecs.mRollRate * ComputeRotationFactor();
615 }
616 
617 Degree
ComputePitchRate(void)618 AircraftPhysics::ComputePitchRate( void )
619 {
620 ASSERT( mSpecs.mPitchRate > 0 );
621 
622     return mSpecs.mPitchRate * ComputeRotationFactor();
623 }
624 
625 Degree
ComputeYawRate(void)626 AircraftPhysics::ComputeYawRate( void )
627 {
628 ASSERT( mSpecs.mYawRate > 0 );
629 
630     return mSpecs.mYawRate * ComputeRotationFactor();
631 }
632 
633 ////////////////////////////////////////////////////////////////////////////////
634 ////////////////////////  AircraftPhysics : turning  ///////////////////////////
635 ////////////////////////////////////////////////////////////////////////////////
636 
637 /*****************************************************************************
638  * Determine if the user seems to be doing a normal banked turn.
639  * @returns { eNotTurning, eTurningLeft, eTurningRight }
640  *****************************************************************************/
641 AircraftPhysics::eTurning
ComputeTurningDir(void)642 AircraftPhysics::ComputeTurningDir( void )
643 {
644 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
645 
646     // Determine whether turning left or right by computing the 1D angle
647     // between Y coordinate (Z coordinate in world) of the local X axis and (0,1,0).
648     const Matrix m = mAircraft->GetMatrix();
649     const Degree deg = Rad2Deg( Radian( std::acos( m[Zx] ) ) ) - 90.0f;
650 ASSERT( mSpecs.mTurnDegreeLow > 0.0f );
651 ASSERT( mSpecs.mTurnDegreeHigh > 0.0f );
652     if ( (ABS(deg) >= mSpecs.mTurnDegreeLow)
653      and (ABS(deg) <= mSpecs.mTurnDegreeHigh) )
654     {
655         return deg < 0.0f ? eTurningLeft : eTurningRight;
656     }
657     else
658     {
659         return eNotTurning;
660     }
661 }
662 
663 /*****************************************************************************
664  * @return True if the player seems to be doing a banked turn.
665  *****************************************************************************/
666 bool
IfTurning(void)667 AircraftPhysics::IfTurning( void )
668 {
669 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
670 
671     const eTurning turning = ComputeTurningDir();
672     return (turning == eTurningLeft)
673         or (turning == eTurningRight);
674 }
675 
676 ////////////////////////////////////////////////////////////////////////////////
677 ///////////////////////  AircraftPhysics : stalling  ///////////////////////////
678 ////////////////////////////////////////////////////////////////////////////////
679 
680 /*****************************************************************************
681  * @return True if stalling.
682  *****************************************************************************/
683 bool
IfStall(void)684 AircraftPhysics::IfStall( void )
685 {
686 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
687 ASSERT( mSpecs.mMaxAofA > Degree(0) );
688 
689     // Don't stall if physics is disabled or aircraft is sitting on runway.
690     if ( PhysicsControl::IfStallEnabled()
691      and IfEnabled()
692      and not mAircraft->IfCollisionRunway() )
693     {
694         const Degree aoa = ComputeAngleOfAttack();
695         return ABS(aoa) > mSpecs.mMaxAofA;
696     }
697     else
698     {
699         return false;
700     }
701 }
702 
703 /*****************************************************************************
704  * Compute fraction indicating the amount of stalling.
705  * Might return > 1.0 for severe stall.
706  *****************************************************************************/
707 fp
ComputeStall(void)708 AircraftPhysics::ComputeStall( void )
709 {
710 CHECK_TYPESIG(this,TYPESIG_AIRCRAFT_PHYSICS);
711 ASSERT( mSpecs.mMaxAofA > Degree(0) );
712 
713     return ABS(ComputeAngleOfAttack()) / mSpecs.mMaxAofA;
714 }
715 
716 ////////////////////////////////////////////////////////////////////////////////
717 //////////////////////  AircraftPhysics::MotionSpace  //////////////////////////
718 ////////////////////////////////////////////////////////////////////////////////
719 
720 /*****************************************************************************
721  * ctor/dtor
722  *****************************************************************************/
MotionSpace(void)723 AircraftPhysics::MotionSpace::MotionSpace( void )
724 {
725     Reset();
726 }
727 
728 void
Reset(void)729 AircraftPhysics::MotionSpace::Reset( void )
730 {
731     mThrustForce.set(0.0f,0.0f,0.0f);
732     mThrustAccel.set(0.0f,0.0f,0.0f);
733 
734     mDragForce.set(0.0f,0.0f,0.0f);
735     mDragAccel.set(0.0f,0.0f,0.0f);
736 
737     mLiftForce.set(0.0f,0.0f,0.0f);
738     mLiftAccel.set(0.0f,0.0f,0.0f);
739 
740     mWeightForce.set(0.0f,0.0f,0.0f);
741     mWeightAccel.set(0.0f,0.0f,0.0f);
742 
743     mNetAccel.set(0.0f,0.0f,0.0f);
744 
745     mVelocity.set(0.0f,0.0f,0.0f);
746 }
747 
748 } // namespace physics
749